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, double publish_frequency, std::string global_frame) | |
Constructor for the Costmap2DPublisher. | |
void | publishCostmap () |
Publishes the visualization data over ROS. | |
void | publishFootprint () |
Publishes footprint visualization data over ROS. | |
void | updateCostmapData (const Costmap2D &costmap, const std::vector< geometry_msgs::Point > &footprint=std::vector< geometry_msgs::Point >(), const tf::Stamped< tf::Pose > &global_pose=tf::Stamped< tf::Pose >()) |
Update the visualization data from a Costmap2D. | |
~Costmap2DPublisher () | |
Destructor. | |
Private Member Functions | |
void | mapPublishLoop (double frequency) |
Private Attributes | |
bool | active_ |
std::vector< geometry_msgs::Point > | footprint_ |
ros::Publisher | footprint_pub_ |
std::string | global_frame_ |
tf::Stamped< tf::Pose > | global_pose_ |
ros::Publisher | inf_obs_pub_ |
std::vector< std::pair< double, double > > | inflated_obstacles_ |
double | inscribed_radius_ |
boost::recursive_mutex | lock_ |
A lock. | |
bool | new_data_ |
ros::Publisher | obs_pub_ |
std::vector< std::pair< double, double > > | raw_obstacles_ |
double | resolution_ |
std::vector< std::pair< double, double > > | unknown_space_ |
ros::Publisher | unknown_space_pub_ |
boost::thread * | visualizer_thread_ |
A thread for publising to the visualizer. | |
bool | visualizer_thread_shutdown_ |
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, |
double | publish_frequency, | ||
std::string | global_frame | ||
) |
Constructor for the Costmap2DPublisher.
ros_node | The node under which to publish the visualization output |
global_frame | The frame in which to publish the visualization output |
Definition at line 41 of file costmap_2d_publisher.cpp.
Destructor.
Definition at line 52 of file costmap_2d_publisher.cpp.
bool costmap_2d::Costmap2DPublisher::active | ( | ) | [inline] |
Check if the publisher is active.
Definition at line 89 of file costmap_2d_publisher.h.
void costmap_2d::Costmap2DPublisher::mapPublishLoop | ( | double | frequency | ) | [private] |
Definition at line 60 of file costmap_2d_publisher.cpp.
Publishes the visualization data over ROS.
Definition at line 161 of file costmap_2d_publisher.cpp.
Publishes footprint visualization data over ROS.
Definition at line 122 of file costmap_2d_publisher.cpp.
void costmap_2d::Costmap2DPublisher::updateCostmapData | ( | const Costmap2D & | costmap, |
const std::vector< geometry_msgs::Point > & | footprint = std::vector<geometry_msgs::Point>() , |
||
const tf::Stamped< tf::Pose > & | global_pose = tf::Stamped<tf::Pose>() |
||
) |
Update the visualization data from a Costmap2D.
costmap | The Costmap2D object to create visualization messages from |
footprint | The footprint of the robot associated with the costmap |
Definition at line 86 of file costmap_2d_publisher.cpp.
bool costmap_2d::Costmap2DPublisher::active_ [private] |
Definition at line 98 of file costmap_2d_publisher.h.
std::vector<geometry_msgs::Point> costmap_2d::Costmap2DPublisher::footprint_ [private] |
Definition at line 101 of file costmap_2d_publisher.h.
Definition at line 99 of file costmap_2d_publisher.h.
std::string costmap_2d::Costmap2DPublisher::global_frame_ [private] |
Definition at line 94 of file costmap_2d_publisher.h.
Definition at line 102 of file costmap_2d_publisher.h.
Definition at line 99 of file costmap_2d_publisher.h.
std::vector< std::pair<double, double> > costmap_2d::Costmap2DPublisher::inflated_obstacles_ [private] |
Definition at line 96 of file costmap_2d_publisher.h.
double costmap_2d::Costmap2DPublisher::inscribed_radius_ [private] |
Definition at line 100 of file costmap_2d_publisher.h.
boost::recursive_mutex costmap_2d::Costmap2DPublisher::lock_ [private] |
A lock.
Definition at line 97 of file costmap_2d_publisher.h.
bool costmap_2d::Costmap2DPublisher::new_data_ [private] |
Definition at line 98 of file costmap_2d_publisher.h.
Definition at line 99 of file costmap_2d_publisher.h.
std::vector< std::pair<double, double> > costmap_2d::Costmap2DPublisher::raw_obstacles_ [private] |
Definition at line 96 of file costmap_2d_publisher.h.
double costmap_2d::Costmap2DPublisher::resolution_ [private] |
Definition at line 100 of file costmap_2d_publisher.h.
std::vector< std::pair<double, double> > costmap_2d::Costmap2DPublisher::unknown_space_ [private] |
Definition at line 96 of file costmap_2d_publisher.h.
Definition at line 99 of file costmap_2d_publisher.h.
boost::thread* costmap_2d::Costmap2DPublisher::visualizer_thread_ [private] |
A thread for publising to the visualizer.
Definition at line 95 of file costmap_2d_publisher.h.
bool costmap_2d::Costmap2DPublisher::visualizer_thread_shutdown_ [private] |
Definition at line 103 of file costmap_2d_publisher.h.