37 #ifndef COSTMAP_CLIENT_ 38 #define COSTMAP_CLIENT_ 41 #include <geometry_msgs/Pose.h> 42 #include <map_msgs/OccupancyGridUpdate.h> 43 #include <nav_msgs/OccupancyGrid.h> 112 void updateFullMap(
const nav_msgs::OccupancyGrid::ConstPtr& msg);
double transform_tolerance_
timeout before transform errors
geometry_msgs::Pose getRobotPose() const
Get the pose of the robot in the global frame of the costmap.
costmap_2d::Costmap2D * getCostmap()
Return a pointer to the "master" costmap which receives updates from all the layers.
void updatePartialMap(const map_msgs::OccupancyGridUpdate::ConstPtr &msg)
ros::Subscriber costmap_updates_sub_
void updateFullMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
const std::string & getGlobalFrameID() const
Returns the global frame of the costmap.
const costmap_2d::Costmap2D * getCostmap() const
Return a pointer to the "master" costmap which receives updates from all the layers.
ros::Subscriber costmap_sub_
std::string robot_base_frame_
The frame_id of the robot base.
costmap_2d::Costmap2D costmap_
Costmap2DClient(ros::NodeHandle ¶m_nh, ros::NodeHandle &subscription_nh, const tf::TransformListener *tf_listener)
Contructs client and start listening.
const std::string & getBaseFrameID() const
Returns the local frame of the costmap.
const tf::TransformListener *const tf_
Used for transforming point clouds.
std::string global_frame_
The global frame for the costmap.