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. | |
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. | |
void | publishCostmap () |
Publishes the visualization data over ROS. | |
void | updateBounds (unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn) |
Include the given bounds in the changed-rectangle. | |
~Costmap2DPublisher () | |
Destructor. | |
Private Member Functions | |
void | onNewSubscription (const ros::SingleSubscriberPublisher &pub) |
Publish the latest full costmap to the new subscriber. | |
void | prepareGrid () |
Prepare grid_ message for publication. | |
Private Attributes | |
bool | active_ |
bool | always_send_full_costmap_ |
Costmap2D * | costmap_ |
ros::Publisher | costmap_pub_ |
ros::Publisher | costmap_update_pub_ |
std::string | global_frame_ |
nav_msgs::OccupancyGrid | grid_ |
ros::NodeHandle * | node |
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. |
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 |
||
) |
Constructor for the Costmap2DPublisher.
Definition at line 47 of file costmap_2d_publisher.cpp.
Destructor.
Definition at line 79 of file costmap_2d_publisher.cpp.
bool costmap_2d::Costmap2DPublisher::active | ( | ) | [inline] |
Check if the publisher is active.
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.
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.
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 [static, private] |
Translate from 0-255 values in costmap to -1 to 100 values in message.
Definition at line 106 of file costmap_2d_publisher.h.
Definition at line 97 of file costmap_2d_publisher.h.
Definition at line 103 of file costmap_2d_publisher.h.
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.
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.