Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "Sensor.h"
00031 #include "XMLTag.h"
00032
00033 #include <ros/ros.h>
00034 #include <ros/node_handle.h>
00035 #include <sensor_msgs/Image.h>
00036 #include "IplImageReading.h"
00037
00038 #define XML_NODE_IMAGESUBSCRIPTION "ImageSubscription"
00039 #define XML_PROPERTY_TOPIC "TopicName"
00040 #define XML_ATTRIBUTE_FOCAL_LENGTH "focal_length"
00041 #define XML_ATTRIBUTE_PIX_SIZE_X "pix_size_x"
00042 #define XML_ATTRIBUTE_PIX_SIZE_Y "pix_size_y"
00043 #define XML_ATTRIBUTE_PROJ_CENTER_X "proj_center_x"
00044 #define XML_ATTRIBUTE_PROJ_CENTER_Y "proj_center_y"
00045
00046 namespace sensor_msgs
00047 {
00048 class CvBridge;
00049 }
00050
00051 namespace cop
00052 {
00053
00054 class ImageSubscription : public Sensor
00055 {
00056 public:
00057 ImageSubscription() :
00058 m_bWindowCreated(false),
00059 m_grabbing(false)
00060 {
00061
00062 }
00063
00064 ~ImageSubscription(){Stop();}
00065 std::string GetWindowName();
00069 std::string GetName() const{return XML_NODE_IMAGESUBSCRIPTION;};
00075 void Show(const long frame);
00081 Reading* GetReading(const long &Frame);
00082
00088 bool CanSee(RelPose &pose) const;
00089
00090 void CallBack(const sensor_msgs::ImageConstPtr& msg_ptr);
00091
00096 bool Start()
00097 {
00098 printf("Start subscribing topic %s \n", m_stTopicName.c_str());
00099 ros::NodeHandle nh;
00100 printf("Subscribe to topic %s \n", m_stTopicName.c_str());
00101 m_imageSub = nh.subscribe (m_stTopicName, 1, &ImageSubscription::CallBack, this);
00102 m_grabbing = true;
00103 return true;
00104 }
00109 bool Stop()
00110 {
00111 m_grabbing = false;
00112 m_imageSub.shutdown();
00113 return true;
00114
00115 }
00119
00120
00121 XMLTag* Save()
00122 {
00123 XMLTag* tag = new XMLTag(GetName());
00124 Sensor::SaveTo(tag);
00125 tag->AddProperty(XML_PROPERTY_TOPIC, m_stTopicName);
00126 tag->AddProperty(XML_ATTRIBUTE_FOCAL_LENGTH, m_calib.focal_length);
00127 tag->AddProperty(XML_ATTRIBUTE_PIX_SIZE_X, m_calib.pix_size_x);
00128 tag->AddProperty(XML_ATTRIBUTE_PIX_SIZE_Y, m_calib.pix_size_y);
00129 tag->AddProperty(XML_ATTRIBUTE_PROJ_CENTER_X, m_calib.proj_center_x);
00130 tag->AddProperty(XML_ATTRIBUTE_PROJ_CENTER_Y, m_calib.proj_center_y);
00131 return tag;
00132 }
00136 bool IsCamera() const {return true;}
00140 MinimalCalibration m_calib;
00141 std::pair< std::string, std::vector<double> > GetUnformatedCalibrationValues()
00142 {
00143 std::vector<double> vec;
00144 vec.push_back(m_calib.focal_length);
00145 vec.push_back(m_calib.pix_size_x);
00146 vec.push_back(m_calib.pix_size_y);
00147 vec.push_back(m_calib.proj_center_x);
00148 vec.push_back(m_calib.proj_center_y);
00149
00150 return std::pair< std::string, std::vector<double> >("RECTHALCONCALIB", vec);
00151 }
00152 protected:
00156 void SetData(XMLTag* tag);
00157
00158 private:
00159 std::string m_stTopicName;
00160 sensor_msgs::CvBridge *m_bridge;
00161 unsigned int m_max_cameraImagesStored;
00162 ros::Subscriber m_imageSub;
00163 bool m_bWindowCreated;
00164 bool m_grabbing;
00165 };
00166 }