48 #include <visualization_msgs/Marker.h>
49 #include <visualization_msgs/MarkerArray.h>
52 #define DEBUG_PRINT(proc) if (debug_print_) { std::cerr << proc << std::endl; }
65 return "no pointcloud";
68 return "no enough support";
74 return "no enough inliers";
77 return "close to success";
80 return "unknown error";
84 jsk_footstep_msgs::Footstep::Ptr
87 jsk_footstep_msgs::Footstep::Ptr ret(
new jsk_footstep_msgs::Footstep);
95 jsk_footstep_msgs::Footstep::Ptr
98 jsk_footstep_msgs::Footstep::Ptr ret(
new jsk_footstep_msgs::Footstep);
99 Eigen::Affine3f newpose =
pose_ * Eigen::Translation3f(ioffset);
104 ret->offset.x = - ioffset[0];
105 ret->offset.y = - ioffset[1];
106 ret->offset.z = - ioffset[2];
111 pcl::PointIndices::Ptr
113 pcl::PointIndices::Ptr near_indices,
114 double padding_x,
double padding_y)
117 Eigen::Vector3f
z(0, 0, 1);
122 Eigen::Vector3f a_2d =
a + (-
z.dot(
a)) *
z;
123 Eigen::Vector3f b_2d =
b + (-
z.dot(
b)) *
z;
124 Eigen::Vector3f c_2d =
c + (-
z.dot(
c)) *
z;
125 Eigen::Vector3f d_2d =
d + (-
z.dot(
d)) *
z;
127 Eigen::Vector2f a2d(a_2d[0], a_2d[1]);
128 Eigen::Vector2f b2d(b_2d[0], b_2d[1]);
129 Eigen::Vector2f c2d(c_2d[0], c_2d[1]);
130 Eigen::Vector2f d2d(d_2d[0], d_2d[1]);
132 pcl::PointIndices::Ptr ret(
new pcl::PointIndices);
133 ret->indices.reserve(near_indices->indices.size());
134 const std::vector<int> near_indices_indices = near_indices->indices;
135 for (
size_t i = 0;
i < near_indices->indices.size();
i++) {
136 const int index = near_indices_indices[
i];
138 const Eigen::Vector3f ep =
point.getVector3fMap();
139 const Eigen::Vector3f point_2d = ep + (-
z.dot(ep)) *
z;
140 const Eigen::Vector2f p2d(point_2d[0], point_2d[1]);
141 if (
cross2d((b2d - a2d), (p2d - a2d)) > 0 &&
142 cross2d((c2d - b2d), (p2d - b2d)) > 0 &&
143 cross2d((d2d - c2d), (p2d - c2d)) > 0 &&
144 cross2d((a2d - d2d), (p2d - d2d)) > 0) {
146 ret->indices.push_back(
index);
154 pcl::PointIndices::Ptr
157 double padding_x,
double padding_y)
159 pcl::PointIndices::Ptr near_indices(
new pcl::PointIndices);
169 pcl::PointIndices::Ptr
171 pcl::search::Octree<pcl::PointNormal>&
tree)
173 pcl::PointNormal center;
174 center.getVector3fMap() = Eigen::Vector3f(
pose_.translation());
177 pcl::PointIndices::Ptr near_indices(
new pcl::PointIndices);
178 std::vector<float> distances;
179 tree.radiusSearch(center, r, near_indices->indices, distances);
185 Eigen::Vector3f a0, a1, a2, a3;
186 Eigen::Vector3f b0, b1, b2, b3;
187 vertices(a0, a1, a2, a3, collision_padding);
188 other->vertices(b0, b1, b2, b3, collision_padding);
189 Line2D a_01(a0, a1), a_12(a1, a2), a_23(a2, a3), a_30(a3, a0);
190 Line2D b_01(b0, b1), b_12(b1, b2), b_23(b2, b3), b_30(b3, b0);
191 return !(a_01.isCrossing(b_01) ||
192 a_01.isCrossing(b_12) ||
193 a_01.isCrossing(b_23) ||
194 a_01.isCrossing(b_30) ||
195 a_12.isCrossing(b_01) ||
196 a_12.isCrossing(b_12) ||
197 a_12.isCrossing(b_23) ||
198 a_12.isCrossing(b_30) ||
199 a_23.isCrossing(b_01) ||
200 a_23.isCrossing(b_12) ||
201 a_23.isCrossing(b_23) ||
202 a_23.isCrossing(b_30) ||
211 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud,
213 pcl::search::Octree<pcl::PointNormal>& tree_2d,
214 pcl::PointCloud<pcl::PointNormal>::Ptr cloud_2d,
215 const Eigen::Vector3f& z,
216 unsigned int& error_state,
223 DEBUG_PRINT(std::endl <<
"[FS state] projectToCloud");
224 pcl::PointIndices::Ptr indices;
231 parameters.support_check_vertex_neighbor_threshold);
232 DEBUG_PRINT(
"[FS state] pre /(skip_cropping) projection state " << presupport_state);
237 DEBUG_PRINT(
"[FS state] pre / indices " << indices->indices.size());
238 if (indices->indices.size() <
parameters.plane_estimation_min_inliers) {
245 double ax = 0.0, ay = 0.0, az = 0.0;
246 double xx = 0.0, yy = 0.0, zz = 0.0;
247 for (
size_t i = 0;
i < indices->indices.size();
i++) {
248 pcl::PointNormal pp =
cloud->points[indices->indices[
i]];
249 ROS_INFO(
"%d %f %f %f", indices->indices[
i], pp.x, pp.y, pp.z);
250 ax += pp.x; ay += pp.y; az += pp.z;
251 xx += pp.x*pp.x; yy += pp.y*pp.y; zz += pp.z*pp.z;
253 int ss = indices->indices.size();
254 ROS_INFO(
"ave( %d ): %f %f %f, %f %f %f",
255 ss, ax/ss, ay/ss, az/ss,
256 sqrt(xx/ss - (ax/ss)*(ax/ss)),
257 sqrt(yy/ss - (ay/ss)*(ay/ss)),
258 sqrt(zz/ss - (az/ss)*(az/ss)));
264 parameters.support_check_vertex_neighbor_threshold);
265 DEBUG_PRINT(
"[FS state] pre / (!skip_cropping) projection state " << presupport_state);
275 pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
276 pcl::ModelCoefficients::Ptr
coefficients (
new pcl::ModelCoefficients);
277 if (!
parameters.plane_estimation_use_normal) {
278 pcl::SACSegmentation<pcl::PointNormal> seg;
279 seg.setOptimizeCoefficients (
true);
280 seg.setRadiusLimits(0.01, std::numeric_limits<double>::max ());
281 seg.setMethodType(pcl::SAC_RANSAC);
282 seg.setDistanceThreshold(
parameters.plane_estimation_outlier_threshold);
283 seg.setModelType(pcl::SACMODEL_PLANE);
284 seg.setInputCloud(
cloud);
286 seg.setIndices(indices);
287 seg.setMaxIterations(
parameters.plane_estimation_max_iterations);
290 pcl::SACSegmentationFromNormals<pcl::PointNormal, pcl::PointNormal> seg;
291 seg.setOptimizeCoefficients (
true);
292 seg.setRadiusLimits(0.01, std::numeric_limits<double>::max ());
293 seg.setMethodType(pcl::SAC_RANSAC);
294 seg.setDistanceThreshold(
parameters.plane_estimation_outlier_threshold);
295 seg.setModelType(pcl::SACMODEL_NORMAL_PLANE);
296 seg.setInputCloud(
cloud);
298 seg.setInputNormals(
cloud);
299 seg.setNormalDistanceWeight(
parameters.plane_estimation_normal_distance_weight);
300 seg.setMinMaxOpeningAngle(-
parameters.plane_estimation_normal_opening_angle,
301 parameters.plane_estimation_normal_opening_angle);
303 seg.setIndices(indices);
304 seg.setMaxIterations(
parameters.plane_estimation_max_iterations);
308 DEBUG_PRINT(
"[FS state] inliers " << inliers->indices.size() );
309 if (inliers->indices.size() == 0) {
314 else if (inliers->indices.size() <
parameters.plane_estimation_min_inliers) {
315 DEBUG_PRINT(
"[FS state] no enough inliners " << inliers->indices.size() );
322 plane = plane.
flip();
327 Eigen::Vector3f
x =
pose_.matrix().block<3, 3>(0, 0) * Eigen::Vector3f::UnitX();
328 if (acos(
n.dot(
x)) == 0) {
332 Eigen::Vector3f rotation_axis =
n.cross(
x).normalized();
333 Eigen::Vector3f new_x = Eigen::AngleAxisf(
M_PI / 2.0, rotation_axis) *
n;
334 if (acos(new_x.dot(
x)) >
M_PI / 2.0) {
337 Eigen::Vector3f new_y =
n.cross(new_x);
338 Eigen::Matrix3f new_rot_mat;
339 new_rot_mat << new_x, new_y,
n;
340 Eigen::Quaternionf new_rot(new_rot_mat);
341 Eigen::Vector3f
p(
pose_.translation());
345 Eigen::Affine3f new_pose = Eigen::Translation3f(
q) * new_rot;
352 visualization_msgs::Marker
marker;
353 marker.header.frame_id =
"map";
357 marker.type = visualization_msgs::Marker::POINTS;
358 marker.action = visualization_msgs::Marker::ADD;
359 marker.pose.position.x = 0;
360 marker.pose.position.y = 0;
361 marker.pose.position.z = 0;
362 marker.pose.orientation.x = 0.0;
363 marker.pose.orientation.y = 0.0;
364 marker.pose.orientation.z = 0.0;
365 marker.pose.orientation.w = 1.0;
374 for(
int i;
i < inliers->indices.size();
i++) {
375 geometry_msgs::Point pp;
376 pcl::PointNormal pt =
cloud->points[inliers->indices[
i]];
380 marker.points.push_back(pp);
382 visualization_msgs::Marker marker_p;
383 marker_p.header.frame_id =
"map";
387 marker_p.type = visualization_msgs::Marker::POINTS;
388 marker_p.action = visualization_msgs::Marker::ADD;
389 marker_p.pose.position.x = 0;
390 marker_p.pose.position.y = 0;
391 marker_p.pose.position.z = 0;
392 marker_p.pose.orientation.x = 0.0;
393 marker_p.pose.orientation.y = 0.0;
394 marker_p.pose.orientation.z = 0.0;
395 marker_p.pose.orientation.w = 1.0;
396 marker_p.scale.x = 0.01;
397 marker_p.scale.y = 0.01;
398 marker_p.scale.z = 0.1;
399 marker_p.color.a = 1.0;
400 marker_p.color.r = 0.0;
401 marker_p.color.g = 0.0;
402 marker_p.color.b = 1.0;
404 for(
int i;
i < inliers->indices.size();
i++) {
405 geometry_msgs::Point pp;
406 pcl::PointNormal pt =
cloud->points[inliers->indices[
i]];
407 Eigen::Vector3f ep(pt.x, pt.y, pt.z);
413 marker_p.points.push_back(pp);
417 visualization_msgs::MarkerArray arry;
418 arry.markers.push_back(
marker);
419 arry.markers.push_back(marker_p);
420 pub_debug_marker.
publish( arry );
428 parameters.support_check_vertex_neighbor_threshold);
429 DEBUG_PRINT(
"[FS state] (skip_cropping) projection state " << support_state );
436 parameters.support_check_vertex_neighbor_threshold);
437 DEBUG_PRINT(
"[FS state] (!skip_cropping) projection state " << support_state );
449 else if ((inliers->indices.size() / (
double)indices->indices.size()) <
parameters.plane_estimation_min_ratio_of_inliers ) {
450 DEBUG_PRINT(
"[FS state] ratio of inliers " << (inliers->indices.size() / (
double)indices->indices.size()) );
468 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud,
469 pcl::KdTreeFLANN<pcl::PointNormal>&
tree,
470 pcl::PointIndices::Ptr inliers,
471 const int foot_x_sampling_num,
472 const int foot_y_sampling_num,
473 const double vertex_threshold)
478 const Eigen::Vector3f ux = Eigen::Vector3f::UnitX();
479 const Eigen::Vector3f uy = Eigen::Vector3f::UnitY();
480 const Eigen::Affine3f new_origin =
pose *
481 Eigen::Translation3f(- ux *
dimensions_[0] / 2.0) *
483 const Eigen::Affine3f inv_pose = new_origin.inverse();
485 bool occupiedp[foot_x_sampling_num][foot_y_sampling_num];
487 for (
size_t i = 0;
i < foot_x_sampling_num;
i++) {
488 for (
size_t j = 0; j < foot_y_sampling_num; j++) {
489 occupiedp[
i][j] =
false;
493 for (
size_t i = 0;
i < inliers->indices.size();
i++) {
494 pcl::PointNormal pp =
cloud->points[inliers->indices[
i]];
495 const Eigen::Vector3f
p = pp.getVector3fMap();
496 const Eigen::Vector3f local_p = inv_pose *
p;
497 const int nx = floor(local_p[0] /
dx);
498 const int ny = floor(local_p[1] /
dy);
500 if (0 <= nx && nx < foot_x_sampling_num &&
501 0 <= ny && ny < foot_y_sampling_num &&
502 std::abs(local_p[2]) < vertex_threshold) {
503 occupiedp[nx][ny] =
true;
506 for (
size_t i = 0;
i < foot_x_sampling_num;
i++) {
507 for (
size_t j = 0; j < foot_y_sampling_num; j++) {
508 if (!occupiedp[
i][j]) {
518 pcl::PointNormal pa, pb, pc, pd,
p;
519 pa.getVector3fMap() =
a;
520 pb.getVector3fMap() =
b;
521 pc.getVector3fMap() =
c;
522 pd.getVector3fMap() =
d;
523 p.getVector3fMap() = Eigen::Vector3f(
pose.translation());
524 std::vector<int> kdl_indices;
525 std::vector<float> kdl_distances;
526 if (
tree.radiusSearch(
p, vertex_threshold, kdl_indices, kdl_distances, 1) > 0 &&
527 tree.radiusSearch(pa, vertex_threshold, kdl_indices, kdl_distances, 1) > 0 &&
528 tree.radiusSearch(pb, vertex_threshold, kdl_indices, kdl_distances, 1) > 0 &&
529 tree.radiusSearch(pc, vertex_threshold, kdl_indices, kdl_distances, 1) > 0 &&
530 tree.radiusSearch(pd, vertex_threshold, kdl_indices, kdl_distances, 1) > 0) {
540 const Eigen::Affine3f& pose,
541 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud,
542 pcl::KdTreeFLANN<pcl::PointNormal>&
tree,
543 pcl::PointIndices::Ptr inliers,
544 const int foot_x_sampling_num,
545 const int foot_y_sampling_num,
546 const double vertex_threshold)
548 const Eigen::Vector3f ux = Eigen::Vector3f::UnitX();
549 const Eigen::Vector3f uy = Eigen::Vector3f::UnitY();
554 pcl::PointNormal pa, pb, pc, pd,
p;
555 pa.getVector3fMap() =
a;
556 pb.getVector3fMap() =
b;
557 pc.getVector3fMap() =
c;
558 pd.getVector3fMap() =
d;
559 p.getVector3fMap() = Eigen::Vector3f(
pose.translation());
560 std::vector<int> kdl_indices;
561 std::vector<float> kdl_distances;
562 size_t success_count = 0;
564 if (
tree.radiusSearch(
p, vertex_threshold, kdl_indices, kdl_distances, 1) > 0) {
567 if (
tree.radiusSearch(pa, vertex_threshold, kdl_indices, kdl_distances, 1) > 0) {
570 if (
tree.radiusSearch(pb, vertex_threshold, kdl_indices, kdl_distances, 1) > 0) {
573 if (
tree.radiusSearch(pc, vertex_threshold, kdl_indices, kdl_distances, 1) > 0) {
576 if (
tree.radiusSearch(pd, vertex_threshold, kdl_indices, kdl_distances, 1) > 0) {
579 if (success_count == 5) {
593 const Eigen::Vector3f& size,
596 Eigen::Affine3f
pose;
597 Eigen::Vector3f offset (
f.offset.x,
f.offset.y,
f.offset.z);
599 pose *= Eigen::Translation3f(offset);
607 Eigen::Affine3f first =
pose_;
608 Eigen::Affine3f second = other.
pose_;
609 Eigen::Translation3f
pos((Eigen::Vector3f(first.translation()) + Eigen::Vector3f(second.translation())) / 2.0);
610 Eigen::Quaternionf
rot = Eigen::Quaternionf(first.matrix().block<3, 3>(0, 0)).slerp(0.5, Eigen::Quaternionf(second.matrix().block<3, 3>(0, 0)));