$search
00001 /* 00002 * segmenter.hh 00003 * Mac Mason <mmason@willowgarage.com> 00004 * 00005 * Segment out planes & objects & whatnot. 00006 * 00007 * This object needs two things as input: a plane (PointCloud) and an Image. 00008 * It outputs several things: 00009 * 00010 * - A pointcloud of the current plane. 00011 * - Planes, as Plane messages. 00012 * - Objects, as PointClouds. 00013 * 00014 * This object maintains all of its state internally; the NodeHandle, the 00015 * publishers and subscribers, and everything else. So, build one, configure 00016 * it, start it up, and spin. 00017 */ 00018 00019 #pragma once 00020 00021 #include <string> 00022 #include <boost/utility.hpp> // For noncopyable 00023 #include <boost/scoped_ptr.hpp> 00024 #include <boost/thread.hpp> 00025 #include <boost/circular_buffer.hpp> 00026 00027 #include "ros/ros.h" 00028 00029 #include "pcl16/point_types.h" 00030 #include "pcl16_ros/point_cloud.h" 00031 #include "pcl16/ModelCoefficients.h" 00032 #include "tf/transform_listener.h" 00033 #include "tf/transform_broadcaster.h" 00034 #include "image_transport/image_transport.h" 00035 #include "sensor_msgs/CameraInfo.h" 00036 #include "message_filters/synchronizer.h" 00037 #include "message_filters/sync_policies/approximate_time.h" 00038 #include <pcl16/features/integral_image_normal.h> 00039 #include <pcl16/segmentation/organized_multi_plane_segmentation.h> 00040 #include <pcl16/segmentation/edge_aware_plane_comparator.h> 00041 00042 #include "dynamic_reconfigure/server.h" 00043 #include "semanticmodel/FilterConfig.h" 00044 #include "semanticmodel/Plane.h" 00045 #include <cstddef> 00046 00047 using semanticmodel::FilterConfig; 00048 using std::vector; 00049 00050 namespace semanticmodel 00051 { 00052 00053 class Segmenter : public boost::noncopyable 00054 { 00055 00056 private: 00057 // Save some _serious_ typing. 00058 typedef pcl16::PointXYZRGB Point; 00059 typedef pcl16::PointCloud<Point> PointCloud; 00060 00061 // Time here is tricky. However, openni_camera does approximate 00062 // synchronization for us, and then sets the cloud's timestamp to the 00063 // depth image's stamp. Sadly, that isn't (necessarily) the same as the 00064 // RGB image's stamp. Instead, we approximately synchronize all three, 00065 // knowing that (we hope) the first two are already exactly 00066 // synchronized, and the third has already passed through an 00067 // ApproximateTime policy. 00068 typedef message_filters::sync_policies:: 00069 ApproximateTime<sensor_msgs::Image, 00070 sensor_msgs::CameraInfo, 00071 sensor_msgs::Image, // Second pair are the depths. 00072 sensor_msgs::CameraInfo, 00073 PointCloud> Sync; 00074 00075 00076 public: 00077 // Any of the output topics can be the empty string, in which case we 00078 // don't publish them. The input topics, however, must both be provided. 00079 // 00080 // camera_input_topic is the (partial) namespace of the camera. For 00081 // example, the Kinect publishes /camera/rgb/image_color and 00082 // /camera/rgb/camera_info; camera_input_topic should be /camera/rgb. 00083 // (camera_info and image_color are hardcoded.) 00084 // 00085 // The passed-in topic names are appended to name_space (this permits 00086 // private naming). 00087 Segmenter(const std::string& name_space, 00088 const std::string& cloud_input_topic, 00089 const std::string& camera_input_topic, 00090 const std::string& depth_input_topic, 00091 const std::string& planecloud_output_topic, 00092 const std::string& plane_output_topic, 00093 const std::string& object_output_topic, 00094 const std::string& plane_service_topic); 00095 00096 // No need for a destructor; our members are smart. No need for other 00097 // stuff; noncopyable keeps us well-behaved. 00098 00099 /* 00100 * Our processing pipeline. This has several steps: 00101 * 00102 * 0. Transform the input into the config.canonical_frame tf frame; 00103 * this is (probably) /map, but could generally be any trustworthy frame 00104 * where +z is "up". This allows us to think about "horizontal" in very 00105 * simple terms. 00106 * 00107 * 1. A passthrough filter. This filters out NaNs, but (more 00108 * importantly) truncates out the floor and ceiling. 00109 * 00110 * 2. A plane fitter (using region-growing). This looks for 00111 * _horizontal_ planes, not just any planes. The output from this 00112 * function is zero or more planes, as PointClouds, already projected 00113 * onto their plane equations, and a vector of ModelCoefficients 00114 * objects, representing those equations. 00115 * 00116 * 3. Get the convex hull of the extracted plane. 00117 * 00118 * 4. The convex hulls we've just built aren't quite big enough; we want 00119 * to search for objects atop those hulls merged with existing ones 00120 * (which is what plane_tracker does). So, send them to the tracker, and 00121 * get back the hulls to use for the next step. 00122 * 00123 * 5. Collect the points above the convex hull; these are potential 00124 * objects. 00125 * 00126 * 6. Cluster those points to generate actual objects. 00127 * 00128 * These functions are public, for the moment, because they might be 00129 * generally useful, or something. They might not really deserve 00130 * publicity. 00131 */ 00132 void passthrough(PointCloud::Ptr& in, PointCloud::Ptr& out); 00133 00134 void fit_planes(PointCloud::ConstPtr in, 00135 pcl16::PointCloud<pcl16::Normal>::ConstPtr normals, 00136 const tf::Transform& trans, 00137 vector<PointCloud::Ptr>& good_planes, 00138 vector<pcl16::ModelCoefficients>& good_models, 00139 vector<pcl16::ModelCoefficients>& bad_models); 00140 00141 // We need the contents of both planes and hulls, so planes isn't 00142 // modified here. 00143 void convex_hulls(const vector<PointCloud::Ptr>& planes, 00144 vector<PointCloud::Ptr>& hulls); 00145 00146 // Send in some information, get back out new planes. 00147 void publish_planes(const vector<PointCloud::Ptr>& planes, 00148 const vector<PointCloud::Ptr>& hulls, 00149 const vector<pcl16::ModelCoefficients>& coeffs, 00150 vector<semanticmodel::Plane>& outputs); 00151 00152 // Note that we start working with the un-voxelized cloud again. 00153 void get_aboves(const vector<PointCloud::Ptr>& hulls, 00154 const vector<pcl16::ModelCoefficients>& coeffs, 00155 const PointCloud::Ptr& densecloud, 00156 PointCloud::Ptr& out); 00157 00158 // Throw out those "above" points that fit one of the bad_coeffs planes 00159 // too well. This helps us get rid of extraneous "wall" objects. 00160 void lose_bads(const PointCloud::ConstPtr& aboves, 00161 PointCloud::Ptr good_aboves, 00162 const vector<pcl16::ModelCoefficients>& bad_coeffs); 00163 00164 // Finally, the callback that actually drives everything. 00165 void synchronized_pipeline_callback( 00166 const sensor_msgs::ImageConstPtr& rgb_img, 00167 const sensor_msgs::CameraInfoConstPtr& rgb_info, 00168 const sensor_msgs::ImageConstPtr& depth_image, 00169 const sensor_msgs::CameraInfoConstPtr& depth_info, 00170 const PointCloud::ConstPtr& cloud); 00171 00172 // Timer to publish latest detected planes 00173 void publishLatestPlanes(const ros::WallTimerEvent& e); 00174 00175 private: 00176 // How big are our queues? 00177 static const int QUEUE_SIZE = 100; 00178 00179 // We are a node. 00180 ros::NodeHandle handle; 00181 00182 // For dynamic_reconfigure support. 00183 FilterConfig config; 00184 dynamic_reconfigure::Server<FilterConfig> dynparam_srv; 00185 dynamic_reconfigure::Server<FilterConfig>::CallbackType dynparam_func; 00186 boost::mutex config_mutex; 00187 00188 // Finally, the dynamic_reconfigure callback. 00189 void dynamic_reconfigure_callback(const FilterConfig& config, 00190 uint32_t level); 00191 00192 // is a plane horizontal to within a threshold? 00193 bool isHorizontal(const pcl16::ModelCoefficients& coeffs) const; 00194 00195 // is a plane within GROUND_PLANE_THRESHOLD (m) of the ground? 00196 bool isGroundPlane(const pcl16::ModelCoefficients& coeffs) const; 00197 00198 // Transform coefficients into map frame 00199 pcl16::ModelCoefficients transformCoeffs(const btTransform& trans, 00200 const pcl16::ModelCoefficients& in); 00201 00202 // tf support; pointers are needed here to enforce that we have a 00203 // nodehandle before these are built. 00204 boost::scoped_ptr<tf::TransformListener> listener; 00205 boost::scoped_ptr<tf::TransformBroadcaster> broadcaster; 00206 00207 // Squeeze all of our messages together. See the long comment below, 00208 // too. 00209 boost::scoped_ptr< message_filters::Synchronizer<Sync> > sync; 00210 00211 /* 00212 * We need image_transport to play nicely with ApproximateTime, which it 00213 * doesn't (automatically), because the ApproximateTime stuff requires 00214 * message_filter subscriptions, not image_transport subscriptions. We 00215 * can get around this (cf openni_record_player) using .add<i> on our 00216 * synchronizer; this means we need barely-op callbacks for the three 00217 * channels we're watching, plus subscribers for them. 00218 */ 00219 ros::Subscriber cloud_sub; 00220 image_transport::ImageTransport rgb_transport; // For the next one. 00221 image_transport::CameraSubscriber cam_sub; // Gets both. 00222 image_transport::ImageTransport depth_transport; 00223 image_transport::CameraSubscriber depth_sub; // Gets both. 00224 00225 // The barely-op callbacks described above; these just push their 00226 // messages into the sync queues. 00227 void cloud_cb(const PointCloud::ConstPtr& cloud); 00228 void camera_cb(const sensor_msgs::ImageConstPtr& img, 00229 const sensor_msgs::CameraInfoConstPtr& info); 00230 void depth_cb(const sensor_msgs::ImageConstPtr& img, 00231 const sensor_msgs::CameraInfoConstPtr& info); 00232 00233 // The various things we push out. 00234 ros::Publisher map_points_pub; // Just the points transformed to /map. 00235 ros::Publisher planecloud_pub; 00236 ros::Publisher plane_pub; 00237 ros::Publisher object_pub; 00238 ros::Publisher latest_plane_pub_; 00239 00240 // For our plane-merging service 00241 ros::ServiceClient planetracker_srv; 00242 00243 // Plane segmentation 00244 pcl16::OrganizedMultiPlaneSegmentation<Point, pcl16::Normal, pcl16::Label> 00245 plane_segmenter_; 00246 00247 // Normal estimation 00248 pcl16::IntegralImageNormalEstimation<Point, pcl16::Normal> normal_estimator_; 00249 00250 // Pairwise comparator used by segmentation 00251 boost::shared_ptr<pcl16::EdgeAwarePlaneComparator<Point, pcl16::Normal> > 00252 comp_; 00253 00254 // Latest detected planes 00255 boost::circular_buffer<PointCloud::Ptr> latest_planes_; 00256 ros::WallTimer latest_plane_timer_; 00257 00258 // If we're on a robot, we can short-circuit early (as soon as planes 00259 // are published for the benefit of the head pointer). This is collected 00260 // from a param at construction-time. 00261 bool short_circuit; 00262 00263 // Some debugging data. 00264 int processed; 00265 int skipped; 00266 }; 00267 00268 } // namespace semanticmodel