36 #define BOOST_PARAMETER_MAX_ARITY 7 39 #include <pcl/filters/extract_indices.h> 40 #include <pcl/common/distances.h> 42 #include <pcl/filters/project_inliers.h> 43 #include <pcl/surface/convex_hull.h> 44 #include <pcl/filters/project_inliers.h> 45 #include <jsk_recognition_msgs/SparseOccupancyGridArray.h> 48 #include <geometry_msgs/PoseArray.h> 56 DiagnosticNodelet::onInit();
58 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
59 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
61 srv_->setCallback (f);
65 = pnh_->advertise<jsk_recognition_msgs::PolygonArray>(
66 "debug/magnified_polygons", 1);
68 = pnh_->advertise<sensor_msgs::PointCloud2>(
69 "debug/convex_cloud", 1);
71 = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
72 "debug/raw_grid_map", 1);
74 = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
75 "debug/noeroded_grid_map", 1);
77 = pnh_->advertise<geometry_msgs::PoseArray>(
78 "debug/plane_poses", 1);
80 = pnh_->advertise<geometry_msgs::PoseArray>(
81 "debug/magnified_plane_poses", 1);
83 = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
86 "/footstep_simple/goal", 1);
88 "output/non_plane_indices", 1);
93 "input/leg_bounding_box", 1,
101 "/move_base_simple/goal", 1,
108 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
111 sync_->registerCallback(
113 this, _1, _2, _3, _4, _5));
132 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
133 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
134 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
135 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
136 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
139 NODELET_INFO(
" Number of points -- %d", cloud_msg->width * cloud_msg->height);
140 NODELET_INFO(
" Number of full points -- %d", full_cloud_msg->width * full_cloud_msg->height);
141 NODELET_INFO(
" Number of clusters: -- %lu", indices_msg->cluster_indices.size());
142 NODELET_INFO(
" Frame Id: %s", cloud_msg->header.frame_id.c_str());
147 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
148 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
149 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
150 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
151 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
153 std::string
frame_id = cloud_msg->header.frame_id;
154 if (full_cloud_msg->header.frame_id != frame_id) {
157 if (polygon_msg->header.frame_id != frame_id) {
160 for (
size_t i = 0; i < polygon_msg->polygons.size(); i++) {
161 if (polygon_msg->polygons[i].header.frame_id != frame_id) {
165 if (coefficients_msg->header.frame_id != frame_id) {
168 for (
size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
169 if (coefficients_msg->coefficients[i].header.frame_id != frame_id) {
173 if (indices_msg->header.frame_id != frame_id) {
176 for (
size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
177 if (indices_msg->cluster_indices[i].header.frame_id != frame_id) {
185 const geometry_msgs::PoseStamped::ConstPtr&
msg)
196 msg->header.frame_id,
200 Eigen::Affine3f local_coords, transform;
203 Eigen::Affine3f global_coords = transform * local_coords;
206 double max_height = - DBL_MAX;
208 Eigen::Affine3f max_projected_coords = Eigen::Affine3f::Identity();
211 Eigen::Affine3f projected_coords;
212 target_grid->getPolygon()->projectOnPlane(global_coords, projected_coords);
213 Eigen::Vector3f projected_point(projected_coords.translation());
214 if (target_grid->isOccupiedGlobal(projected_point)) {
215 double height = projected_point[2];
216 if (max_height < height) {
218 max_grid = target_grid;
219 max_projected_coords = projected_coords;
225 geometry_msgs::PoseStamped ros_coords;
227 ros_coords.header.stamp = msg->header.stamp;
237 const jsk_recognition_msgs::BoundingBox::ConstPtr&
box)
244 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
245 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
246 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
247 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
248 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
253 if (!
isValidFrameIds(cloud_msg, full_cloud_msg, polygon_msg, coefficients_msg, indices_msg)) {
258 NODELET_ERROR(
"Bounding Box for Footprint is not yet ready");
262 printInputData(cloud_msg, full_cloud_msg, polygon_msg, coefficients_msg, indices_msg);
265 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud (
new pcl::PointCloud<pcl::PointNormal>);
268 pcl::PointCloud<pcl::PointNormal>::Ptr full_cloud (
new pcl::PointCloud<pcl::PointNormal>);
272 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes =
convertToConvexPolygons(cloud, indices_msg, coefficients_msg);
274 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> magnified_convexes =
magnifyConvexes(convexes);
280 geometry_msgs::PoseArray pose_array;
281 pose_array.header = cloud_msg->header;
282 for (
size_t i = 0; i < convexes.size(); i++) {
283 Eigen::Affine3f
pose = convexes[i]->coordinates();
284 geometry_msgs::Pose ros_pose;
286 pose_array.poses.push_back(ros_pose);
291 geometry_msgs::PoseArray pose_array;
292 pose_array.header = cloud_msg->header;
293 for (
size_t i = 0; i < magnified_convexes.size(); i++) {
294 Eigen::Affine3f
pose = magnified_convexes[i]->coordinates();
295 geometry_msgs::Pose ros_pose;
297 pose_array.poses.push_back(ros_pose);
303 std::set<int> non_plane_indices;
304 std::vector<GridPlane::Ptr> raw_grid_planes =
buildGridPlanes(full_cloud, magnified_convexes, non_plane_indices);
308 ros_non_plane_indices.indices = std::vector<int>(non_plane_indices.begin(),
309 non_plane_indices.end());
310 ros_non_plane_indices.header = cloud_msg->header;
312 std::vector<GridPlane::Ptr> morphological_filtered_grid_planes
316 morphological_filtered_grid_planes);
318 std::vector<GridPlane::Ptr> eroded_grid_planes
320 std::vector<GridPlane::Ptr> result_grid_planes;
328 result_grid_planes = eroded_grid_planes;
338 NODELET_ERROR(
"Failed to lookup transformation: %s", e.what());
343 std::vector<GridPlane::Ptr>& grid_maps)
345 std::vector<GridPlane::Ptr> ret;
346 for (
size_t i = 0; i < grid_maps.size(); i++) {
348 ret.push_back(eroded_grid_map);
354 const Eigen::Affine3f& pose,
const std::vector<GridPlane::Ptr>& grid_maps)
356 Eigen::Vector3f foot_z = (pose.rotation() * Eigen::Vector3f::UnitZ()).
normalized();
357 Eigen::Vector3f foot_p(pose.translation());
358 double min_distance = DBL_MAX;
360 for (
size_t i = 0; i < grid_maps.size(); i++) {
362 Eigen::Vector3f normal = grid->getPolygon()->getNormal();
366 Eigen::Vector3f foot_center(pose.translation());
367 if (!grid->isOccupiedGlobal(foot_center)) {
369 double d = grid->getPolygon()->distanceFromVertices(foot_center);
370 if (d < min_distance) {
387 const std::string& footprint_frame,
const std_msgs::Header&
header,
388 const std::vector<GridPlane::Ptr>& grid_maps)
393 header.frame_id, footprint_frame,
396 Eigen::Affine3f eigen_transform;
403 const jsk_recognition_msgs::BoundingBox::ConstPtr&
box,
404 const std_msgs::Header&
header,
411 box->header.frame_id,
414 Eigen::Affine3f transform;
416 Eigen::Affine3f local_pose;
418 Eigen::Affine3f global_pose = transform * local_pose;
419 std::vector<double> dimensions;
420 dimensions.push_back(box->dimensions.x);
421 dimensions.push_back(box->dimensions.y);
422 dimensions.push_back(box->dimensions.z);
424 Eigen::Quaternionf(global_pose.rotation()),
427 completed_grid_map->fillCellsFromCube(*
cube);
428 return completed_grid_map;
432 const std_msgs::Header&
header, std::vector<GridPlane::Ptr>& grid_maps)
435 std::vector<GridPlane::Ptr> completed_grid_maps(grid_maps.size());
436 std::set<int> ground_plane_indices;
440 footprint_frame, header, grid_maps);
441 if (grid_index != -1) {
442 NODELET_INFO(
"Found ground plane for %s: %d", footprint_frame.c_str(), grid_index);
443 ground_plane_indices.insert(grid_index);
446 NODELET_WARN(
"Cannnot find ground plane for %s: %d", footprint_frame.c_str(), grid_index);
449 for (
size_t i = 0; i < grid_maps.size(); i++) {
450 if (ground_plane_indices.find(i) == ground_plane_indices.end()) {
452 completed_grid_maps[i] = grid_maps[i];
459 return completed_grid_maps;
462 NODELET_FATAL(
"Failed to lookup transformation: %s", e.what());
463 return std::vector<GridPlane::Ptr>();
468 std::vector<GridPlane::Ptr>& raw_grid_maps)
470 std::vector<GridPlane::Ptr> ret;
471 for (
size_t i = 0; i < raw_grid_maps.size(); i++) {
474 ret.push_back(eroded_grid_map);
482 const std_msgs::Header&
header,
483 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
485 pcl::PointCloud<pcl::PointXYZ>::Ptr
486 boundary_cloud (
new pcl::PointCloud<pcl::PointXYZ>);
487 for (
size_t i = 0; i < convexes.size(); i++) {
488 pcl::PointCloud<pcl::PointXYZ>::Ptr
489 one_boundary_cloud (
new pcl::PointCloud<pcl::PointXYZ>);
490 convexes[i]->boundariesToPointCloud<pcl::PointXYZ>(
491 *one_boundary_cloud);
492 *boundary_cloud = *boundary_cloud + *one_boundary_cloud;
494 sensor_msgs::PointCloud2 ros_cloud;
496 ros_cloud.header =
header;
502 const std_msgs::Header&
header,
503 std::vector<GridPlane::Ptr>& grids)
505 jsk_recognition_msgs::SimpleOccupancyGridArray grid_array;
506 grid_array.header =
header;
507 for (
size_t i = 0; i < grids.size(); i++) {
508 jsk_recognition_msgs::SimpleOccupancyGrid
grid = grids[i]->toROSMsg();
510 grid_array.grids.push_back(grid);
517 pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
518 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes,
519 std::set<int>& non_plane_indices)
521 std::vector<GridPlane::Ptr> ret(convexes.size());
523 for (
size_t i = 0; i < convexes.size(); i++) {
539 const std_msgs::Header&
header,
540 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
542 jsk_recognition_msgs::PolygonArray polygon_array;
543 polygon_array.header =
header;
544 for (
size_t i = 0; i < convexes.size(); i++) {
545 geometry_msgs::PolygonStamped
polygon;
546 polygon.polygon = convexes[i]->toROSMsg();
548 polygon_array.polygons.push_back(polygon);
554 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
556 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> ret(0);
557 for (
size_t i = 0; i < convexes.size(); i++) {
561 if (new_convex->getNormalFromVertices().dot(Eigen::Vector3f::UnitZ()) < 0) {
562 new_convex = boost::make_shared<jsk_recognition_utils::ConvexPolygon>(new_convex->flipConvex());
564 ret.push_back(new_convex);
570 const pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
571 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
572 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
574 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes(0);
575 for (
size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
576 pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
577 inliers->indices = indices_msg->cluster_indices[i].indices;
578 pcl::ModelCoefficients::Ptr
coefficients (
new pcl::ModelCoefficients);
579 coefficients->values = coefficients_msg->coefficients[i].values;
581 = jsk_recognition_utils::convexFromCoefficientsAndInliers<pcl::PointNormal>(
582 cloud, inliers, coefficients);
583 convexes.push_back(convex);
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > magnifyConvexes(std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Magnify jsk_recognition_utils::ConvexPolygons according to maginify_distance_ parameter.
virtual void configCallback(Config &config, uint32_t level)
Callback method of dynamic reconfigure.
virtual GridPlane::Ptr completeGridMapByBoundingBox(const jsk_recognition_msgs::BoundingBox::ConstPtr &box, const std_msgs::Header &header, GridPlane::Ptr grid_map)
#define NODELET_ERROR(...)
ros::Subscriber sub_leg_bbox_
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::EnvironmentPlaneModeling, nodelet::Nodelet)
virtual std::vector< GridPlane::Ptr > completeFootprintRegion(const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grid_maps)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convertToConvexPolygons(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
ros::Publisher pub_debug_raw_grid_map_
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
ros::Publisher pub_grid_map_
ros::Publisher pub_debug_plane_coords_
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
virtual std::vector< GridPlane::Ptr > erodeFiltering(std::vector< GridPlane::Ptr > &grid_maps)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
bool complete_footprint_region_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
ros::Publisher pub_debug_magnified_plane_coords_
virtual std::vector< GridPlane::Ptr > morphologicalFiltering(std::vector< GridPlane::Ptr > &raw_grid_maps)
virtual void boundingBoxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box_array)
virtual void publishConvexPolygonsBoundaries(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
ros::Publisher pub_debug_magnified_polygons_
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
main callback function
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_full_cloud_
TFSIMD_FORCE_INLINE Vector3 normalized() const
Nodelet implementation of jsk_pcl/EnvironmentPlaneModeling.
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
virtual void moveBaseSimpleGoalCallback(const geometry_msgs::PoseStamped::ConstPtr &msg)
ros::Publisher pub_debug_noeroded_grid_map_
double footprint_plane_distance_threshold_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std_msgs::Header latest_global_header_
std::vector< std::string > footprint_frames_
EnvironmentPlaneModelingConfig Config
tf::TransformListener * tf_listener_
virtual std::vector< GridPlane::Ptr > buildGridPlanes(pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convexes, std::set< int > &non_plane_indices)
make GridPlane from jsk_recognition_utils::ConvexPolygon and PointCloud
ros::Subscriber sub_move_base_simple_goal_
double distance_threshold_
virtual void printInputData(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
virtual bool isValidFrameIds(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
ros::Publisher pub_non_plane_indices_
virtual void publishConvexPolygons(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Publish array of jsk_recognition_utils::ConvexPolygon::Ptr by using specified publisher.
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
double footprint_plane_angular_threshold_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define NODELET_INFO(...)
ros::Publisher pub_debug_convex_point_cloud_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
ros::Publisher pub_snapped_move_base_simple_goal_
virtual int lookupGroundPlaneForFootprint(const std::string &footprint_frame_id, const std_msgs::Header &header, const std::vector< GridPlane::Ptr > &grid_maps)
static tf::TransformListener * getInstance()
std::vector< GridPlane::Ptr > latest_grid_maps_
#define NODELET_FATAL(...)
pcl::PointIndices PCLIndicesMsg
Cube cube(Eigen::Vector3f(1, 0, 0), Eigen::Quaternionf(0.108755, 0.088921, 0.108755, 0.984092), Eigen::Vector3f(0.3, 0.3, 0.3))
int morphological_filter_size_
virtual void publishGridMaps(ros::Publisher &pub, const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grids)
Publish array of GridPlane::Ptr by using specified publisher.
jsk_recognition_msgs::BoundingBox::ConstPtr latest_leg_bounding_box_