footstep_planner_walls.cpp
Go to the documentation of this file.
1 /*
2  * A footstep planner for humanoid robots
3  *
4  * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
5  * http://www.ros.org/wiki/footstep_planner
6  *
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, version 3.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <http://www.gnu.org/licenses/>.
19  */
20 
21 #include <ros/ros.h>
23 #include <nav_msgs/OccupancyGrid.h>
24 #include <gridmap_2d/GridMap2D.h>
25 
26 
27 using namespace footstep_planner;
30 
38 public:
40  {
41  ros::NodeHandle privateNh("~");
42  // params:
43  privateNh.param("footstep_wall_dist", ivFootstepWallDist, 0.15);
44 
45  // provide callbacks to interact with the footstep planner:
46  ivGridMapSub = ivNh.subscribe<nav_msgs::OccupancyGrid>("map", 1, &FootstepPlannerWallsNode::mapCallback, this);
47  ivGoalPoseSub = ivNh.subscribe<geometry_msgs::PoseStamped>("goal", 1, &FootstepPlanner::goalPoseCallback, &ivFootstepPlanner);
48  ivStartPoseSub = ivNh.subscribe<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1, &FootstepPlanner::startPoseCallback, &ivFootstepPlanner);
49 
50  // service:
51  ivFootstepPlanService = ivNh.advertiseService("plan_footsteps", &FootstepPlanner::planService, &ivFootstepPlanner);
52  }
53 
55 
56  void mapCallback(const nav_msgs::OccupancyGridConstPtr& occupancyMap)
57  {
58  ROS_INFO("Obstacle map received, now waiting for wall map.");
59  ivGridMap = GridMap2DPtr(new GridMap2D(occupancyMap));
60  // don't set wall => wait for wall map!
61  //ivFootstepPlanner.setMap(ivGridMap);
62 
63  // now subscribe to walls, so that they arrive in order:
64  ivWallMapSub = ivNh.subscribe<nav_msgs::OccupancyGrid>(
65  "map_walls", 1, &FootstepPlannerWallsNode::wallMapCallback, this);
66  }
67 
68  void wallMapCallback(const nav_msgs::OccupancyGridConstPtr& occupancyMap)
69  {
70  ROS_INFO("Wall / Obstacle map received");
71  assert(ivGridMap);
72  GridMap2DPtr wallMap(new GridMap2D(occupancyMap));
73 
74  GridMap2DPtr enlargedWallMap(new GridMap2D(occupancyMap));
75  cv::Mat binaryMap = (enlargedWallMap->distanceMap() > ivFootstepWallDist);
76  bitwise_and(binaryMap, ivGridMap->binaryMap(), binaryMap);
77 
78  enlargedWallMap->setMap(binaryMap);
79 
80  ivFootstepPlanner.updateMap(enlargedWallMap);
81  }
82 
83 protected:
88  ros::Subscriber ivGoalPoseSub, ivGridMapSub, ivWallMapSub, ivStartPoseSub, ivRobotPoseSub;
90 };
91 
92 
93 int main(int argc, char** argv)
94 {
95  ros::init(argc, argv, "footstep_planner");
96 
98 
99  ros::spin();
100 
101  return 0;
102 }
Wrapper class for FootstepPlanner, providing callbacks for the node functionality. This node additionally sets wall regions for the footstep planner, from a dedicated map callback.
ros::ServiceServer ivFootstepPlanService
int main(int argc, char **argv)
footstep_planner::FootstepPlanner ivFootstepPlanner
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void goalPoseCallback(const geometry_msgs::PoseStampedConstPtr &goal_pose)
Callback to set the goal pose as a robot pose centered between two feet. If the start pose has been s...
A class to control the interaction between ROS and the footstep planner.
boost::shared_ptr< GridMap2D > GridMap2DPtr
ROSCPP_DECL void spin(Spinner &spinner)
void startPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &start_pose)
Callback to set the start pose as a robot pose centered between two feet. If the goal pose has been s...
void mapCallback(const nav_msgs::OccupancyGridConstPtr &occupancyMap)
void wallMapCallback(const nav_msgs::OccupancyGridConstPtr &occupancyMap)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool planService(humanoid_nav_msgs::PlanFootsteps::Request &req, humanoid_nav_msgs::PlanFootsteps::Response &resp)
Service handle to plan footsteps.


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:24