Provide cost_map::fromROSCostMap2D() as a ros service. More...
#include <converter.hpp>
Public Member Functions | |
| bool | callback (cost_map_msgs::GetCostMap::Request &req, cost_map_msgs::GetCostMap::Response &res) |
| Costmap2DROSServiceProvider (costmap_2d::Costmap2DROS *ros_costmap, const std::string &service_name="get_cost_map") | |
| Costmap2DROSServiceProvider (costmap_2d::Costmap2DROS *ros_costmap, ros::NodeHandle &node_handle, const std::string &service_name="get_cost_map") | |
Private Attributes | |
| costmap_2d::Costmap2DROS * | ros_costmap |
| ros::ServiceServer | service |
Provide cost_map::fromROSCostMap2D() as a ros service.
Definition at line 138 of file converter.hpp.
| cost_map::Costmap2DROSServiceProvider::Costmap2DROSServiceProvider | ( | costmap_2d::Costmap2DROS * | ros_costmap, |
| const std::string & | service_name = "get_cost_map" |
||
| ) |
Definition at line 298 of file converter.cpp.
| cost_map::Costmap2DROSServiceProvider::Costmap2DROSServiceProvider | ( | costmap_2d::Costmap2DROS * | ros_costmap, |
| ros::NodeHandle & | node_handle, | ||
| const std::string & | service_name = "get_cost_map" |
||
| ) |
Definition at line 306 of file converter.cpp.
| bool cost_map::Costmap2DROSServiceProvider::callback | ( | cost_map_msgs::GetCostMap::Request & | req, |
| cost_map_msgs::GetCostMap::Response & | res | ||
| ) |
Definition at line 314 of file converter.cpp.
Definition at line 148 of file converter.hpp.
Definition at line 149 of file converter.hpp.