23 #include <nav_msgs/OccupancyGrid.h> 43 privateNh.
param(
"footstep_wall_dist", ivFootstepWallDist, 0.15);
56 void mapCallback(
const nav_msgs::OccupancyGridConstPtr& occupancyMap)
58 ROS_INFO(
"Obstacle map received, now waiting for wall map.");
64 ivWallMapSub = ivNh.subscribe<nav_msgs::OccupancyGrid>(
70 ROS_INFO(
"Wall / Obstacle map received");
75 cv::Mat binaryMap = (enlargedWallMap->distanceMap() > ivFootstepWallDist);
76 bitwise_and(binaryMap, ivGridMap->binaryMap(), binaryMap);
78 enlargedWallMap->setMap(binaryMap);
80 ivFootstepPlanner.updateMap(enlargedWallMap);
93 int main(
int argc,
char** argv)
95 ros::init(argc, argv,
"footstep_planner");
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< GridMap2D > GridMap2DPtr
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const