#include <costmap_client.h>
Definition at line 50 of file costmap_client.h.
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.
- Parameters
-
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 50 of file costmap_client.cpp.
const std::string& explore::Costmap2DClient::getBaseFrameID |
( |
| ) |
const |
|
inline |
Returns the local frame of the costmap.
- Returns
- The local frame of the costmap
Definition at line 106 of file costmap_client.h.
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 77 of file costmap_client.h.
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.
- Returns
- The global frame of the costmap
Definition at line 97 of file costmap_client.h.
Get the pose of the robot in the global frame of the costmap.
- Returns
- pose of the robot in the global frame of the costmap
Definition at line 190 of file costmap_client.cpp.
void explore::Costmap2DClient::updateFullMap |
( |
const nav_msgs::OccupancyGrid::ConstPtr & |
msg | ) |
|
|
protected |
void explore::Costmap2DClient::updatePartialMap |
( |
const map_msgs::OccupancyGridUpdate::ConstPtr & |
msg | ) |
|
|
protected |
std::string explore::Costmap2DClient::global_frame_ |
|
protected |
std::string explore::Costmap2DClient::robot_base_frame_ |
|
protected |
double explore::Costmap2DClient::transform_tolerance_ |
|
protected |
The documentation for this class was generated from the following files: