Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
explore::Costmap2DClient Class Reference

#include <costmap_client.h>

Public Member Functions

 Costmap2DClient (ros::NodeHandle &param_nh, ros::NodeHandle &subscription_nh, const tf::TransformListener *tf_listener)
 Contructs client and start listening. More...
 
const std::string & getBaseFrameID () const
 Returns the local frame of the costmap. More...
 
costmap_2d::Costmap2DgetCostmap ()
 Return a pointer to the "master" costmap which receives updates from all the layers. More...
 
const costmap_2d::Costmap2DgetCostmap () const
 Return a pointer to the "master" costmap which receives updates from all the layers. More...
 
const std::string & getGlobalFrameID () const
 Returns the global frame of the costmap. More...
 
geometry_msgs::Pose getRobotPose () const
 Get the pose of the robot in the global frame of the costmap. More...
 

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. More...
 
std::string robot_base_frame_
 The frame_id of the robot base. More...
 
const tf::TransformListener *const tf_
 Used for transforming point clouds. More...
 
double transform_tolerance_
 timeout before transform errors More...
 

Private Attributes

ros::Subscriber costmap_sub_
 
ros::Subscriber costmap_updates_sub_
 

Detailed Description

Definition at line 50 of file costmap_client.h.

Constructor & Destructor Documentation

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.

Parameters
param_nhnode hadle to retrieve parameters from
subscription_nhnode hadle where topics will be subscribed
tf_listenerWill be used for transformation of robot pose.

Definition at line 50 of file costmap_client.cpp.

Member Function Documentation

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.

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 77 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.

Returns
The global frame of the costmap

Definition at line 97 of file costmap_client.h.

geometry_msgs::Pose explore::Costmap2DClient::getRobotPose ( ) const

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

Definition at line 115 of file costmap_client.cpp.

void explore::Costmap2DClient::updatePartialMap ( const map_msgs::OccupancyGridUpdate::ConstPtr &  msg)
protected

Definition at line 145 of file costmap_client.cpp.

Member Data Documentation

costmap_2d::Costmap2D explore::Costmap2DClient::costmap_
protected

Definition at line 115 of file costmap_client.h.

ros::Subscriber explore::Costmap2DClient::costmap_sub_
private

Definition at line 125 of file costmap_client.h.

ros::Subscriber explore::Costmap2DClient::costmap_updates_sub_
private

Definition at line 126 of file costmap_client.h.

std::string explore::Costmap2DClient::global_frame_
protected

The global frame for the costmap.

Definition at line 119 of file costmap_client.h.

std::string explore::Costmap2DClient::robot_base_frame_
protected

The frame_id of the robot base.

Definition at line 120 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 121 of file costmap_client.h.


The documentation for this class was generated from the following files:


explore
Author(s): Jiri Horner
autogenerated on Mon Jun 10 2019 13:56:49