37 #include <geometry_msgs/PolygonStamped.h>
38 #include <Eigen/StdVector>
39 #include <pcl/ModelCoefficients.h>
40 #include <pcl/filters/project_inliers.h>
41 #include <pcl/filters/extract_indices.h>
42 #include <pcl/sample_consensus/method_types.h>
43 #include <pcl/sample_consensus/model_types.h>
44 #include <pcl/segmentation/sac_segmentation.h>
45 #include <pcl/common/distances.h>
46 #include <pcl/features/normal_3d.h>
47 #include <pcl/surface/concave_hull.h>
48 #include <pcl/common/centroid.h>
49 #include <visualization_msgs/Marker.h>
54 #include <visualization_msgs/MarkerArray.h>
61 DiagnosticNodelet::onInit();
65 *pnh_,
"output/plane_aligned", 1);
67 *pnh_,
"output/convex_aligned", 1);
69 *pnh_,
"output/convex_aligned_pose_array", 1);
94 = boost::make_shared<message_filters::Synchronizer<SyncPolygonPolicy> >(100);
103 "input/convex_align_polygon", 1,
119 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
120 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
123 vital_checker_->poke();
128 const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
136 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
138 pose_msg->header.stamp,
140 Eigen::Affine3d pose_eigend;
141 Eigen::Affine3f pose_eigen;
144 Eigen::Vector3f pose_point(pose_eigen.translation());
145 double min_distance = DBL_MAX;
147 for (
size_t i = 0;
i < convexes.size();
i++) {
149 double d = convex->distanceToPoint(pose_point);
150 if (d < min_distance) {
157 geometry_msgs::PoseStamped aligned_pose =
alignPose(pose_eigen, min_convex);
158 aligned_pose.header = pose_msg->header;
167 jsk_recognition_msgs::SnapFootstep::Request&
req,
168 jsk_recognition_msgs::SnapFootstep::Response&
res)
171 jsk_footstep_msgs::FootstepArray input_footsteps =
req.input;
172 res.output.header = input_footsteps.header;
173 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
175 input_footsteps.header.stamp,
177 for (
size_t i = 0;
i < input_footsteps.footsteps.size();
i++) {
178 jsk_footstep_msgs::Footstep footstep = input_footsteps.footsteps[
i];
179 Eigen::Affine3d pose_eigend;
180 Eigen::Affine3f pose_eigen;
182 Eigen::Vector3f pose_point(pose_eigen.translation());
184 jsk_footstep_msgs::Footstep aligned_footstep;
185 if (min_index != -1) {
187 geometry_msgs::PoseStamped aligned_pose =
alignPose(pose_eigen, min_convex);
188 aligned_footstep.pose = aligned_pose.pose;
191 aligned_footstep.pose = footstep.pose;
194 aligned_footstep.leg = footstep.leg;
195 aligned_footstep.dimensions = footstep.dimensions;
196 aligned_footstep.duration = footstep.duration;
197 aligned_footstep.footstep_group = footstep.footstep_group;
198 res.output.footsteps.push_back(aligned_footstep);
204 const geometry_msgs::PolygonStamped::ConstPtr& poly_msg)
207 geometry_msgs::PoseArray pose_array;
208 pose_array.header = poly_msg->header;
213 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
215 poly_msg->header.stamp,
217 for (
size_t i = 0;
i < poly_msg->polygon.points.size();
i++) {
218 geometry_msgs::Point32
p = poly_msg->polygon.points[
i];
219 Eigen::Vector3f pose_point(
p.x,
p.y,
p.z);
221 if (min_index == -1) {
227 Eigen::Affine3f pose_eigen = Eigen::Affine3f::Identity();
228 pose_eigen.translate(pose_point);
229 geometry_msgs::PoseStamped aligned_pose =
alignPose(pose_eigen, min_convex);
230 aligned_pose.header = poly_msg->header;
231 pose_array.poses.push_back(aligned_pose.pose);
238 const Eigen::Vector3f& pose_point,
239 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
242 double min_distance = DBL_MAX;
244 for (
size_t i = 0;
i < convexes.size();
i++) {
246 if (convex->isProjectableInside(pose_point)) {
247 double d = convex->distanceToPoint(pose_point);
248 if (
d < min_distance) {
259 const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
267 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
269 pose_msg->header.stamp,
271 Eigen::Affine3d pose_eigend;
272 Eigen::Affine3f pose_eigen;
275 Eigen::Vector3f pose_point(pose_eigen.translation());
277 if (min_index != -1) {
279 geometry_msgs::PoseStamped aligned_pose =
alignPose(pose_eigen, min_convex);
280 aligned_pose.header = pose_msg->header;
291 Eigen::Affine3f aligned_pose(
pose);
292 Eigen::Vector3f original_point(
pose.translation());
293 Eigen::Vector3f projected_point;
294 convex->project(original_point, projected_point);
296 Eigen::Vector3f normal = convex->getNormal();
297 Eigen::Vector3f old_normal;
298 old_normal[0] =
pose(0, 2);
299 old_normal[1] =
pose(1, 2);
300 old_normal[2] =
pose(2, 2);
301 Eigen::Quaternionf
rot;
302 if (normal.dot(old_normal) < 0) {
305 rot.setFromTwoVectors(old_normal, normal);
306 aligned_pose = aligned_pose *
rot;
307 aligned_pose.translation() = projected_point;
308 Eigen::Affine3d aligned_posed;
310 geometry_msgs::PoseStamped ret;
317 jsk_recognition_msgs::PolygonArray::ConstPtr polygons)
319 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>
result;
322 for (
size_t i = 0;
i <
polygons->polygons.size();
i++) {
329 for (
size_t j = 0; j <
polygon.polygon.points.size(); j++) {
335 Eigen::Affine3d eigen_transform;
337 Eigen::Vector4d transformed_pointd = eigen_transform.inverse() *
p;
338 Eigen::Vector3f transformed_point;
339 transformed_point[0] = transformed_pointd[0];
340 transformed_point[1] = transformed_pointd[1];
341 transformed_point[2] = transformed_pointd[2];
342 vertices.push_back(transformed_point);
344 std::reverse(vertices.begin(), vertices.end());