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