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 #include <nodelet/nodelet.h>
00043 #include "openni_camera/openni_driver.h"
00044 #include <boost/shared_ptr.hpp>
00045 #include <dynamic_reconfigure/server.h>
00046 #include <openni_camera/OpenNIConfig.h>
00047 #include <image_transport/image_transport.h>
00048 #include <string>
00049 #include <message_filters/synchronizer.h>
00050 #include <message_filters/sync_policies/approximate_time.h>
00051 #include <Eigen/Core>
00052 #include <pcl/PointIndices.h>
00053
00054 namespace openni_camera
00055 {
00057 class OpenNINodelet : public nodelet::Nodelet
00058 {
00059 public:
00060 virtual ~OpenNINodelet ();
00061 private:
00062 typedef OpenNIConfig Config;
00063 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00064 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> SyncPolicy;
00065 typedef message_filters::Synchronizer<SyncPolicy> Synchronizer;
00066
00068 virtual void onInit ();
00069 void setupDevice (ros::NodeHandle& param_nh);
00070 void updateModeMaps ();
00071 void startSynchronization ();
00072 void stopSynchronization ();
00073 void setupDeviceModes (int image_mode, int depth_mode);
00074 bool isImageModeSupported (int image_mode) const;
00075 bool isDepthModeSupported (int depth_mode) const;
00076
00077 void configCallback (Config &config, uint32_t level);
00078 int mapXnMode2ConfigMode (const XnMapOutputMode& output_mode) const;
00079 XnMapOutputMode mapConfigMode2XnMode (int mode) const;
00080
00081
00082 void imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void* cookie);
00083 void depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie);
00084 void subscriberChangedEvent ();
00085
00086
00087 inline bool isImageStreamRequired() const;
00088 inline bool isDepthStreamRequired() const;
00089 sensor_msgs::CameraInfoPtr fillCameraInfo (ros::Time time, bool is_rgb);
00090
00091
00092 ros::Publisher pub_rgb_info_, pub_depth_info_;
00093 image_transport::Publisher pub_rgb_image_, pub_gray_image_, pub_depth_image_;
00094
00096 image_transport::Publisher pub_image_raw_, pub_depth_raw_;
00097
00098 ros::Publisher pub_disparity_;
00099 ros::Publisher pub_point_cloud_;
00100 ros::Publisher pub_point_cloud_rgb_;
00101
00103 ros::Subscriber sub_mask_indices_;
00104
00105
00106 boost::shared_ptr<Synchronizer> depth_rgb_sync_;
00107
00108
00109 void publishRgbImage (const openni_wrapper::Image& image, ros::Time time) const;
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 publishDepthImage (const openni_wrapper::DepthImage& depth, ros::Time time) const;
00113 void publishDepthImageRaw (const openni_wrapper::DepthImage& depth, ros::Time time) const;
00114 void publishDisparity (const openni_wrapper::DepthImage& depth, ros::Time time) const;
00115 void publishXYZPointCloud (const openni_wrapper::DepthImage& depth, ros::Time time) const;
00116 void publishXYZRGBPointCloud (const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& rgb_msg) const;
00117
00119 void maskIndicesCb(const pcl::PointIndicesConstPtr& indices);
00120
00122 boost::shared_ptr<openni_wrapper::OpenNIDevice> device_;
00123
00125 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00126 Config config_;
00127 boost::recursive_mutex reconfigure_mutex_;
00128
00129
00130
00131 std::string rgb_frame_id_;
00132 std::string depth_frame_id_;
00133 unsigned image_width_;
00134 unsigned image_height_;
00135 unsigned depth_width_;
00136 unsigned depth_height_;
00137
00139 bool use_indices_;
00140
00142 std::vector<int32_t> mask_indices_;
00143
00144 struct modeComp
00145 {
00146 bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode& mode2) const
00147 {
00148 if (mode1.nXRes < mode2.nXRes)
00149 return true;
00150 else if (mode1.nXRes > mode2.nXRes)
00151 return false;
00152 else if (mode1.nYRes < mode2.nYRes)
00153 return true;
00154 else if (mode1.nYRes > mode2.nYRes)
00155 return false;
00156 else if (mode1.nFPS < mode2.nFPS)
00157 return true;
00158 else
00159 return false;
00160 }
00161 };
00162 std::map<XnMapOutputMode, int, modeComp> xn2config_map_;
00163 std::map<int, XnMapOutputMode> config2xn_map_;
00164 public:
00165 EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
00166 };
00167
00168 bool OpenNINodelet::isImageStreamRequired() const
00169 {
00170 return (pub_rgb_image_.getNumSubscribers() > 0 ||
00171 pub_image_raw_.getNumSubscribers() > 0 ||
00172 pub_gray_image_.getNumSubscribers() > 0 ||
00173 pub_point_cloud_rgb_.getNumSubscribers() > 0 );
00174 }
00175
00176 bool OpenNINodelet::isDepthStreamRequired() const
00177 {
00178 return (pub_depth_image_.getNumSubscribers() > 0 ||
00179 pub_depth_raw_.getNumSubscribers() > 0 ||
00180 pub_disparity_.getNumSubscribers() > 0 ||
00181 pub_point_cloud_.getNumSubscribers() > 0 ||
00182 pub_point_cloud_rgb_.getNumSubscribers() > 0 );
00183 }
00184
00185 }
00186
00187 #endif //#ifndef OPENNI_NODELET_OPENNI_H_