Public Member Functions | Private Member Functions | Private Attributes
costmap_2d::Costmap2DPublisher Class Reference

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

#include <costmap_2d_publisher.h>

List of all members.

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::Pointfootprint_
ros::Publisher footprint_pub_
std::string global_frame_
tf::Stamped< tf::Poseglobal_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_

Detailed Description

A tool to periodically publish visualization data from a Costmap2D.

Definition at line 51 of file costmap_2d_publisher.h.


Constructor & Destructor Documentation

costmap_2d::Costmap2DPublisher::Costmap2DPublisher ( ros::NodeHandle  ros_node,
double  publish_frequency,
std::string  global_frame 
)

Constructor for the Costmap2DPublisher.

Parameters:
ros_nodeThe node under which to publish the visualization output
global_frameThe 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.


Member Function Documentation

Check if the publisher is active.

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

Definition at line 88 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.

Parameters:
costmapThe Costmap2D object to create visualization messages from
footprintThe footprint of the robot associated with the costmap

Definition at line 86 of file costmap_2d_publisher.cpp.


Member Data Documentation

Definition at line 97 of file costmap_2d_publisher.h.

Definition at line 100 of file costmap_2d_publisher.h.

Definition at line 98 of file costmap_2d_publisher.h.

Definition at line 93 of file costmap_2d_publisher.h.

Definition at line 101 of file costmap_2d_publisher.h.

Definition at line 98 of file costmap_2d_publisher.h.

std::vector< std::pair<double, double> > costmap_2d::Costmap2DPublisher::inflated_obstacles_ [private]

Definition at line 95 of file costmap_2d_publisher.h.

Definition at line 99 of file costmap_2d_publisher.h.

boost::recursive_mutex costmap_2d::Costmap2DPublisher::lock_ [private]

A lock.

Definition at line 96 of file costmap_2d_publisher.h.

Definition at line 97 of file costmap_2d_publisher.h.

Definition at line 98 of file costmap_2d_publisher.h.

std::vector< std::pair<double, double> > costmap_2d::Costmap2DPublisher::raw_obstacles_ [private]

Definition at line 95 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::unknown_space_ [private]

Definition at line 95 of file costmap_2d_publisher.h.

Definition at line 98 of file costmap_2d_publisher.h.

A thread for publising to the visualizer.

Definition at line 94 of file costmap_2d_publisher.h.

Definition at line 102 of file costmap_2d_publisher.h.


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


costmap_2d
Author(s): Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:13:40