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
00031
00032
00033
00034
00035 #include <image_transport/image_transport.h>
00036 #include <image_transport/camera_publisher.h>
00037 #include <sensor_msgs/fill_image.h>
00038 #include <sensor_msgs/Image.h>
00039 #include <sensor_msgs/CameraInfo.h>
00040 #include <sensor_msgs/SetCameraInfo.h>
00041
00042 #include <dynamic_reconfigure/server.h>
00043 #include <vrmagic_multi_driver/CamParamsConfig.h>
00044
00045 #include <boost/thread.hpp>
00046
00047 #include <vrmagic_devkit_wrapper/vrmusbcam2.h>
00048
00049 class PropertyCache;
00050
00051 class VRMagicStereoNode
00052 {
00053 private:
00054 bool calibrated;
00055 unsigned int framesDelivered;
00056 unsigned int width, height;
00057 ros::NodeHandle leftNs, rightNs, thisNode;
00058 image_transport::CameraPublisher camPubLeft, camPubRight;
00059 sensor_msgs::CameraInfo leftCalib, rightCalib;
00060 ros::ServiceServer leftCalibUpdate, rightCalibUpdate;
00061
00062 dynamic_reconfigure::Server<vrmagic_multi_driver::CamParamsConfig> dConfServer;
00063 ros::Rate fpsLimit;
00064 VRmUsbCamDevice device;
00065 PropertyCache *props;
00066 boost::mutex camAccess, calibAccess, timerAccess;
00067 sensor_msgs::Image imgLeft;
00068 sensor_msgs::Image imgRight;
00069 const std::string frame_id;
00070
00071 void propertyUpdate(vrmagic_multi_driver::CamParamsConfig &config, uint32_t level);
00072
00073 bool runUpdateLeft(sensor_msgs::SetCameraInfo::Request &req,
00074 sensor_msgs::SetCameraInfo::Response &res);
00075
00076 bool runUpdateRight(sensor_msgs::SetCameraInfo::Request &req,
00077 sensor_msgs::SetCameraInfo::Response &res);
00078
00079 void storeCalibration();
00080 void loadCalibration();
00081 void AnnounceTopics();
00082 void AbandonTopics();
00083 void broadcastFrame();
00084 void grabFrame(VRmDWORD port, sensor_msgs::Image &img, const ros::Time &triggerTime);
00085 void initCam(VRmDWORD camDesired);
00086 void initProperties();
00087
00088 public:
00089 VRMagicStereoNode(VRmDWORD camDesired);
00090 ~VRMagicStereoNode();
00091 void spin();
00092 void retireCam();
00093
00094 };