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 #define BOOST_PARAMETER_MAX_ARITY 7
00037
00038 #include "jsk_pcl_ros/environment_plane_modeling.h"
00039 #include <pcl/filters/extract_indices.h>
00040 #include <pcl/common/distances.h>
00041 #include <pcl_conversions/pcl_conversions.h>
00042 #include <pcl/filters/project_inliers.h>
00043 #include <pcl/surface/convex_hull.h>
00044 #include <pcl/filters/project_inliers.h>
00045 #include <jsk_recognition_msgs/SparseOccupancyGridArray.h>
00046
00047 #include <pluginlib/class_list_macros.h>
00048 #include <geometry_msgs/PoseArray.h>
00049 #include "jsk_pcl_ros/geo_util.h"
00050 #include "jsk_pcl_ros/grid_map.h"
00051 #include <jsk_topic_tools/rosparam_utils.h>
00052 namespace jsk_pcl_ros
00053 {
00054 void EnvironmentPlaneModeling::onInit()
00055 {
00056 DiagnosticNodelet::onInit();
00057
00058 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00059 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00060 boost::bind (&EnvironmentPlaneModeling::configCallback, this, _1, _2);
00061 srv_->setCallback (f);
00062
00063 pnh_->param("complete_footprint_region", complete_footprint_region_, false);
00064 pub_debug_magnified_polygons_
00065 = pnh_->advertise<jsk_recognition_msgs::PolygonArray>(
00066 "debug/magnified_polygons", 1);
00067 pub_debug_convex_point_cloud_
00068 = pnh_->advertise<sensor_msgs::PointCloud2>(
00069 "debug/convex_cloud", 1);
00070 pub_debug_raw_grid_map_
00071 = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
00072 "debug/raw_grid_map", 1);
00073 pub_debug_noeroded_grid_map_
00074 = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
00075 "debug/noeroded_grid_map", 1);
00076 pub_debug_plane_coords_
00077 = pnh_->advertise<geometry_msgs::PoseArray>(
00078 "debug/plane_poses", 1);
00079 pub_debug_magnified_plane_coords_
00080 = pnh_->advertise<geometry_msgs::PoseArray>(
00081 "debug/magnified_plane_poses", 1);
00082 pub_grid_map_
00083 = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
00084 "output", 1, true);
00085 pub_snapped_move_base_simple_goal_ = pnh_->advertise<geometry_msgs::PoseStamped>(
00086 "/footstep_simple/goal", 1);
00087 pub_non_plane_indices_ = pnh_->advertise<PCLIndicesMsg>(
00088 "output/non_plane_indices", 1);
00089 if (complete_footprint_region_) {
00090 tf_listener_ = TfListenerSingleton::getInstance();
00091
00092 sub_leg_bbox_ = pnh_->subscribe(
00093 "input/leg_bounding_box", 1,
00094 &EnvironmentPlaneModeling::boundingBoxCallback, this);
00095
00096 jsk_topic_tools::readVectorParameter(
00097 *pnh_, "footprint_frames", footprint_frames_);
00098
00099 }
00100 sub_move_base_simple_goal_ = pnh_->subscribe(
00101 "/move_base_simple/goal", 1,
00102 &EnvironmentPlaneModeling::moveBaseSimpleGoalCallback, this);
00103 sub_cloud_.subscribe(*pnh_, "input", 1);
00104 sub_full_cloud_.subscribe(*pnh_, "input/full_cloud", 1);
00105 sub_indices_.subscribe(*pnh_, "input/indices", 1);
00106 sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
00107 sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
00108 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00109 sync_->connectInput(sub_cloud_, sub_full_cloud_, sub_polygons_,
00110 sub_coefficients_, sub_indices_);
00111 sync_->registerCallback(
00112 boost::bind(&EnvironmentPlaneModeling::inputCallback,
00113 this, _1, _2, _3, _4, _5));
00114 }
00115
00116 void EnvironmentPlaneModeling::configCallback(Config &config, uint32_t level)
00117 {
00118 boost::mutex::scoped_lock lock(mutex_);
00119 magnify_distance_ = config.magnify_distance;
00120 distance_threshold_ = config.distance_threshold;
00121 normal_threshold_ = config.normal_threshold;
00122 resolution_ = config.resolution;
00123 morphological_filter_size_ = config.morphological_filter_size;
00124 erode_filter_size_ = config.erode_filter_size;
00125 footprint_plane_angular_threshold_ = config.footprint_plane_angular_threshold;
00126 footprint_plane_distance_threshold_ = config.footprint_plane_distance_threshold;
00127 }
00128
00129 void EnvironmentPlaneModeling::printInputData(
00130 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00131 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
00132 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00133 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00134 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
00135 {
00136 JSK_NODELET_INFO("Input data --");
00137 JSK_NODELET_INFO(" Number of points -- %d", cloud_msg->width * cloud_msg->height);
00138 JSK_NODELET_INFO(" Number of full points -- %d", full_cloud_msg->width * full_cloud_msg->height);
00139 JSK_NODELET_INFO(" Number of clusters: -- %lu", indices_msg->cluster_indices.size());
00140 JSK_NODELET_INFO(" Frame Id: %s", cloud_msg->header.frame_id.c_str());
00141 JSK_NODELET_INFO(" Complete Footprint: %s", complete_footprint_region_? "true": "false");
00142 }
00143
00144 bool EnvironmentPlaneModeling::isValidFrameIds(
00145 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00146 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
00147 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00148 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00149 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
00150 {
00151 std::string frame_id = cloud_msg->header.frame_id;
00152 if (full_cloud_msg->header.frame_id != frame_id) {
00153 return false;
00154 }
00155 if (polygon_msg->header.frame_id != frame_id) {
00156 return false;
00157 }
00158 for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
00159 if (polygon_msg->polygons[i].header.frame_id != frame_id) {
00160 return false;
00161 }
00162 }
00163 if (coefficients_msg->header.frame_id != frame_id) {
00164 return false;
00165 }
00166 for (size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
00167 if (coefficients_msg->coefficients[i].header.frame_id != frame_id) {
00168 return false;
00169 }
00170 }
00171 if (indices_msg->header.frame_id != frame_id) {
00172 return false;
00173 }
00174 for (size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
00175 if (indices_msg->cluster_indices[i].header.frame_id != frame_id) {
00176 return false;
00177 }
00178 }
00179 return true;
00180 }
00181
00182 void EnvironmentPlaneModeling::moveBaseSimpleGoalCallback(
00183 const geometry_msgs::PoseStamped::ConstPtr& msg)
00184 {
00185 boost::mutex::scoped_lock lock(mutex_);
00186 if (latest_grid_maps_.size() == 0) {
00187 JSK_NODELET_WARN("not yet grid maps are available");
00188 return;
00189 }
00190
00191 tf::StampedTransform tf_transform = lookupTransformWithDuration(
00192 tf_listener_,
00193 latest_global_header_.frame_id,
00194 msg->header.frame_id,
00195 latest_global_header_.stamp,
00196 ros::Duration(1.0));
00197
00198 Eigen::Affine3f local_coords, transform;
00199 tf::poseMsgToEigen(msg->pose, local_coords);
00200 tf::transformTFToEigen(tf_transform, transform);
00201 Eigen::Affine3f global_coords = transform * local_coords;
00202
00203
00204 double max_height = - DBL_MAX;
00205 GridPlane::Ptr max_grid;
00206 Eigen::Affine3f max_projected_coords = Eigen::Affine3f::Identity();
00207 for (size_t i = 0; i < latest_grid_maps_.size(); i++) {
00208 GridPlane::Ptr target_grid = latest_grid_maps_[i];
00209 Eigen::Affine3f projected_coords;
00210 target_grid->getPolygon()->projectOnPlane(global_coords, projected_coords);
00211 Eigen::Vector3f projected_point(projected_coords.translation());
00212 if (target_grid->isOccupiedGlobal(projected_point)) {
00213 double height = projected_point[2];
00214 if (max_height < height) {
00215 max_height = height;
00216 max_grid = target_grid;
00217 max_projected_coords = projected_coords;
00218 }
00219 }
00220 }
00221 if (max_grid) {
00222
00223 geometry_msgs::PoseStamped ros_coords;
00224 tf::poseEigenToMsg(max_projected_coords, ros_coords.pose);
00225 ros_coords.header.stamp = msg->header.stamp;
00226 ros_coords.header.frame_id = latest_global_header_.frame_id;
00227 pub_snapped_move_base_simple_goal_.publish(ros_coords);
00228 }
00229 else {
00230 JSK_NODELET_ERROR("Failed to find corresponding grid");
00231 }
00232 }
00233
00234 void EnvironmentPlaneModeling::boundingBoxCallback(
00235 const jsk_recognition_msgs::BoundingBox::ConstPtr& box)
00236 {
00237 boost::mutex::scoped_lock lock(mutex_);
00238 latest_leg_bounding_box_ = box;
00239 }
00240
00241 void EnvironmentPlaneModeling::inputCallback(
00242 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00243 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
00244 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00245 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00246 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
00247 {
00248 boost::mutex::scoped_lock lock(mutex_);
00249 try {
00250
00251 if (!isValidFrameIds(cloud_msg, full_cloud_msg, polygon_msg, coefficients_msg, indices_msg)) {
00252 JSK_NODELET_FATAL("frame_id is not correct");
00253 return;
00254 }
00255 if (complete_footprint_region_ && !latest_leg_bounding_box_) {
00256 JSK_NODELET_ERROR("Bounding Box for Footprint is not yet ready");
00257 return;
00258 }
00259
00260 printInputData(cloud_msg, full_cloud_msg, polygon_msg, coefficients_msg, indices_msg);
00261
00262
00263 pcl::PointCloud<pcl::PointNormal>::Ptr cloud (new pcl::PointCloud<pcl::PointNormal>);
00264 pcl::fromROSMsg(*cloud_msg, *cloud);
00265
00266 pcl::PointCloud<pcl::PointNormal>::Ptr full_cloud (new pcl::PointCloud<pcl::PointNormal>);
00267 pcl::fromROSMsg(*full_cloud_msg, *full_cloud);
00268
00269
00270 std::vector<ConvexPolygon::Ptr> convexes = convertToConvexPolygons(cloud, indices_msg, coefficients_msg);
00271
00272 std::vector<ConvexPolygon::Ptr> magnified_convexes = magnifyConvexes(convexes);
00273 publishConvexPolygonsBoundaries(pub_debug_convex_point_cloud_, cloud_msg->header, magnified_convexes);
00274
00275 publishConvexPolygons(pub_debug_magnified_polygons_, cloud_msg->header, magnified_convexes);
00276
00277 {
00278 geometry_msgs::PoseArray pose_array;
00279 pose_array.header = cloud_msg->header;
00280 for (size_t i = 0; i < convexes.size(); i++) {
00281 Eigen::Affine3f pose = convexes[i]->coordinates();
00282 geometry_msgs::Pose ros_pose;
00283 tf::poseEigenToMsg(pose, ros_pose);
00284 pose_array.poses.push_back(ros_pose);
00285 }
00286 pub_debug_plane_coords_.publish(pose_array);
00287 }
00288 {
00289 geometry_msgs::PoseArray pose_array;
00290 pose_array.header = cloud_msg->header;
00291 for (size_t i = 0; i < magnified_convexes.size(); i++) {
00292 Eigen::Affine3f pose = magnified_convexes[i]->coordinates();
00293 geometry_msgs::Pose ros_pose;
00294 tf::poseEigenToMsg(pose, ros_pose);
00295 pose_array.poses.push_back(ros_pose);
00296 }
00297 pub_debug_magnified_plane_coords_.publish(pose_array);
00298 }
00299
00300
00301 std::set<int> non_plane_indices;
00302 std::vector<GridPlane::Ptr> raw_grid_planes = buildGridPlanes(full_cloud, magnified_convexes, non_plane_indices);
00303
00304 publishGridMaps(pub_debug_raw_grid_map_, cloud_msg->header, raw_grid_planes);
00305 PCLIndicesMsg ros_non_plane_indices;
00306 ros_non_plane_indices.indices = std::vector<int>(non_plane_indices.begin(),
00307 non_plane_indices.end());
00308 ros_non_plane_indices.header = cloud_msg->header;
00309 pub_non_plane_indices_.publish(ros_non_plane_indices);
00310 std::vector<GridPlane::Ptr> morphological_filtered_grid_planes
00311 = morphologicalFiltering(raw_grid_planes);
00312
00313 publishGridMaps(pub_debug_noeroded_grid_map_, cloud_msg->header,
00314 morphological_filtered_grid_planes);
00315
00316 std::vector<GridPlane::Ptr> eroded_grid_planes
00317 = erodeFiltering(morphological_filtered_grid_planes);
00318 std::vector<GridPlane::Ptr> result_grid_planes;
00319
00320 if (complete_footprint_region_) {
00321 result_grid_planes
00322 = completeFootprintRegion(cloud_msg->header,
00323 eroded_grid_planes);
00324 }
00325 else {
00326 result_grid_planes = eroded_grid_planes;
00327 }
00328
00329 publishGridMaps(pub_grid_map_, cloud_msg->header,
00330 result_grid_planes);
00331
00332 latest_global_header_ = cloud_msg->header;
00333 latest_grid_maps_ = result_grid_planes;
00334 }
00335 catch (tf2::TransformException& e) {
00336 JSK_NODELET_ERROR("Failed to lookup transformation: %s", e.what());
00337 }
00338 }
00339
00340 std::vector<GridPlane::Ptr> EnvironmentPlaneModeling::erodeFiltering(
00341 std::vector<GridPlane::Ptr>& grid_maps)
00342 {
00343 std::vector<GridPlane::Ptr> ret;
00344 for (size_t i = 0; i < grid_maps.size(); i++) {
00345 GridPlane::Ptr eroded_grid_map = grid_maps[i]->erode(erode_filter_size_);
00346 ret.push_back(eroded_grid_map);
00347 }
00348 return ret;
00349 }
00350
00351 int EnvironmentPlaneModeling::lookupGroundPlaneForFootprint(
00352 const Eigen::Affine3f& pose, const std::vector<GridPlane::Ptr>& grid_maps)
00353 {
00354 Eigen::Vector3f foot_z = (pose.rotation() * Eigen::Vector3f::UnitZ()).normalized();
00355 Eigen::Vector3f foot_p(pose.translation());
00356 double min_distance = DBL_MAX;
00357 int min_index = -1;
00358 for (size_t i = 0; i < grid_maps.size(); i++) {
00359 GridPlane::Ptr grid = grid_maps[i];
00360 Eigen::Vector3f normal = grid->getPolygon()->getNormal();
00361 if (std::abs(normal.dot(foot_z)) > cos(footprint_plane_angular_threshold_)) {
00362
00363 if (grid->getPolygon()->distanceToPoint(foot_p) < footprint_plane_distance_threshold_) {
00364 Eigen::Vector3f foot_center(pose.translation());
00365 if (!grid->isOccupiedGlobal(foot_center)) {
00366
00367 double d = grid->getPolygon()->distanceFromVertices(foot_center);
00368 if (d < min_distance) {
00369 min_distance = d;
00370 min_index = i;
00371 }
00372 }
00373 else {
00374 JSK_NODELET_INFO("Foot print is already occupied");
00375 return -1;
00376 }
00377
00378 }
00379 }
00380 }
00381 return min_index;
00382 }
00383
00384 int EnvironmentPlaneModeling::lookupGroundPlaneForFootprint(
00385 const std::string& footprint_frame, const std_msgs::Header& header,
00386 const std::vector<GridPlane::Ptr>& grid_maps)
00387 {
00388
00389 tf::StampedTransform transform
00390 = lookupTransformWithDuration(tf_listener_,
00391 header.frame_id, footprint_frame,
00392 header.stamp,
00393 ros::Duration(1.0));
00394 Eigen::Affine3f eigen_transform;
00395 tf::transformTFToEigen(transform, eigen_transform);
00396
00397 return lookupGroundPlaneForFootprint(eigen_transform, grid_maps);
00398 }
00399
00400 GridPlane::Ptr EnvironmentPlaneModeling::completeGridMapByBoundingBox(
00401 const jsk_recognition_msgs::BoundingBox::ConstPtr& box,
00402 const std_msgs::Header& header,
00403 GridPlane::Ptr grid_map)
00404 {
00405
00406 tf::StampedTransform tf_transform = lookupTransformWithDuration(
00407 tf_listener_,
00408 header.frame_id,
00409 box->header.frame_id,
00410 header.stamp,
00411 ros::Duration(1.0));
00412 Eigen::Affine3f transform;
00413 tf::transformTFToEigen(tf_transform, transform);
00414 Eigen::Affine3f local_pose;
00415 tf::poseMsgToEigen(box->pose, local_pose);
00416 Eigen::Affine3f global_pose = transform * local_pose;
00417 std::vector<double> dimensions;
00418 dimensions.push_back(box->dimensions.x);
00419 dimensions.push_back(box->dimensions.y);
00420 dimensions.push_back(box->dimensions.z);
00421 Cube::Ptr cube (new Cube(Eigen::Vector3f(global_pose.translation()),
00422 Eigen::Quaternionf(global_pose.rotation()),
00423 dimensions));
00424 GridPlane::Ptr completed_grid_map = grid_map->clone();
00425 completed_grid_map->fillCellsFromCube(*cube);
00426 return completed_grid_map;
00427 }
00428
00429 std::vector<GridPlane::Ptr> EnvironmentPlaneModeling::completeFootprintRegion(
00430 const std_msgs::Header& header, std::vector<GridPlane::Ptr>& grid_maps)
00431 {
00432 try {
00433 std::vector<GridPlane::Ptr> completed_grid_maps(grid_maps.size());
00434 std::set<int> ground_plane_indices;
00435 for (size_t i = 0; i < footprint_frames_.size(); i++) {
00436 std::string footprint_frame = footprint_frames_[i];
00437 int grid_index = lookupGroundPlaneForFootprint(
00438 footprint_frame, header, grid_maps);
00439 if (grid_index != -1) {
00440 JSK_NODELET_INFO("Found ground plane for %s: %d", footprint_frame.c_str(), grid_index);
00441 ground_plane_indices.insert(grid_index);
00442 }
00443 else {
00444 JSK_NODELET_WARN("Cannnot find ground plane for %s: %d", footprint_frame.c_str(), grid_index);
00445 }
00446 }
00447 for (size_t i = 0; i < grid_maps.size(); i++) {
00448 if (ground_plane_indices.find(i) == ground_plane_indices.end()) {
00449
00450 completed_grid_maps[i] = grid_maps[i];
00451 }
00452 else {
00453 completed_grid_maps[i] = completeGridMapByBoundingBox(
00454 latest_leg_bounding_box_, header, grid_maps[i]);
00455 }
00456 }
00457 return completed_grid_maps;
00458 }
00459 catch (tf2::TransformException& e) {
00460 JSK_NODELET_FATAL("Failed to lookup transformation: %s", e.what());
00461 return std::vector<GridPlane::Ptr>();
00462 }
00463 }
00464
00465 std::vector<GridPlane::Ptr> EnvironmentPlaneModeling::morphologicalFiltering(
00466 std::vector<GridPlane::Ptr>& raw_grid_maps)
00467 {
00468 std::vector<GridPlane::Ptr> ret;
00469 for (size_t i = 0; i < raw_grid_maps.size(); i++) {
00470 GridPlane::Ptr dilated_grid_map = raw_grid_maps[i]->dilate(morphological_filter_size_);
00471 GridPlane::Ptr eroded_grid_map = dilated_grid_map->erode(morphological_filter_size_);
00472 ret.push_back(eroded_grid_map);
00473 }
00474 return ret;
00475 }
00476
00477
00478 void EnvironmentPlaneModeling::publishConvexPolygonsBoundaries(
00479 ros::Publisher& pub,
00480 const std_msgs::Header& header,
00481 std::vector<ConvexPolygon::Ptr>& convexes)
00482 {
00483 pcl::PointCloud<pcl::PointXYZ>::Ptr
00484 boundary_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00485 for (size_t i = 0; i < convexes.size(); i++) {
00486 pcl::PointCloud<pcl::PointXYZ>::Ptr
00487 one_boundary_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00488 convexes[i]->boundariesToPointCloud<pcl::PointXYZ>(
00489 *one_boundary_cloud);
00490 *boundary_cloud = *boundary_cloud + *one_boundary_cloud;
00491 }
00492 sensor_msgs::PointCloud2 ros_cloud;
00493 pcl::toROSMsg(*boundary_cloud, ros_cloud);
00494 ros_cloud.header = header;
00495 pub.publish(ros_cloud);
00496 }
00497
00498 void EnvironmentPlaneModeling::publishGridMaps(
00499 ros::Publisher& pub,
00500 const std_msgs::Header& header,
00501 std::vector<GridPlane::Ptr>& grids)
00502 {
00503 jsk_recognition_msgs::SimpleOccupancyGridArray grid_array;
00504 grid_array.header = header;
00505 for (size_t i = 0; i < grids.size(); i++) {
00506 jsk_recognition_msgs::SimpleOccupancyGrid grid = grids[i]->toROSMsg();
00507 grid.header = header;
00508 grid_array.grids.push_back(grid);
00509 }
00510 pub.publish(grid_array);
00511 }
00512
00513
00514 std::vector<GridPlane::Ptr> EnvironmentPlaneModeling::buildGridPlanes(
00515 pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
00516 std::vector<ConvexPolygon::Ptr> convexes,
00517 std::set<int>& non_plane_indices)
00518 {
00519 std::vector<GridPlane::Ptr> ret(convexes.size());
00520
00521 for (size_t i = 0; i < convexes.size(); i++) {
00522 GridPlane::Ptr grid(new GridPlane(convexes[i], resolution_));
00523 size_t num = grid->fillCellsFromPointCloud(cloud, distance_threshold_,
00524 normal_threshold_,
00525 non_plane_indices);
00526 JSK_NODELET_INFO("%lu plane contains %lu points",
00527 i, num);
00528 ret[i] = grid;
00529 }
00530 return ret;
00531 }
00532
00533
00534
00535 void EnvironmentPlaneModeling::publishConvexPolygons(
00536 ros::Publisher& pub,
00537 const std_msgs::Header& header,
00538 std::vector<ConvexPolygon::Ptr>& convexes)
00539 {
00540 jsk_recognition_msgs::PolygonArray polygon_array;
00541 polygon_array.header = header;
00542 for (size_t i = 0; i < convexes.size(); i++) {
00543 geometry_msgs::PolygonStamped polygon;
00544 polygon.polygon = convexes[i]->toROSMsg();
00545 polygon.header = header;
00546 polygon_array.polygons.push_back(polygon);
00547 }
00548 pub.publish(polygon_array);
00549 }
00550
00551 std::vector<ConvexPolygon::Ptr> EnvironmentPlaneModeling::magnifyConvexes(
00552 std::vector<ConvexPolygon::Ptr>& convexes)
00553 {
00554 std::vector<ConvexPolygon::Ptr> ret(0);
00555 for (size_t i = 0; i < convexes.size(); i++) {
00556 ConvexPolygon::Ptr vertices_convex(new ConvexPolygon(convexes[i]->getVertices()));
00557 ConvexPolygon::Ptr new_convex = vertices_convex->magnifyByDistance(magnify_distance_);
00558
00559 if (new_convex->getNormalFromVertices().dot(Eigen::Vector3f::UnitZ()) < 0) {
00560 new_convex = boost::make_shared<ConvexPolygon>(new_convex->flipConvex());
00561 }
00562 ret.push_back(new_convex);
00563 }
00564 return ret;
00565 }
00566
00567 std::vector<ConvexPolygon::Ptr> EnvironmentPlaneModeling::convertToConvexPolygons(
00568 const pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
00569 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00570 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00571 {
00572 std::vector<ConvexPolygon::Ptr> convexes(0);
00573 for (size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
00574 pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00575 inliers->indices = indices_msg->cluster_indices[i].indices;
00576 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
00577 coefficients->values = coefficients_msg->coefficients[i].values;
00578 ConvexPolygon::Ptr convex
00579 = convexFromCoefficientsAndInliers<pcl::PointNormal>(
00580 cloud, inliers, coefficients);
00581 convexes.push_back(convex);
00582 }
00583
00584 return convexes;
00585 }
00586
00587 }
00588
00589 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::EnvironmentPlaneModeling,
00590 nodelet::Nodelet);