#include <costmap_client.h>
Public Member Functions | |
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. | |
costmap_2d::Costmap2D * | getCostmap () |
Return a pointer to the "master" costmap which receives updates from all the layers. | |
const costmap_2d::Costmap2D * | getCostmap () const |
Return a pointer to the "master" costmap which receives updates from all the layers. | |
const std::string & | getGlobalFrameID () const |
Returns the global frame of the costmap. | |
bool | getRobotPose (tf::Stamped< tf::Pose > &global_pose) const |
Get the pose of the robot in the global frame of the costmap. | |
Protected Member Functions | |
void | updateFullMap (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
void | updatePartialMap (const map_msgs::OccupancyGridUpdate::ConstPtr &msg) |
Protected Attributes | |
costmap_2d::Costmap2D | costmap_ |
std::string | global_frame_ |
The global frame for the costmap. | |
std::string | robot_base_frame_ |
The frame_id of the robot base. | |
const tf::TransformListener *const | tf_ |
Used for transforming point clouds. | |
double | transform_tolerance_ |
timeout before transform errors | |
Private Attributes | |
ros::Subscriber | costmap_sub_ |
ros::Subscriber | costmap_updates_sub_ |
Definition at line 49 of file costmap_client.h.
explore::Costmap2DClient::Costmap2DClient | ( | ros::NodeHandle & | param_nh, |
ros::NodeHandle & | subscription_nh, | ||
const tf::TransformListener * | tf_listener | ||
) |
Contructs client and start listening.
Constructor will block until first map update is received and map is ready to use, also will block before trasformation robot_base_frame <-> global_frame is available.
param_nh | node hadle to retrieve parameters from |
subscription_nh | node hadle where topics will be subscribed |
tf_listener | Will be used for transformation of robot pose. |
Definition at line 49 of file costmap_client.cpp.
const std::string& explore::Costmap2DClient::getBaseFrameID | ( | ) | const [inline] |
Returns the local frame of the costmap.
Definition at line 106 of file costmap_client.h.
costmap_2d::Costmap2D* explore::Costmap2DClient::getCostmap | ( | ) | [inline] |
Return a pointer to the "master" costmap which receives updates from all the layers.
This pointer will stay the same for the lifetime of Costmap2DClient object.
Definition at line 78 of file costmap_client.h.
const costmap_2d::Costmap2D* explore::Costmap2DClient::getCostmap | ( | ) | const [inline] |
Return a pointer to the "master" costmap which receives updates from all the layers.
This pointer will stay the same for the lifetime of Costmap2DClient object.
Definition at line 88 of file costmap_client.h.
const std::string& explore::Costmap2DClient::getGlobalFrameID | ( | ) | const [inline] |
Returns the global frame of the costmap.
Definition at line 97 of file costmap_client.h.
bool explore::Costmap2DClient::getRobotPose | ( | tf::Stamped< tf::Pose > & | global_pose | ) | const |
Get the pose of the robot in the global frame of the costmap.
global_pose | Will be set to the pose of the robot in the global frame of the costmap |
Definition at line 179 of file costmap_client.cpp.
void explore::Costmap2DClient::updateFullMap | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) | [protected] |
Definition at line 102 of file costmap_client.cpp.
void explore::Costmap2DClient::updatePartialMap | ( | const map_msgs::OccupancyGridUpdate::ConstPtr & | msg | ) | [protected] |
Definition at line 131 of file costmap_client.cpp.
Definition at line 115 of file costmap_client.h.
Definition at line 124 of file costmap_client.h.
Definition at line 125 of file costmap_client.h.
std::string explore::Costmap2DClient::global_frame_ [protected] |
The global frame for the costmap.
Definition at line 118 of file costmap_client.h.
std::string explore::Costmap2DClient::robot_base_frame_ [protected] |
The frame_id of the robot base.
Definition at line 119 of file costmap_client.h.
const tf::TransformListener* const explore::Costmap2DClient::tf_ [protected] |
Used for transforming point clouds.
Definition at line 117 of file costmap_client.h.
double explore::Costmap2DClient::transform_tolerance_ [protected] |
timeout before transform errors
Definition at line 120 of file costmap_client.h.