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_NODELET_OPENNI_H_
00040 #define OPENNI_NODELET_OPENNI_H_
00041
00042
00043 #include <ros/ros.h>
00044 #include <nodelet/nodelet.h>
00045 #include <image_transport/image_transport.h>
00046
00047
00048 #include <camera_info_manager/camera_info_manager.h>
00049 #include <dynamic_reconfigure/server.h>
00050 #if 0
00051 #include <openni_camera/OpenNIConfig.h>
00052 #else
00053 #include <openni_camera_unstable/OpenNIConfig.h>
00054 namespace openni_camera {
00055 using namespace openni_camera_unstable;
00056 }
00057 #endif
00058
00059
00060 #include "openni_camera/openni_driver.h"
00061
00062 namespace openni_camera
00063 {
00065 class OpenNINodelet : public nodelet::Nodelet
00066 {
00067 public:
00068 virtual ~OpenNINodelet ();
00069 private:
00070 typedef OpenNIConfig Config;
00071 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00072
00074 virtual void onInit ();
00075 void setupDevice ();
00076 void updateModeMaps ();
00077 void startSynchronization ();
00078 void stopSynchronization ();
00079 void setupDeviceModes (int image_mode, int depth_mode);
00080
00082 int mapXnMode2ConfigMode (const XnMapOutputMode& output_mode) const;
00083 XnMapOutputMode mapConfigMode2XnMode (int mode) const;
00084
00085
00086 void imageCb(boost::shared_ptr<openni_wrapper::Image> image, void* cookie);
00087 void depthCb(boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie);
00088 void irCb(boost::shared_ptr<openni_wrapper::IRImage> ir_image, void* cookie);
00089 void connectCb();
00090 void configCb(Config &config, uint32_t level);
00091
00092
00093 inline bool isImageStreamRequired() const;
00094 inline bool isDepthStreamRequired() const;
00095 inline bool isIrStreamRequired() const;
00096
00097
00098 sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const;
00099 sensor_msgs::CameraInfoPtr getRgbCameraInfo(ros::Time time) const;
00100 sensor_msgs::CameraInfoPtr getIrCameraInfo(ros::Time time) const;
00101 sensor_msgs::CameraInfoPtr getDepthCameraInfo(ros::Time time) const;
00102
00103
00104 ros::Publisher pub_rgb_info_, pub_depth_info_, pub_depth_registered_info_, pub_ir_info_;
00105 image_transport::Publisher pub_rgb_raw_, pub_rgb_mono_, pub_rgb_color_;
00106 image_transport::Publisher pub_depth_, pub_depth_registered_;
00107 image_transport::Publisher pub_ir_;
00108
00109
00110 void publishRgbImageRaw (const openni_wrapper::Image& image, ros::Time time) const;
00111 void publishGrayImage (const openni_wrapper::Image& image, ros::Time time) const;
00112 void publishRgbImage (const openni_wrapper::Image& image, ros::Time time) const;
00113 void publishDepthImageRaw(const openni_wrapper::DepthImage& depth,
00114 ros::Time time, const std::string& frame_id,
00115 const image_transport::Publisher& pub) const;
00116 void publishIrImage(const openni_wrapper::IRImage& ir, ros::Time time) const;
00117
00119 boost::shared_ptr<openni_wrapper::OpenNIDevice> device_;
00120
00122 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00123 Config config_;
00124
00126 boost::shared_ptr<CameraInfoManager> rgb_info_manager_, ir_info_manager_;
00127 std::string rgb_frame_id_;
00128 std::string depth_frame_id_;
00129 double depth_ir_offset_x_;
00130 double depth_ir_offset_y_;
00131
00133 unsigned image_width_;
00134 unsigned image_height_;
00135 unsigned depth_width_;
00136 unsigned depth_height_;
00137
00138 void watchDog(const ros::TimerEvent& event);
00139
00141 double time_out_;
00142 ros::Time time_stamp_;
00143 ros::Timer watch_dog_timer_;
00144
00145 struct modeComp
00146 {
00147 bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode& mode2) const
00148 {
00149 if (mode1.nXRes < mode2.nXRes)
00150 return true;
00151 else if (mode1.nXRes > mode2.nXRes)
00152 return false;
00153 else if (mode1.nYRes < mode2.nYRes)
00154 return true;
00155 else if (mode1.nYRes > mode2.nYRes)
00156 return false;
00157 else if (mode1.nFPS < mode2.nFPS)
00158 return true;
00159 else
00160 return false;
00161 }
00162 };
00163 std::map<XnMapOutputMode, int, modeComp> xn2config_map_;
00164 std::map<int, XnMapOutputMode> config2xn_map_;
00165 };
00166
00167 bool OpenNINodelet::isImageStreamRequired() const
00168 {
00169 return (pub_rgb_raw_ .getNumSubscribers() > 0 ||
00170 pub_rgb_mono_ .getNumSubscribers() > 0 ||
00171 pub_rgb_color_ .getNumSubscribers() > 0 ||
00172 pub_rgb_info_ .getNumSubscribers() > 0 );
00173 }
00174
00175 bool OpenNINodelet::isDepthStreamRequired() const
00176 {
00177 if (device_->isDepthRegistered())
00178 return (pub_depth_registered_ .getNumSubscribers() > 0 ||
00179 pub_depth_registered_info_.getNumSubscribers() > 0 );
00180 else
00181 return (pub_depth_ .getNumSubscribers() > 0 ||
00182 pub_depth_info_.getNumSubscribers() > 0 );
00183 }
00184
00185 bool OpenNINodelet::isIrStreamRequired() const
00186 {
00187 return (pub_ir_ .getNumSubscribers() > 0 ||
00188 pub_ir_info_.getNumSubscribers() > 0 );
00189 }
00190
00191 }
00192
00193 #endif //#ifndef OPENNI_NODELET_OPENNI_H_