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 #ifndef OPENNI2_DRIVER_H
00033 #define OPENNI2_DRIVER_H
00034
00035 #include <boost/shared_ptr.hpp>
00036 #include <boost/cstdint.hpp>
00037 #include <boost/bind.hpp>
00038 #include <boost/function.hpp>
00039
00040 #include <sensor_msgs/Image.h>
00041
00042 #include <dynamic_reconfigure/server.h>
00043 #include <openni2_camera/OpenNI2Config.h>
00044
00045 #include <image_transport/image_transport.h>
00046 #include <camera_info_manager/camera_info_manager.h>
00047
00048 #include <string>
00049 #include <vector>
00050
00051 #include "openni2_camera/openni2_device_manager.h"
00052 #include "openni2_camera/openni2_device.h"
00053 #include "openni2_camera/openni2_video_mode.h"
00054
00055 #include <ros/ros.h>
00056
00057 namespace openni2_wrapper
00058 {
00059
00060 class OpenNI2Driver
00061 {
00062 public:
00063 OpenNI2Driver(ros::NodeHandle& n, ros::NodeHandle& pnh) ;
00064
00065 private:
00066 typedef openni2_camera::OpenNI2Config Config;
00067 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00068
00069 void newIRFrameCallback(sensor_msgs::ImagePtr image);
00070 void newColorFrameCallback(sensor_msgs::ImagePtr image);
00071 void newDepthFrameCallback(sensor_msgs::ImagePtr image);
00072
00073
00074 sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const;
00075 sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const;
00076 sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const;
00077 sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const;
00078
00079 void readConfigFromParameterServer();
00080
00081
00082 std::string resolveDeviceURI(const std::string& device_id) throw(OpenNI2Exception);
00083 void initDevice();
00084
00085 void advertiseROSTopics();
00086
00087 void colorConnectCb();
00088 void depthConnectCb();
00089 void irConnectCb();
00090
00091 void configCb(Config &config, uint32_t level);
00092
00093 void applyConfigToOpenNIDevice();
00094
00095 void genVideoModeTableMap();
00096 int lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode& video_mode);
00097
00098 sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image);
00099
00100 void setIRVideoMode(const OpenNI2VideoMode& ir_video_mode);
00101 void setColorVideoMode(const OpenNI2VideoMode& color_video_mode);
00102 void setDepthVideoMode(const OpenNI2VideoMode& depth_video_mode);
00103
00104 ros::NodeHandle& nh_;
00105 ros::NodeHandle& pnh_;
00106
00107 boost::shared_ptr<OpenNI2DeviceManager> device_manager_;
00108 boost::shared_ptr<OpenNI2Device> device_;
00109
00110 std::string device_id_;
00111
00113 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00114 bool config_init_;
00115
00116 boost::mutex connect_mutex_;
00117
00118 image_transport::CameraPublisher pub_color_;
00119 image_transport::CameraPublisher pub_depth_;
00120 image_transport::CameraPublisher pub_depth_raw_;
00121 image_transport::CameraPublisher pub_ir_;
00122 ros::Publisher pub_projector_info_;
00123
00125 boost::shared_ptr<camera_info_manager::CameraInfoManager> color_info_manager_, ir_info_manager_;
00126
00127 OpenNI2VideoMode ir_video_mode_;
00128 OpenNI2VideoMode color_video_mode_;
00129 OpenNI2VideoMode depth_video_mode_;
00130
00131 std::string ir_frame_id_;
00132 std::string color_frame_id_;
00133 std::string depth_frame_id_ ;
00134
00135 std::string color_info_url_, ir_info_url_;
00136
00137 bool color_depth_synchronization_;
00138 bool depth_registration_;
00139
00140 std::map<int, OpenNI2VideoMode> video_modes_lookup_;
00141
00142
00143 double depth_ir_offset_x_;
00144 double depth_ir_offset_y_;
00145 int z_offset_mm_;
00146 double z_scaling_;
00147
00148 ros::Duration ir_time_offset_;
00149 ros::Duration color_time_offset_;
00150 ros::Duration depth_time_offset_;
00151
00152 int data_skip_;
00153
00154 int data_skip_ir_counter_;
00155 int data_skip_color_counter_;
00156 int data_skip_depth_counter_;
00157
00158 bool auto_exposure_;
00159 bool auto_white_balance_;
00160
00161 bool ir_subscribers_;
00162 bool color_subscribers_;
00163 bool depth_subscribers_;
00164 bool depth_raw_subscribers_;
00165
00166 bool use_device_time_;
00167
00168 Config old_config_;
00169 };
00170
00171 }
00172
00173 #endif