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 #include <pluginlib/class_list_macros.h>
00039 #include "pcl_ros/surface/convex_hull.h"
00040 #include <geometry_msgs/PolygonStamped.h>
00041
00043 void
00044 pcl_ros::ConvexHull2D::onInit ()
00045 {
00046 ros::NodeHandle pnh = getMTPrivateNodeHandle ();
00047 pub_output_ = pnh.advertise<PointCloud> ("output", max_queue_size_);
00048 pub_plane_ = pnh.advertise<geometry_msgs::PolygonStamped>("output_polygon", max_queue_size_);
00049
00050
00051 pnh.getParam ("use_indices", use_indices_);
00052
00053
00054 if (use_indices_)
00055 {
00056
00057 sub_input_filter_.subscribe (pnh, "input", 1);
00058
00059 sub_indices_filter_.subscribe (pnh, "indices", 1);
00060
00061 if (approximate_sync_)
00062 {
00063 sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointIndices> > >(max_queue_size_);
00064
00065 sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
00066 sync_input_indices_a_->registerCallback (bind (&ConvexHull2D::input_indices_callback, this, _1, _2));
00067 }
00068 else
00069 {
00070 sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointIndices> > >(max_queue_size_);
00071
00072 sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
00073 sync_input_indices_e_->registerCallback (bind (&ConvexHull2D::input_indices_callback, this, _1, _2));
00074 }
00075 }
00076 else
00077
00078 sub_input_ = pnh.subscribe<PointCloud> ("input", 1, bind (&ConvexHull2D::input_indices_callback, this, _1, PointIndicesConstPtr ()));
00079
00080 NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
00081 " - use_indices : %s",
00082 getName ().c_str (),
00083 (use_indices_) ? "true" : "false");
00084 }
00085
00087 void
00088 pcl_ros::ConvexHull2D::input_indices_callback (const PointCloudConstPtr &cloud,
00089 const PointIndicesConstPtr &indices)
00090 {
00091
00092 if (pub_output_.getNumSubscribers () <= 0 && pub_plane_.getNumSubscribers () <= 0)
00093 return;
00094
00095 PointCloud output;
00096
00097
00098 if (!isValid (cloud))
00099 {
00100 NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
00101
00102 output.header = cloud->header;
00103 pub_output_.publish (output.makeShared ());
00104 return;
00105 }
00106
00107 if (indices && !isValid (indices, "indices"))
00108 {
00109 NODELET_ERROR ("[%s::input_indices_callback] Invalid indices!", getName ().c_str ());
00110
00111 output.header = cloud->header;
00112 pub_output_.publish (output.makeShared ());
00113 return;
00114 }
00115
00117 if (indices)
00118 NODELET_DEBUG ("[%s::input_indices_model_callback]\n"
00119 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00120 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
00121 getName ().c_str (),
00122 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName ("input").c_str (),
00123 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName ("indices").c_str ());
00124 else
00125 NODELET_DEBUG ("[%s::input_indices_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", getName ().c_str (), cloud->width * cloud->height, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName ("input").c_str ());
00126
00127
00128 IndicesConstPtr indices_ptr;
00129 if (indices)
00130 indices_ptr = boost::make_shared <std::vector<int> > (indices->indices);
00131
00132 impl_.setInputCloud (cloud);
00133 impl_.setIndices (indices_ptr);
00134
00135
00136 impl_.reconstruct (output);
00137
00138
00139 if (output.points.size () >= 3)
00140 {
00141 geometry_msgs::PolygonStamped poly;
00142 poly.header = output.header;
00143 poly.polygon.points.resize (output.points.size ());
00144
00145 pcl::Vector4fMap O = output.points[1].getVector4fMap ();
00146 pcl::Vector4fMap B = output.points[0].getVector4fMap ();
00147 pcl::Vector4fMap A = output.points[2].getVector4fMap ();
00148
00149 Eigen::Vector4f OA = A - O;
00150 Eigen::Vector4f OB = B - O;
00151 Eigen::Vector4f N = OA.cross3 (OB);
00152 double theta = N.dot (O);
00153 bool reversed = false;
00154 if (theta < (M_PI / 2.0))
00155 reversed = true;
00156 for (size_t i = 0; i < output.points.size (); ++i)
00157 {
00158 if (reversed)
00159 {
00160 size_t j = output.points.size () - i - 1;
00161 poly.polygon.points[i].x = output.points[j].x;
00162 poly.polygon.points[i].y = output.points[j].y;
00163 poly.polygon.points[i].z = output.points[j].z;
00164 }
00165 else
00166 {
00167 poly.polygon.points[i].x = output.points[i].x;
00168 poly.polygon.points[i].y = output.points[i].y;
00169 poly.polygon.points[i].z = output.points[i].z;
00170 }
00171 }
00172 pub_plane_.publish (boost::make_shared<const geometry_msgs::PolygonStamped> (poly));
00173 }
00174
00175 output.header = cloud->header;
00176 pub_output_.publish (output.makeShared ());
00177 }
00178
00179 typedef pcl_ros::ConvexHull2D ConvexHull2D;
00180 PLUGINLIB_DECLARE_CLASS (pcl, ConvexHull2D, ConvexHull2D, nodelet::Nodelet);
00181