Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
costmap_2d::Costmap2DPublisher Class Reference

A tool to periodically publish visualization data from a Costmap2D. More...

#include <costmap_2d_publisher.h>

Public Member Functions

bool active ()
 Check if the publisher is active. More...
 
 Costmap2DPublisher (ros::NodeHandle *ros_node, Costmap2D *costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap=false)
 Constructor for the Costmap2DPublisher. More...
 
void publishCostmap ()
 Publishes the visualization data over ROS. More...
 
void updateBounds (unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
 Include the given bounds in the changed-rectangle. More...
 
 ~Costmap2DPublisher ()
 Destructor. More...
 

Private Member Functions

void onNewSubscription (const ros::SingleSubscriberPublisher &pub)
 Publish the latest full costmap to the new subscriber. More...
 
void prepareGrid ()
 Prepare grid_ message for publication. More...
 

Private Attributes

bool active_
 
bool always_send_full_costmap_
 
Costmap2Dcostmap_
 
ros::Publisher costmap_pub_
 
ros::Publisher costmap_update_pub_
 
std::string global_frame_
 
nav_msgs::OccupancyGrid grid_
 
ros::NodeHandlenode
 
double saved_origin_x_
 
double saved_origin_y_
 
unsigned int x0_
 
unsigned int xn_
 
unsigned int y0_
 
unsigned int yn_
 

Static Private Attributes

static char * cost_translation_table_ = NULL
 Translate from 0-255 values in costmap to -1 to 100 values in message. More...
 

Detailed Description

A tool to periodically publish visualization data from a Costmap2D.

Definition at line 52 of file costmap_2d_publisher.h.

Constructor & Destructor Documentation

costmap_2d::Costmap2DPublisher::Costmap2DPublisher ( ros::NodeHandle ros_node,
Costmap2D costmap,
std::string  global_frame,
std::string  topic_name,
bool  always_send_full_costmap = false 
)

Constructor for the Costmap2DPublisher.

Definition at line 47 of file costmap_2d_publisher.cpp.

costmap_2d::Costmap2DPublisher::~Costmap2DPublisher ( )

Destructor.

Definition at line 79 of file costmap_2d_publisher.cpp.

Member Function Documentation

bool costmap_2d::Costmap2DPublisher::active ( )
inline

Check if the publisher is active.

Returns
True if the frequency for the publisher is non-zero, false otherwise

Definition at line 84 of file costmap_2d_publisher.h.

void costmap_2d::Costmap2DPublisher::onNewSubscription ( const ros::SingleSubscriberPublisher pub)
private

Publish the latest full costmap to the new subscriber.

Definition at line 83 of file costmap_2d_publisher.cpp.

void costmap_2d::Costmap2DPublisher::prepareGrid ( )
private

Prepare grid_ message for publication.

Definition at line 90 of file costmap_2d_publisher.cpp.

void costmap_2d::Costmap2DPublisher::publishCostmap ( )

Publishes the visualization data over ROS.

Definition at line 120 of file costmap_2d_publisher.cpp.

void costmap_2d::Costmap2DPublisher::updateBounds ( unsigned int  x0,
unsigned int  xn,
unsigned int  y0,
unsigned int  yn 
)
inline

Include the given bounds in the changed-rectangle.

Definition at line 67 of file costmap_2d_publisher.h.

Member Data Documentation

bool costmap_2d::Costmap2DPublisher::active_
private

Definition at line 101 of file costmap_2d_publisher.h.

bool costmap_2d::Costmap2DPublisher::always_send_full_costmap_
private

Definition at line 102 of file costmap_2d_publisher.h.

char * costmap_2d::Costmap2DPublisher::cost_translation_table_ = NULL
staticprivate

Translate from 0-255 values in costmap to -1 to 100 values in message.

Definition at line 106 of file costmap_2d_publisher.h.

Costmap2D* costmap_2d::Costmap2DPublisher::costmap_
private

Definition at line 97 of file costmap_2d_publisher.h.

ros::Publisher costmap_2d::Costmap2DPublisher::costmap_pub_
private

Definition at line 103 of file costmap_2d_publisher.h.

ros::Publisher costmap_2d::Costmap2DPublisher::costmap_update_pub_
private

Definition at line 104 of file costmap_2d_publisher.h.

std::string costmap_2d::Costmap2DPublisher::global_frame_
private

Definition at line 98 of file costmap_2d_publisher.h.

nav_msgs::OccupancyGrid costmap_2d::Costmap2DPublisher::grid_
private

Definition at line 105 of file costmap_2d_publisher.h.

ros::NodeHandle* costmap_2d::Costmap2DPublisher::node
private

Definition at line 96 of file costmap_2d_publisher.h.

double costmap_2d::Costmap2DPublisher::saved_origin_x_
private

Definition at line 100 of file costmap_2d_publisher.h.

double costmap_2d::Costmap2DPublisher::saved_origin_y_
private

Definition at line 100 of file costmap_2d_publisher.h.

unsigned int costmap_2d::Costmap2DPublisher::x0_
private

Definition at line 99 of file costmap_2d_publisher.h.

unsigned int costmap_2d::Costmap2DPublisher::xn_
private

Definition at line 99 of file costmap_2d_publisher.h.

unsigned int costmap_2d::Costmap2DPublisher::y0_
private

Definition at line 99 of file costmap_2d_publisher.h.

unsigned int costmap_2d::Costmap2DPublisher::yn_
private

Definition at line 99 of file costmap_2d_publisher.h.


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


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:42