GeneralVirtualCamera.hpp
Go to the documentation of this file.
00001 #ifndef VIRTUALPINHOLECAMERA_HPP_
00002 #define VIRTUALPINHOLECAMERA_HPP_
00003 
00004 
00005 #include <angles/angles.h>
00006 #include <list>
00007 #include <math.h>
00008 #include <tf/transform_broadcaster.h>
00009 #include <sensor_msgs/CameraInfo.h>
00010 #include <opencv2/core/core.hpp>
00011 #include <cv_bridge/cv_bridge.h>
00012 
00013 #include "common_defs.hpp"
00014 #include "inner_components/InterpolatingImageComposer.hpp"
00015 #include "inner_components/PinholeCameraModel.hpp"
00016 #include "inner_components/BasicCylinderCameraModel.hpp"
00017 #include "inner_components/SphericalCameraModel.hpp"
00018 #include "VirtualCamera.hpp"
00019 
00020 
00021 namespace virtual_camera {
00022 
00023 
00030 class GeneralVirtualCamera: public VirtualCamera {
00031 private:
00032         boost::array<double, 9> Rci, Rci0;
00033         boost::array<double, 9> Kci, Kci0;
00034         boost::array<double, 12> Pci, Pci0;
00035         std::vector<double> Dci;
00036         bool isValidCameraInfo;
00037         tf::TransformBroadcaster broadcaster;
00038         tf::Transform transform;
00039         ImageComposerPtr composer;
00040         CameraModelPtr model;
00041         TableV3Ptr pointCloud;
00042         RealCameraPtrListPtr realCameras;
00043         VirtualCameraParametersPtr parameters;
00044         std::string name;
00046         double hFovRad;
00048         double vFovRad;
00049         int seqId;
00051         bool composerCacheFlag;
00053         bool updatePointCloudFlag;
00054 
00055         void updateExternalParameters(const VirtualCameraParametersPtr & params);
00056         void updateInternalParameters(const VirtualCameraParametersPtr & params);
00057         void updateCameraModel(const std::string & indentifier);
00058         cv_bridge::CvImagePtr createEmptyImage();
00059         void updateCachesIfNeeded();
00060         void broadcast();
00061         void updateCameraInfo();
00062 
00063 public:
00064 
00065 
00071         GeneralVirtualCamera(const std::string & name,
00072                         const VirtualCameraParametersPtr &  params);
00073 
00074         sensor_msgs::CameraInfoConstPtr getCameraInfo();
00075         sensor_msgs::ImageConstPtr generateImage();
00076         bool addRealCamera(const RealCameraPtr & realCamera);
00077         bool removeRealCamera(const RealCameraPtr & realCamera);
00078         void updateVirtualCameraParameters(const VirtualCameraParametersPtr & params);
00079         double getFrameRate();
00080         std::string getName();
00081 
00082 };
00083 
00084 
00085 }
00086 
00087 #endif /* VIRTUALPINHOLECAMERA_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Defines


virtual_camera
Author(s): Jan Brabec; maintained by Tomas Petricek / petrito1@cmp.felk.cvut
autogenerated on Tue Dec 10 2013 14:58:11