VirtualCameraNodelet.hpp
Go to the documentation of this file.
00001 
00002 #ifndef VIRTUALCAMERANODELET_HPP_
00003 #define VIRTUALCAMERANODELET_HPP_
00004 
00005 #define BOOST_DISABLE_ASSERTS
00006 
00007 #include <ros/ros.h>
00008 #include <string>
00009 #include <vector>
00010 #include <list>
00011 #include <nodelet/nodelet.h>
00012 #include <image_transport/image_transport.h>
00013 #include <sensor_msgs/image_encodings.h>
00014 #include <sensor_msgs/CameraInfo.h>
00015 #include <opencv2/core/core.hpp>
00016 #include <opencv2/highgui/highgui.hpp>
00017 #include <cv_bridge/CvBridge.h>
00018 #include <cv_bridge/cv_bridge.h>
00019 #include <pluginlib/class_list_macros.h>
00020 #include <tf/transform_listener.h>
00021 #include <boost/lexical_cast.hpp>
00022 #include <boost/thread/mutex.hpp>
00023 #include "virtual_camera/VirtualCameraParameters.h"
00024 #include "virtual_camera/AddRealCamera.h"
00025 #include "VirtualCamera.hpp"
00026 #include "GeneralVirtualCamera.hpp"
00027 #include "RealCamera.hpp"
00028 #include "RealMonoCamera.hpp"
00029 #include "RealCameraSynchronizer.hpp"
00030 
00031 namespace virtual_camera {
00032 
00067 class VirtualCameraNodelet : public nodelet::Nodelet {
00068 private:
00069         ros::NodeHandle nh;
00070         boost::shared_ptr<image_transport::ImageTransport> it;
00071         std::string name;
00072         VirtualCameraPtr camera;
00073         ros::Publisher cameraInfoPublisher;
00074         ros::Timer timer;
00075         ros::Subscriber virtCamParamsSubscriber;
00076         ros::Subscriber addCameraSubscriber;
00077         std::vector<ros::Subscriber> realCamInfoSubs;
00078         RealCameraSynchronizerPtr synchronizer;
00079         MutexPtr imageSyncMutex;
00080         boost::shared_ptr<tf::TransformListener> transformListener;
00081 
00086         std::list<RealCameraPtr> addWaitList;
00087 
00093          VirtualCameraParametersPtr handleStartupParameters();
00094 
00100          void handleNewCameraParams(const VirtualCameraParametersPtr & params);
00101 
00102 
00106          void addRealCamerasFromParams();
00107 
00108 
00113          void registerCamerasFromWaitList();
00114 
00115 
00121          std::string getNameFromTopic(const std::string & topic);
00122 
00123 
00124 
00125 public:
00130         void loop(const ros::TimerEvent& event);
00131 
00132 
00139         void newCameraCallback(AddRealCameraConstPtr cam);
00140 
00141 
00145         virtual void onInit();
00146 
00147 };
00148 
00149 
00150 }//END OF NAMESPACE
00151 
00152 PLUGINLIB_DECLARE_CLASS(virtual_camera, VirtualCameraNodelet,
00153                 virtual_camera::VirtualCameraNodelet, nodelet::Nodelet);
00154 
00155 #endif
00156 
00157 
00158 
 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