$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011 Willow Garage, Inc. 00005 * Radu Bogdan Rusu <rusu@willowgarage.com> 00006 * Suat Gedikli <gedikli@willowgarage.com> 00007 * Patrick Mihelich <mihelich@willowgarage.com> 00008 * 00009 * All rights reserved. 00010 * 00011 * Redistribution and use in source and binary forms, with or without 00012 * modification, are permitted provided that the following conditions 00013 * are met: 00014 * 00015 * * Redistributions of source code must retain the above copyright 00016 * notice, this list of conditions and the following disclaimer. 00017 * * Redistributions in binary form must reproduce the above 00018 * copyright notice, this list of conditions and the following 00019 * disclaimer in the documentation and/or other materials provided 00020 * with the distribution. 00021 * * Neither the name of Willow Garage, Inc. nor the names of its 00022 * contributors may be used to endorse or promote products derived 00023 * from this software without specific prior written permission. 00024 * 00025 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00026 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00027 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00028 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00029 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00030 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00031 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00032 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00033 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00034 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00035 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00036 * POSSIBILITY OF SUCH DAMAGE. 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 // callback methods 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 // helper methods 00087 inline bool isImageStreamRequired() const; 00088 inline bool isDepthStreamRequired() const; 00089 sensor_msgs::CameraInfoPtr fillCameraInfo (ros::Time time, bool is_rgb); 00090 00091 // published topics 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 // Approximate synchronization for XYZRGB point clouds. 00106 boost::shared_ptr<Synchronizer> depth_rgb_sync_; 00107 00108 // publish methods 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 //boost::mutex depth_mutex_; 00129 //boost::mutex image_mutex_; 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_