38 #include <boost/bind.hpp> 48 std::string topic_name,
bool always_send_full_costmap) :
49 node(ros_node), costmap_(costmap), global_frame_(global_frame), active_(false),
50 always_send_full_costmap_(always_send_full_costmap)
68 for (
int i = 1; i < 253; i++)
97 grid_.info.resolution = resolution;
104 grid_.info.origin.position.x = wx - resolution / 2;
105 grid_.info.origin.position.y = wy - resolution / 2;
106 grid_.info.origin.position.z = 0.0;
107 grid_.info.origin.orientation.w = 1.0;
114 for (
unsigned int i = 0; i <
grid_.data.size(); i++)
143 map_msgs::OccupancyGridUpdate
update;
149 update.height =
yn_ -
y0_;
150 update.data.resize(update.width * update.height);
153 for (
unsigned int y = y0_; y <
yn_; y++)
155 for (
unsigned int x = x0_; x <
xn_; x++)
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
ros::Publisher costmap_pub_
bool always_send_full_costmap_
double getOriginY() const
Accessor for the y origin of the costmap.
~Costmap2DPublisher()
Destructor.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void publish(const boost::shared_ptr< M > &message) const
void onNewSubscription(const ros::SingleSubscriberPublisher &pub)
Publish the latest full costmap to the new subscriber.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
void prepareGrid()
Prepare grid_ message for publication.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const boost::shared_ptr< M const > &message) const
static char * cost_translation_table_
Translate from 0-255 values in costmap to -1 to 100 values in message.
double getOriginX() const
Accessor for the x origin of the costmap.
std::string global_frame_
ros::Publisher costmap_update_pub_
double getResolution() const
Accessor for the resolution of the costmap.
nav_msgs::OccupancyGrid grid_
A 2D costmap provides a mapping between points in the world and their associated "costs".
uint32_t getNumSubscribers() const
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
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.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
void publishCostmap()
Publishes the visualization data over ROS.