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
00036
00037
00038
00039 #ifndef OPENNI_CAMERA_DRIVER_H
00040 #define OPENNI_CAMERA_DRIVER_H
00041
00042
00043 #include <ros/ros.h>
00044 #include <nodelet/nodelet.h>
00045 #include <image_transport/image_transport.h>
00046 #include <boost/thread.hpp>
00047
00048
00049 #include <camera_info_manager/camera_info_manager.h>
00050 #include <dynamic_reconfigure/server.h>
00051 #include <freenect_camera/FreenectConfig.h>
00052
00053
00054 #include <freenect_camera/freenect_driver.hpp>
00055
00056
00057 #include <diagnostic_updater/diagnostic_updater.h>
00058 #include <diagnostic_updater/publisher.h>
00059
00060 namespace freenect_camera
00061 {
00063 class DriverNodelet : public nodelet::Nodelet
00064 {
00065 public:
00066 virtual ~DriverNodelet ();
00067 private:
00068 typedef FreenectConfig Config;
00069 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00070 typedef diagnostic_updater::FrequencyStatusParam FrequencyStatusParam;
00071 typedef diagnostic_updater::HeaderlessTopicDiagnostic TopicDiagnostic;
00072 typedef boost::shared_ptr<TopicDiagnostic> TopicDiagnosticPtr;
00073
00075 virtual void onInit ();
00076 void onInitImpl ();
00077 void setupDevice ();
00078 void updateModeMaps ();
00079 void startSynchronization ();
00080 void stopSynchronization ();
00081
00083 int mapMode2ConfigMode (const OutputMode& output_mode) const;
00084 OutputMode mapConfigMode2OutputMode (int mode) const;
00085
00086
00087 void rgbCb(const ImageBuffer& image, void* cookie);
00088 void depthCb(const ImageBuffer& depth_image, void* cookie);
00089 void irCb(const ImageBuffer&_image, void* cookie);
00090 void configCb(Config &config, uint32_t level);
00091
00092 void rgbConnectCb();
00093 void depthConnectCb();
00094 void irConnectCb();
00095
00096
00097 sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const;
00098 sensor_msgs::CameraInfoPtr getRgbCameraInfo(const ImageBuffer& image, ros::Time time) const;
00099 sensor_msgs::CameraInfoPtr getIrCameraInfo(const ImageBuffer& image, ros::Time time) const;
00100 sensor_msgs::CameraInfoPtr getDepthCameraInfo(const ImageBuffer& image, ros::Time time) const;
00101 sensor_msgs::CameraInfoPtr getProjectorCameraInfo(const ImageBuffer& image, ros::Time time) const;
00102
00103
00104 image_transport::CameraPublisher pub_rgb_;
00105 image_transport::CameraPublisher pub_depth_, pub_depth_registered_;
00106 image_transport::CameraPublisher pub_ir_;
00107 ros::Publisher pub_projector_info_;
00108
00109
00110 boost::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;
00111 double pub_freq_max_, pub_freq_min_;
00112 TopicDiagnosticPtr pub_rgb_freq_;
00113 bool enable_rgb_diagnostics_;
00114 TopicDiagnosticPtr pub_depth_freq_;
00115 bool enable_depth_diagnostics_;
00116 TopicDiagnosticPtr pub_ir_freq_;
00117 bool enable_ir_diagnostics_;
00118 boost::thread diagnostics_thread_;
00119 void updateDiagnostics();
00120 bool close_diagnostics_;
00121
00122
00123 void publishRgbImage(const ImageBuffer& image, ros::Time time) const;
00124 void publishDepthImage(const ImageBuffer& depth, ros::Time time) const;
00125 void publishIrImage(const ImageBuffer& ir, ros::Time time) const;
00126
00128 boost::shared_ptr<FreenectDevice> device_;
00129 boost::thread init_thread_;
00130 boost::mutex connect_mutex_;
00131
00133 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00134 Config config_;
00135
00137 boost::shared_ptr<camera_info_manager::CameraInfoManager> rgb_info_manager_, ir_info_manager_;
00138 std::string rgb_frame_id_;
00139 std::string depth_frame_id_;
00140 double depth_ir_offset_x_;
00141 double depth_ir_offset_y_;
00142 int z_offset_mm_;
00143
00144
00145 boost::mutex counter_mutex_;
00146 int rgb_frame_counter_;
00147 int depth_frame_counter_;
00148 int ir_frame_counter_;
00149 bool publish_rgb_;
00150 bool publish_ir_;
00151 bool publish_depth_;
00152 void checkFrameCounters();
00153
00154 void watchDog(const ros::TimerEvent& event);
00155
00157 double time_out_;
00158 ros::Time rgb_time_stamp_;
00159 ros::Time depth_time_stamp_;
00160 ros::Time ir_time_stamp_;
00161 ros::Time time_stamp_;
00162 ros::Timer watch_dog_timer_;
00163
00165 bool libfreenect_debug_;
00166
00167 std::map<OutputMode, int> mode2config_map_;
00168 std::map<int, OutputMode> config2mode_map_;
00169 };
00170 }
00171
00172 #endif
freenect_camera
Author(s): Patrick Mihelich, Suat Gedikli, Radu Bogdan Rusu (original openni_camera driver)., Piyush Khandelwal (libfreenect port).
autogenerated on Fri Aug 28 2015 10:41:49