Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include <ros/ros.h>
00022 #include <footstep_planner/FootstepPlanner.h>
00023 #include <nav_msgs/OccupancyGrid.h>
00024 #include <gridmap_2d/GridMap2D.h>
00025
00026
00027 using namespace footstep_planner;
00028 using gridmap_2d::GridMap2D;
00029 using gridmap_2d::GridMap2DPtr;
00030
00037 class FootstepPlannerWallsNode {
00038 public:
00039 FootstepPlannerWallsNode()
00040 {
00041 ros::NodeHandle privateNh("~");
00042
00043 privateNh.param("footstep_wall_dist", ivFootstepWallDist, 0.15);
00044
00045
00046 ivGridMapSub = ivNh.subscribe<nav_msgs::OccupancyGrid>("map", 1, &FootstepPlannerWallsNode::mapCallback, this);
00047 ivGoalPoseSub = ivNh.subscribe<geometry_msgs::PoseStamped>("goal", 1, &FootstepPlanner::goalPoseCallback, &ivFootstepPlanner);
00048 ivStartPoseSub = ivNh.subscribe<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1, &FootstepPlanner::startPoseCallback, &ivFootstepPlanner);
00049
00050
00051 ivFootstepPlanService = ivNh.advertiseService("plan_footsteps", &FootstepPlanner::planService, &ivFootstepPlanner);
00052 }
00053
00054 virtual ~FootstepPlannerWallsNode(){}
00055
00056 void mapCallback(const nav_msgs::OccupancyGridConstPtr& occupancyMap)
00057 {
00058 ROS_INFO("Obstacle map received, now waiting for wall map.");
00059 ivGridMap = GridMap2DPtr(new GridMap2D(occupancyMap));
00060
00061
00062
00063
00064 ivWallMapSub = ivNh.subscribe<nav_msgs::OccupancyGrid>(
00065 "map_walls", 1, &FootstepPlannerWallsNode::wallMapCallback, this);
00066 }
00067
00068 void wallMapCallback(const nav_msgs::OccupancyGridConstPtr& occupancyMap)
00069 {
00070 ROS_INFO("Wall / Obstacle map received");
00071 assert(ivGridMap);
00072 GridMap2DPtr wallMap(new GridMap2D(occupancyMap));
00073
00074 GridMap2DPtr enlargedWallMap(new GridMap2D(occupancyMap));
00075 cv::Mat binaryMap = (enlargedWallMap->distanceMap() > ivFootstepWallDist);
00076 bitwise_and(binaryMap, ivGridMap->binaryMap(), binaryMap);
00077
00078 enlargedWallMap->setMap(binaryMap);
00079
00080 ivFootstepPlanner.updateMap(enlargedWallMap);
00081 }
00082
00083 protected:
00084 ros::NodeHandle ivNh;
00085 footstep_planner::FootstepPlanner ivFootstepPlanner;
00086 GridMap2DPtr ivGridMap;
00087 double ivFootstepWallDist;
00088 ros::Subscriber ivGoalPoseSub, ivGridMapSub, ivWallMapSub, ivStartPoseSub, ivRobotPoseSub;
00089 ros::ServiceServer ivFootstepPlanService;
00090 };
00091
00092
00093 int main(int argc, char** argv)
00094 {
00095 ros::init(argc, argv, "footstep_planner");
00096
00097 FootstepPlannerWallsNode planner;
00098
00099 ros::spin();
00100
00101 return 0;
00102 }