#include <ros/ros.h>
#include <nodelet/nodelet.h>
#include <std_srvs/Empty.h>
#include <tf/transform_listener.h>
#include <tf2_ros/transform_broadcaster.h>
#include <std_msgs/Empty.h>
#include <std_msgs/Int32.h>
#include "std_msgs/Int32MultiArray.h"
#include <sensor_msgs/NavSatFix.h>
#include <nav_msgs/GetMap.h>
#include <nav_msgs/GetPlan.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <sensor_msgs/Imu.h>
#include <rtabmap/core/Parameters.h>
#include <rtabmap/core/Rtabmap.h>
#include <rtabmap/core/OdometryInfo.h>
#include "rtabmap_ros/GetNodeData.h"
#include "rtabmap_ros/GetMap.h"
#include "rtabmap_ros/GetMap2.h"
#include "rtabmap_ros/ListLabels.h"
#include "rtabmap_ros/PublishMap.h"
#include "rtabmap_ros/SetGoal.h"
#include "rtabmap_ros/SetLabel.h"
#include "rtabmap_ros/RemoveLabel.h"
#include "rtabmap_ros/Goal.h"
#include "rtabmap_ros/GetPlan.h"
#include "rtabmap_ros/CommonDataSubscriber.h"
#include "rtabmap_ros/OdomInfo.h"
#include "rtabmap_ros/AddLink.h"
#include "rtabmap_ros/GetNodesInRadius.h"
#include "rtabmap_ros/LoadDatabase.h"
#include "rtabmap_ros/DetectMoreLoopClosures.h"
#include "rtabmap_ros/GlobalBundleAdjustment.h"
#include "rtabmap_ros/CleanupLocalGrids.h"
#include "MapsManager.h"
#include "rtabmap_ros/ULogToRosout.h"
#include <actionlib/client/simple_action_client.h>
#include <move_base_msgs/MoveBaseAction.h>
#include <move_base_msgs/MoveBaseActionGoal.h>
#include <move_base_msgs/MoveBaseActionResult.h>
#include <move_base_msgs/MoveBaseActionFeedback.h>
#include <actionlib_msgs/GoalStatusArray.h>
Go to the source code of this file.
◆ MoveBaseClient