table_approaches.cpp
Go to the documentation of this file.
00001 #include <numeric>
00002 #include <ros/ros.h>
00003 #include <algorithm>
00004 
00005 #include "sensor_msgs/PointCloud2.h"
00006 #include <pcl/features/normal_3d.h>
00007 #include <pcl/kdtree/kdtree_flann.h>
00008 #include <pcl/point_types.h>
00009 #include <pcl_ros/point_cloud.h>
00010 #include <pcl/point_cloud.h>
00011 #include <pcl/features/principal_curvatures.h>
00012 #include <pcl/segmentation/extract_clusters.h>
00013 #include <pcl/filters/passthrough.h>
00014 #include <pcl/sample_consensus/method_types.h>
00015 #include <pcl/sample_consensus/model_types.h>
00016 #include <pcl/segmentation/sac_segmentation.h>
00017 #include <pcl/surface/mls.h>
00018 #include <pcl/surface/convex_hull.h>
00019 #include <pcl/filters/project_inliers.h>
00020 #include <pcl/filters/voxel_grid.h>
00021 
00022 #include <tf/transform_listener.h>
00023 #include "pcl_ros/transforms.h"
00024 #include <boost/make_shared.hpp>
00025 #include <boost/thread/mutex.hpp>
00026 #include <cv_bridge/cv_bridge.h>
00027 #include <opencv/cv.h>
00028 #include <opencv2/imgproc/imgproc.hpp>
00029 #include <opencv2/highgui/highgui.hpp>
00030 #include <image_transport/image_transport.h>
00031 #include <sensor_msgs/image_encodings.h>
00032 #include <geometry_msgs/PoseArray.h>
00033 #include <geometry_msgs/PolygonStamped.h>
00034 #include <geometry_msgs/Point.h>
00035 #include <visualization_msgs/Marker.h>
00036 #include <hrl_table_detect/GetTableApproaches.h>
00037 #include <LinearMath/btMatrix3x3.h>
00038 #include <LinearMath/btQuaternion.h>
00039 #include <std_srvs/Empty.h>
00040 
00041 #include <costmap_2d/costmap_2d_ros.h>
00042 #include <costmap_2d/costmap_2d.h>
00043 #include <base_local_planner/world_model.h>
00044 #include <base_local_planner/costmap_model.h>
00045 #include <base_local_planner/trajectory_planner_ros.h>
00046 #include <pluginlib/class_loader.h>
00047 #include <nav_core/base_local_planner.h>
00048 #include <nav_core/base_global_planner.h>
00049 
00050 #define DIST(x1,y1,x2,y2) (std::sqrt((x1-x2)*(x1-x2)+(y1-y2)*(y1-y2)))
00051 
00052 using namespace sensor_msgs;
00053 using namespace std;
00054 namespace hrl_table_detect {
00055     
00056     class TableApproaches {
00057         public:
00058             ros::NodeHandle nh;
00059             ros::ServiceServer table_appr_srv;
00060             ros::Publisher valid_pub, close_pub, invalid_pub, approach_pub;
00061             tf::TransformListener tf_listener;
00062             costmap_2d::Costmap2DROS* costmap_ros;
00063             base_local_planner::TrajectoryPlannerROS traj_planner;
00064             vector<geometry_msgs::Point> footprint_model;
00065             base_local_planner::CostmapModel* world_model;
00066             costmap_2d::Costmap2D costmap;
00067 
00068             TableApproaches();
00069             ~TableApproaches();
00070             void onInit();
00071             bool tableApprCallback(hrl_table_detect::GetTableApproaches::Request& req, 
00072                                    hrl_table_detect::GetTableApproaches::Response& resp);
00073             double footprintCost(const Eigen::Vector3f& pos, double scale);
00074     };
00075 
00076     TableApproaches::TableApproaches()  {
00077     }
00078 
00079     TableApproaches::~TableApproaches()  {
00080         delete costmap_ros;
00081     }
00082 
00083     void TableApproaches::onInit() {
00084         table_appr_srv = nh.advertiseService("/table_detection/detect_table_approaches", &TableApproaches::tableApprCallback, this);
00085         costmap_ros = new costmap_2d::Costmap2DROS("table_costmap", tf_listener);
00086         traj_planner.initialize("table_traj_planner", &tf_listener, costmap_ros);
00087         footprint_model = costmap_ros->getRobotFootprint();
00088         valid_pub = nh.advertise<geometry_msgs::PoseArray>("valid_poses", 1);
00089         invalid_pub = nh.advertise<geometry_msgs::PoseArray>("invalid_poses", 1);
00090         approach_pub = nh.advertise<geometry_msgs::PoseArray>("approach_poses", 1);
00091         close_pub = nh.advertise<geometry_msgs::PoseArray>("close_poses", 1);
00092         
00093         //costmap_ros->start();
00094         ros::Duration(1.0).sleep();
00095     }
00096 
00097     bool pose_dist_comp(geometry_msgs::Pose& p1, geometry_msgs::Pose& p2, geometry_msgs::Point& app_pt) {
00098         return DIST(p1.position.x, p1.position.y, app_pt.x, app_pt.y) < DIST(p2.position.x, p2.position.y, app_pt.x, app_pt.y);
00099     }
00100 
00101     bool pose_dist_thresh(geometry_msgs::Pose pose, geometry_msgs::Point pt, double thresh) {
00102         ROS_INFO("dist: %f, thresh: %f, val %d", DIST(pose.position.x, pose.position.y, pt.x, pt.y), thresh, DIST(pose.position.x, pose.position.y, pt.x, pt.y) < thresh);
00103         return DIST(pose.position.x, pose.position.y, pt.x, pt.y) < thresh;
00104     }
00105 
00106     bool TableApproaches::tableApprCallback(hrl_table_detect::GetTableApproaches::Request& req,
00107                                    hrl_table_detect::GetTableApproaches::Response& resp) {
00108         double pose_step = 0.01, start_dist = 0.25, max_dist = 1.2, min_cost = 250;
00109         double close_thresh = 0.10;
00110 
00111 
00112         // TODO should this be transformed?
00113         std::vector<geometry_msgs::Point> table_poly = req.table.points;
00114         geometry_msgs::PointStamped approach_pt = req.approach_pt;
00115         /*
00116         double xsize = 1.0, ysize = 1.0, xoff = 2.5, yoff = 0.0;
00117         geometry_msgs::Point pt; 
00118         pt.x = xoff-xsize/2; pt.y = yoff-ysize/2;
00119         table_poly.push_back(pt);
00120         pt.x = xoff+xsize/2; pt.y = yoff-ysize/2;
00121         table_poly.push_back(pt);
00122         pt.x = xoff+xsize/2; pt.y = yoff+ysize/2;
00123         table_poly.push_back(pt);
00124         pt.x = xoff-xsize/2; pt.y = yoff+ysize/2;
00125         table_poly.push_back(pt);
00126         geometry_msgs::PointStamped approach_pt;
00127         approach_pt.header.frame_id = "/base_link";
00128         approach_pt.header.stamp = ros::Time::now();
00129         approach_pt.point.x = 2.2; approach_pt.point.y = 0.3; 
00130         */
00131 
00132         costmap_ros->getCostmapCopy(costmap);
00133         world_model = new base_local_planner::CostmapModel(costmap);
00134         geometry_msgs::PoseArray valid_locs;
00135         valid_locs.header.frame_id = "/base_link";
00136         valid_locs.header.stamp = ros::Time::now();
00137         geometry_msgs::PoseArray invalid_locs;
00138         invalid_locs.header.frame_id = "/base_link";
00139         invalid_locs.header.stamp = ros::Time::now();
00140         geometry_msgs::PoseArray close_locs;
00141         close_locs.header.frame_id = "/base_link";
00142         close_locs.header.stamp = ros::Time::now();
00143         for(int i=0;i<4000;i++) {
00144             geometry_msgs::PoseStamped cpose, odom_pose;
00145             cpose.header.frame_id = "/base_link";
00146             cpose.header.stamp = ros::Time(0);
00147             cpose.pose.position.x = (rand()%8000) / 1000.0 -4 ; 
00148             cpose.pose.position.y = (rand()%8000) / 1000.0 - 4;
00149             double rot = (rand()%10000) / 10000.0 * 2 * 3.14;
00150             cpose.pose.orientation = tf::createQuaternionMsgFromYaw(rot);
00151             cout << cpose.pose.orientation.z << " " << cpose.pose.orientation.w << " " << rot << endl;
00152             tf_listener.transformPose("/odom_combined", cpose, odom_pose);
00153             //uint32_t x, y;
00154             //if(!costmap.worldToMap(odom_pose.pose.position.x, odom_pose.pose.position.y, x, y))
00155                 //continue;
00156             Eigen::Vector3f pos(odom_pose.pose.position.x, odom_pose.pose.position.y, tf::getYaw(odom_pose.pose.orientation));
00157             //cout << x << ", " << y << ":" << curpt.point.x << "," << curpt.point.y << "$";
00158             //cout << double(costmap.getCost(x,y)) << endl;
00159             double foot_cost = footprintCost(pos, 1);
00160             if(foot_cost == 0) 
00161                 valid_locs.poses.push_back(cpose.pose);
00162             else if(foot_cost != -1)
00163                 close_locs.poses.push_back(cpose.pose);
00164             else 
00165                 invalid_locs.poses.push_back(cpose.pose);
00166             cout << foot_cost << endl;
00167         }
00168         cout << costmap_ros->getRobotFootprint().size() << endl;
00169         valid_pub.publish(valid_locs);
00170         invalid_pub.publish(invalid_locs);
00171         close_pub.publish(close_locs);
00172 
00173         geometry_msgs::PoseArray dense_table_poses;
00174         dense_table_poses.header.frame_id = "/base_link";
00175         dense_table_poses.header.stamp = ros::Time::now();
00176         uint32_t i2;
00177         for(uint32_t i=0;i<table_poly.size();i++) {
00178             i2 = i+1;
00179             if(i2 == table_poly.size())
00180                 i2 = 0;
00181             double diffx = table_poly[i2].x-table_poly[i].x;
00182             double diffy = table_poly[i2].y-table_poly[i].y;
00183             double len = std::sqrt(diffx*diffx + diffy*diffy);
00184             double ang = std::atan2(diffy, diffx) - 3.14/2;
00185             double incx = std::cos(ang)*0.01, incy = std::sin(ang)*0.01;
00186             for(double t=0;t<len;t+=pose_step) {
00187                 double polyx = table_poly[i].x + t*diffx;
00188                 double polyy = table_poly[i].y + t*diffy;
00189                 geometry_msgs::PoseStamped test_pose, odom_test_pose;
00190                 bool found_pose = false;
00191                 for(int k=start_dist/0.01;k<max_dist/0.01;k++) {
00192                     test_pose.header.frame_id = "/base_link";
00193                     test_pose.header.stamp = ros::Time(0);
00194                     test_pose.pose.position.x = polyx + incx*k;
00195                     test_pose.pose.position.y = polyy + incy*k;
00196                     test_pose.pose.orientation = tf::createQuaternionMsgFromYaw(ang+3.14);
00197                     tf_listener.transformPose("/odom_combined", test_pose, odom_test_pose);
00198                     Eigen::Vector3f pos(odom_test_pose.pose.position.x, 
00199                                         odom_test_pose.pose.position.y, 
00200                                         tf::getYaw(odom_test_pose.pose.orientation));
00201                     double foot_cost = footprintCost(pos, 1.0);
00202                     // found a valid pose
00203                     if(foot_cost >= 0 && foot_cost <= min_cost) {
00204                         found_pose = true;
00205                         break;
00206                     }
00207                     uint32_t mapx, mapy;
00208                     // break if we go outside the grid
00209                     if(!costmap.worldToMap(odom_test_pose.pose.position.x, 
00210                                            odom_test_pose.pose.position.y, mapx, mapy))
00211                         break;
00212                     double occ_map = double(costmap.getCost(mapx, mapy));
00213                     // break if we come across and obstacle
00214                     if(occ_map == costmap_2d::LETHAL_OBSTACLE ||
00215                        occ_map == costmap_2d::NO_INFORMATION)
00216                         break;
00217                 }
00218                 if(found_pose)
00219                     dense_table_poses.poses.push_back(test_pose.pose);
00220             }
00221         }
00222         ROS_INFO("POLY: %d, denseposes: %d", table_poly.size(), dense_table_poses.poses.size());
00223 
00224         // downsample and sort dense pose possibilties by distance to
00225         // approach point and thresholded distance to each other
00226         geometry_msgs::PoseArray downsampled_table_poses;
00227         boost::function<bool(geometry_msgs::Pose&, geometry_msgs::Pose&)> dist_comp
00228                           = boost::bind(&pose_dist_comp, _1, _2, approach_pt.point);
00229         while(ros::ok() && !dense_table_poses.poses.empty()) {
00230             // add the closest valid pose to the approach location on the table
00231             geometry_msgs::Pose new_pose = *std::min_element(
00232                         dense_table_poses.poses.begin(), dense_table_poses.poses.end(), 
00233                         dist_comp);
00234             downsampled_table_poses.poses.push_back(new_pose);
00235             // remove all poses in the dense sampling which are close to
00236             // the newest added pose
00237             boost::function<bool(geometry_msgs::Pose)> rem_thresh
00238                           = boost::bind(&pose_dist_thresh, _1, new_pose.position, 
00239                                         close_thresh);
00240             dense_table_poses.poses.erase(std::remove_if(
00241                                           dense_table_poses.poses.begin(), 
00242                                           dense_table_poses.poses.end(),
00243                                           rem_thresh),
00244                                           dense_table_poses.poses.end());
00245             ROS_INFO("denseposes: %d", dense_table_poses.poses.size());
00246         }
00247         downsampled_table_poses.header.frame_id = "/base_link";
00248         downsampled_table_poses.header.stamp = ros::Time::now();
00249         approach_pub.publish(downsampled_table_poses);
00250         resp.approach_poses = downsampled_table_poses;
00251         ROS_INFO("POLY: %d, poses: %d", table_poly.size(), downsampled_table_poses.poses.size());
00252 
00253         delete world_model;
00254         return true;
00255     }
00256 
00257     double TableApproaches::footprintCost(const Eigen::Vector3f& pos, double scale){
00258         double cos_th = cos(pos[2]);
00259         double sin_th = sin(pos[2]);
00260 
00261         std::vector<geometry_msgs::Point> scaled_oriented_footprint;
00262         for(unsigned int i  = 0; i < footprint_model.size(); ++i){
00263             geometry_msgs::Point new_pt;
00264             new_pt.x = pos[0] + (scale * footprint_model[i].x * cos_th - scale * footprint_model[i].y * sin_th);
00265             new_pt.y = pos[1] + (scale * footprint_model[i].x * sin_th + scale * footprint_model[i].y * cos_th);
00266             scaled_oriented_footprint.push_back(new_pt);
00267         }
00268 
00269         geometry_msgs::Point robot_position;
00270         robot_position.x = pos[0];
00271         robot_position.y = pos[1];
00272 
00273         //check if the footprint is legal
00274         double footprint_cost = world_model->footprintCost(robot_position, scaled_oriented_footprint, costmap.getInscribedRadius(), costmap.getCircumscribedRadius());
00275 
00276         return footprint_cost;
00277     }
00278 };
00279 
00280 using namespace hrl_table_detect;
00281 
00282 int main(int argc, char **argv)
00283 {
00284     ros::init(argc, argv, "table_approaches");
00285     TableApproaches ta;
00286     ta.onInit();
00287     ros::spin();
00288     return 0;
00289 }
00290 
00291 
00292 


hrl_table_detect
Author(s): kelsey
autogenerated on Wed Nov 27 2013 12:15:26