#include <ros/ros.h>
#include <nav_msgs/GetMap.h>
#include <std_srvs/Trigger.h>
#include <tf/transform_listener.h>
#include <actionlib/server/simple_action_server.h>
#include <pluginlib/class_loader.h>
#include <nav2d_navigator/MoveToPosition2DAction.h>
#include <nav2d_navigator/ExploreAction.h>
#include <nav2d_navigator/GetFirstMapAction.h>
#include <nav2d_navigator/LocalizeAction.h>
#include <nav2d_navigator/GridMap.h>
#include <nav2d_navigator/commands.h>
#include <nav2d_navigator/MapInflationTool.h>
#include <nav2d_navigator/ExplorationPlanner.h>
#include <queue>
Go to the source code of this file.
Classes | |
class | RobotNavigator |
Typedefs | |
typedef actionlib::SimpleActionServer < nav2d_navigator::ExploreAction > | ExploreActionServer |
typedef actionlib::SimpleActionServer < nav2d_navigator::GetFirstMapAction > | GetMapActionServer |
typedef actionlib::SimpleActionServer < nav2d_navigator::LocalizeAction > | LocalizeActionServer |
typedef actionlib::SimpleActionServer < nav2d_navigator::MoveToPosition2DAction > | MoveActionServer |
typedef pluginlib::ClassLoader < ExplorationPlanner > | PlanLoader |
typedef actionlib::SimpleActionServer<nav2d_navigator::ExploreAction> ExploreActionServer |
Definition at line 20 of file RobotNavigator.h.
typedef actionlib::SimpleActionServer<nav2d_navigator::GetFirstMapAction> GetMapActionServer |
Definition at line 21 of file RobotNavigator.h.
typedef actionlib::SimpleActionServer<nav2d_navigator::LocalizeAction> LocalizeActionServer |
Definition at line 22 of file RobotNavigator.h.
typedef actionlib::SimpleActionServer<nav2d_navigator::MoveToPosition2DAction> MoveActionServer |
Definition at line 19 of file RobotNavigator.h.
Definition at line 23 of file RobotNavigator.h.