$search
Public Member Functions | |
| bool | getSearchPosServiceCallback (hector_nav_msgs::GetSearchPosition::Request &req, hector_nav_msgs::GetSearchPosition::Response &res) |
| bool | lookupServiceCallback (hector_nav_msgs::GetDistanceToObstacle::Request &req, hector_nav_msgs::GetDistanceToObstacle::Response &res) |
| void | mapCallback (const nav_msgs::OccupancyGridConstPtr &map) |
| bool | mapServiceCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res) |
| OccupancyGridContainer (std::string sub_topic, std::string prefix, ros::NodeHandle &nh, HectorDrawings *drawing_provider, tf::TransformListener *tf_) | |
| ~OccupancyGridContainer () | |
Public Attributes | |
| ros::ServiceServer | dist_lookup_service_ |
| HectorMapTools::DistanceMeasurementProvider | dist_meas_ |
| HectorDrawings * | drawing_provider_ |
| ros::ServiceServer | get_search_pos_service_ |
| nav_msgs::OccupancyGridConstPtr | map_ptr_ |
| nav_msgs::GetMap::Response | map_resp_ |
| ros::ServiceServer | map_service_ |
| ros::Subscriber | map_sub_ |
| tf::TransformListener * | tf_ |
Definition at line 52 of file hector_map_server.cpp.
| OccupancyGridContainer::OccupancyGridContainer | ( | std::string | sub_topic, | |
| std::string | prefix, | |||
| ros::NodeHandle & | nh, | |||
| HectorDrawings * | drawing_provider, | |||
| tf::TransformListener * | tf_ | |||
| ) | [inline] |
Definition at line 55 of file hector_map_server.cpp.
| OccupancyGridContainer::~OccupancyGridContainer | ( | ) | [inline] |
Definition at line 72 of file hector_map_server.cpp.
| bool OccupancyGridContainer::getSearchPosServiceCallback | ( | hector_nav_msgs::GetSearchPosition::Request & | req, | |
| hector_nav_msgs::GetSearchPosition::Response & | res | |||
| ) | [inline] |
Definition at line 166 of file hector_map_server.cpp.
| bool OccupancyGridContainer::lookupServiceCallback | ( | hector_nav_msgs::GetDistanceToObstacle::Request & | req, | |
| hector_nav_msgs::GetDistanceToObstacle::Response & | res | |||
| ) | [inline] |
Definition at line 90 of file hector_map_server.cpp.
| void OccupancyGridContainer::mapCallback | ( | const nav_msgs::OccupancyGridConstPtr & | map | ) | [inline] |
Definition at line 262 of file hector_map_server.cpp.
| bool OccupancyGridContainer::mapServiceCallback | ( | nav_msgs::GetMap::Request & | req, | |
| nav_msgs::GetMap::Response & | res | |||
| ) | [inline] |
Definition at line 75 of file hector_map_server.cpp.
Definition at line 271 of file hector_map_server.cpp.
Definition at line 277 of file hector_map_server.cpp.
Definition at line 279 of file hector_map_server.cpp.
Definition at line 272 of file hector_map_server.cpp.
Definition at line 285 of file hector_map_server.cpp.
Definition at line 283 of file hector_map_server.cpp.
Definition at line 270 of file hector_map_server.cpp.
Definition at line 275 of file hector_map_server.cpp.
Definition at line 280 of file hector_map_server.cpp.