costmap_2d_publisher.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169
  1. /*********************************************************************
  2. *
  3. * Software License Agreement (BSD License)
  4. *
  5. * Copyright (c) 2008, 2013, Willow Garage, Inc.
  6. * All rights reserved.
  7. *
  8. * Redistribution and use in source and binary forms, with or without
  9. * modification, are permitted provided that the following conditions
  10. * are met:
  11. *
  12. * * Redistributions of source code must retain the above copyright
  13. * notice, this list of conditions and the following disclaimer.
  14. * * Redistributions in binary form must reproduce the above
  15. * copyright notice, this list of conditions and the following
  16. * disclaimer in the documentation and/or other materials provided
  17. * with the distribution.
  18. * * Neither the name of Willow Garage, Inc. nor the names of its
  19. * contributors may be used to endorse or promote products derived
  20. * from this software without specific prior written permission.
  21. *
  22. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  23. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  24. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  25. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  26. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  27. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  28. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  29. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  30. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  31. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  32. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  33. * POSSIBILITY OF SUCH DAMAGE.
  34. *
  35. * Author: Eitan Marder-Eppstein
  36. * David V. Lu!!
  37. *********************************************************************/
  38. #include <boost/bind.hpp>
  39. #include <costmap_2d/costmap_2d_publisher.h>
  40. #include <costmap_2d/cost_values.h>
  41. namespace costmap_2d
  42. {
  43. char* Costmap2DPublisher::cost_translation_table_ = NULL;
  44. Costmap2DPublisher::Costmap2DPublisher(ros::NodeHandle * ros_node, Costmap2D* costmap, std::string global_frame,
  45. std::string topic_name, bool always_send_full_costmap) :
  46. node(ros_node), costmap_(costmap), global_frame_(global_frame), active_(false),
  47. always_send_full_costmap_(always_send_full_costmap)
  48. {
  49. costmap_pub_ = ros_node->advertise<nav_msgs::OccupancyGrid>(topic_name, 1,
  50. boost::bind(&Costmap2DPublisher::onNewSubscription, this, _1));
  51. costmap_update_pub_ = ros_node->advertise<map_msgs::OccupancyGridUpdate>(topic_name + "_updates", 1);
  52. if (cost_translation_table_ == NULL)
  53. {
  54. cost_translation_table_ = new char[256];
  55. // special values:
  56. cost_translation_table_[0] = 0; // NO obstacle
  57. cost_translation_table_[253] = 99; // INSCRIBED obstacle
  58. cost_translation_table_[254] = 100; // LETHAL obstacle
  59. cost_translation_table_[255] = -1; // UNKNOWN
  60. // regular cost values scale the range 1 to 252 (inclusive) to fit
  61. // into 1 to 98 (inclusive).
  62. for (int i = 1; i < 253; i++)
  63. {
  64. cost_translation_table_[ i ] = char(1 + (97 * (i - 1)) / 251);
  65. }
  66. }
  67. xn_ = yn_ = 0;
  68. x0_ = costmap_->getSizeInCellsX();
  69. y0_ = costmap_->getSizeInCellsY();
  70. }
  71. Costmap2DPublisher::~Costmap2DPublisher()
  72. {
  73. }
  74. void Costmap2DPublisher::onNewSubscription(const ros::SingleSubscriberPublisher& pub)
  75. {
  76. prepareGrid();
  77. pub.publish(grid_);
  78. }
  79. // prepare grid_ message for publication.
  80. void Costmap2DPublisher::prepareGrid()
  81. {
  82. boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
  83. double resolution = costmap_->getResolution();
  84. grid_.header.frame_id = global_frame_;
  85. grid_.header.stamp = ros::Time::now();
  86. grid_.info.resolution = resolution;
  87. grid_.info.width = costmap_->getSizeInCellsX();
  88. grid_.info.height = costmap_->getSizeInCellsY();
  89. double wx, wy;
  90. costmap_->mapToWorld(0, 0, wx, wy);
  91. grid_.info.origin.position.x = wx - resolution / 2;
  92. grid_.info.origin.position.y = wy - resolution / 2;
  93. grid_.info.origin.position.z = 0.0;
  94. grid_.info.origin.orientation.w = 1.0;
  95. saved_origin_x_ = costmap_->getOriginX();
  96. saved_origin_y_ = costmap_->getOriginY();
  97. grid_.data.resize(grid_.info.width * grid_.info.height);
  98. unsigned char* data = costmap_->getCharMap();
  99. for (unsigned int i = 0; i < grid_.data.size(); i++)
  100. {
  101. grid_.data[i] = cost_translation_table_[ data[ i ]];
  102. }
  103. }
  104. void Costmap2DPublisher::publishCostmap()
  105. {
  106. if (costmap_pub_.getNumSubscribers() == 0)
  107. {
  108. // No subscribers, so why do any work?
  109. return;
  110. }
  111. boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
  112. float resolution = costmap_->getResolution();
  113. if (always_send_full_costmap_ || grid_.info.resolution != resolution ||
  114. grid_.info.width != costmap_->getSizeInCellsX() ||
  115. grid_.info.height != costmap_->getSizeInCellsY() ||
  116. saved_origin_x_ != costmap_->getOriginX() ||
  117. saved_origin_y_ != costmap_->getOriginY())
  118. {
  119. prepareGrid();
  120. costmap_pub_.publish(grid_);
  121. }
  122. else if (x0_ < xn_)
  123. {
  124. // Publish Just an Update
  125. map_msgs::OccupancyGridUpdate update;
  126. update.header.stamp = ros::Time::now();
  127. update.header.frame_id = global_frame_;
  128. update.x = x0_;
  129. update.y = y0_;
  130. update.width = xn_ - x0_;
  131. update.height = yn_ - y0_;
  132. update.data.resize(update.width * update.height);
  133. unsigned int i = 0;
  134. for (unsigned int y = y0_; y < yn_; y++)
  135. {
  136. for (unsigned int x = x0_; x < xn_; x++)
  137. {
  138. unsigned char cost = costmap_->getCost(x, y);
  139. update.data[i++] = cost_translation_table_[ cost ];
  140. }
  141. }
  142. costmap_update_pub_.publish(update);
  143. }
  144. xn_ = yn_ = 0;
  145. x0_ = costmap_->getSizeInCellsX();
  146. y0_ = costmap_->getSizeInCellsY();
  147. }
  148. } // end namespace costmap_2d