00001 #ifndef REALMONOCAMERA_HPP_ 00002 #define REALMONOCAMERA_HPP_ 00003 00004 #include <tf/transform_listener.h> 00005 #include <algorithm> 00006 #include "RealCamera.hpp" 00007 00008 namespace virtual_camera { 00009 00016 class RealMonoCamera: public RealCamera { 00017 private: 00018 std::string name; 00019 tf::Matrix3x3 kMat; 00020 tf::StampedTransform usedTransform; 00021 TableV3Ptr requestPoints; 00026 TableP2Ptr positionCache; 00027 std::string requestFrame; 00028 sensor_msgs::CameraInfoConstPtr camInfo; 00029 sensor_msgs::ImageConstPtr image; 00030 boost::shared_ptr<tf::TransformListener> transformListener; 00031 00032 00037 void buildInnerCache(); 00038 00039 00047 void mapPointToInnerCache(int row, int col, tf::StampedTransform & transform); 00048 00049 00055 void applyPlumbBobDistortion(tf::Vector3 & p); 00056 00057 00061 bool areTransformsEqual(const tf::StampedTransform & t1, const tf::StampedTransform & t2); 00062 public: 00070 RealMonoCamera(std::string name, 00071 const boost::shared_ptr<tf::TransformListener> & listener); 00072 00073 bool isReady(); 00074 sensor_msgs::CameraInfoConstPtr getCameraInfo(); 00075 void setCameraInfo(const sensor_msgs::CameraInfoConstPtr & camInfo); 00076 void updateImage(const sensor_msgs::ImageConstPtr & image); 00077 void setPointsCache(std::string frame, const TableV3Ptr & points); 00078 TableP2ConstPtr getCachedPositions(); 00079 virtual sensor_msgs::ImageConstPtr getImage(); 00080 bool validateCache(); 00081 std::string getName(); 00082 float getWeight(int row, int col); 00083 }; 00084 00085 00086 } 00087 00088 00089 #endif /* REALMONOCAMERA_HPP_ */