A tool to periodically publish visualization data from a Costmap2D.
More...
#include <costmap_2d_publisher.h>
A tool to periodically publish visualization data from a Costmap2D.
Definition at line 52 of file costmap_2d_publisher.h.
costmap_2d::Costmap2DPublisher::Costmap2DPublisher |
( |
ros::NodeHandle * |
ros_node, |
|
|
Costmap2D * |
costmap, |
|
|
std::string |
global_frame, |
|
|
std::string |
topic_name, |
|
|
bool |
always_send_full_costmap = false |
|
) |
| |
costmap_2d::Costmap2DPublisher::~Costmap2DPublisher |
( |
| ) |
|
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::prepareGrid |
( |
| ) |
|
|
private |
void costmap_2d::Costmap2DPublisher::publishCostmap |
( |
| ) |
|
void costmap_2d::Costmap2DPublisher::updateBounds |
( |
unsigned int |
x0, |
|
|
unsigned int |
xn, |
|
|
unsigned int |
y0, |
|
|
unsigned int |
yn |
|
) |
| |
|
inline |
bool costmap_2d::Costmap2DPublisher::active_ |
|
private |
bool costmap_2d::Costmap2DPublisher::always_send_full_costmap_ |
|
private |
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 |
std::string costmap_2d::Costmap2DPublisher::global_frame_ |
|
private |
nav_msgs::OccupancyGrid costmap_2d::Costmap2DPublisher::grid_ |
|
private |
double costmap_2d::Costmap2DPublisher::saved_origin_x_ |
|
private |
double costmap_2d::Costmap2DPublisher::saved_origin_y_ |
|
private |
unsigned int costmap_2d::Costmap2DPublisher::x0_ |
|
private |
unsigned int costmap_2d::Costmap2DPublisher::xn_ |
|
private |
unsigned int costmap_2d::Costmap2DPublisher::y0_ |
|
private |
unsigned int costmap_2d::Costmap2DPublisher::yn_ |
|
private |
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 Sun Mar 3 2019 03:44:17