40 #include <geometry_msgs/PolygonStamped.h>
54 NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n"
55 " - use_indices : %s",
70 sub_input_filter_.subscribe (*pnh_,
"input", 1);
72 sub_indices_filter_.subscribe (*pnh_,
"indices", 1);
74 if (approximate_sync_)
76 sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointIndices> > >(max_queue_size_);
78 sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
83 sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointIndices> > >(max_queue_size_);
85 sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
100 sub_input_filter_.unsubscribe();
101 sub_indices_filter_.unsubscribe();
104 sub_input_.shutdown();
113 if (pub_output_.getNumSubscribers () <= 0 && pub_plane_.getNumSubscribers () <= 0)
119 if (!isValid (cloud))
123 output.header = cloud->header;
124 pub_output_.publish (
ros_ptr(output.makeShared ()));
128 if (indices && !isValid (indices,
"indices"))
132 output.header = cloud->header;
133 pub_output_.publish (
ros_ptr(output.makeShared ()));
140 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
141 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
143 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (),
fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName (
"input").c_str (),
144 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName (
"indices").c_str ());
146 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,
fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName (
"input").c_str ());
151 indices_ptr.reset (
new std::vector<int> (indices->indices));
153 impl_.setInputCloud (
pcl_ptr(cloud));
154 impl_.setIndices (indices_ptr);
157 impl_.reconstruct (output);
160 if (output.points.size () >= 3)
162 geometry_msgs::PolygonStamped poly;
163 poly.header =
fromPCL(output.header);
164 poly.polygon.points.resize (output.points.size ());
166 pcl::Vector4fMap O = output.points[1].getVector4fMap ();
167 pcl::Vector4fMap B = output.points[0].getVector4fMap ();
168 pcl::Vector4fMap A = output.points[2].getVector4fMap ();
170 Eigen::Vector4f OA = A - O;
171 Eigen::Vector4f OB = B - O;
172 Eigen::Vector4f N = OA.cross3 (OB);
173 double theta = N.dot (O);
174 bool reversed =
false;
175 if (theta < (M_PI / 2.0))
177 for (
size_t i = 0; i < output.points.size (); ++i)
181 size_t j = output.points.size () - i - 1;
182 poly.polygon.points[i].x = output.points[j].x;
183 poly.polygon.points[i].y = output.points[j].y;
184 poly.polygon.points[i].z = output.points[j].z;
188 poly.polygon.points[i].x = output.points[i].x;
189 poly.polygon.points[i].y = output.points[i].y;
190 poly.polygon.points[i].z = output.points[i].z;
193 pub_plane_.publish (boost::make_shared<const geometry_msgs::PolygonStamped> (poly));
196 output.header = cloud->header;
197 pub_output_.publish (
ros_ptr(output.makeShared ()));