41 #include <nav_msgs/Path.h> 49 : tf_listener_ptr_(tf_listener_ptr), private_nh_(
"~"),
50 planner_plugin_manager_(
"planners",
53 controller_plugin_manager_(
"controllers",
56 recovery_plugin_manager_(
"recovery_behaviors",
59 tf_timeout_(private_nh_.
param<double>(
"tf_timeout", 3.0)),
60 global_frame_(private_nh_.
param<
std::string>(
"global_frame",
"map")),
61 robot_frame_(private_nh_.
param<
std::string>(
"robot_frame",
"base_link")),
62 robot_info_(*tf_listener_ptr, global_frame_, robot_frame_, tf_timeout_),
126 const mbf_msgs::GetPathGoal &goal = *(goal_handle.
getGoal().get());
127 const geometry_msgs::Point &p = goal.target_pose.pose.position;
129 std::string planner_name;
136 mbf_msgs::GetPathResult result;
137 result.outcome = mbf_msgs::GetPathResult::INVALID_PLUGIN;
138 result.message =
"No plugins loaded at all!";
146 mbf_msgs::GetPathResult result;
147 result.outcome = mbf_msgs::GetPathResult::INVALID_PLUGIN;
148 result.message =
"No plugin loaded with the given name \"" + goal.planner +
"\"!";
169 mbf_msgs::GetPathResult result;
170 result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR;
171 result.message =
"Internal Error: \"planner_plugin\" pointer should not be a null pointer!";
185 const mbf_msgs::ExePathGoal &goal = *(goal_handle.
getGoal().get());
187 std::string controller_name;
194 mbf_msgs::ExePathResult result;
195 result.outcome = mbf_msgs::ExePathResult::INVALID_PLUGIN;
196 result.message =
"No plugins loaded at all!";
204 mbf_msgs::ExePathResult result;
205 result.outcome = mbf_msgs::ExePathResult::INVALID_PLUGIN;
206 result.message =
"No plugin loaded with the given name \"" + goal.controller +
"\"!";
217 if(controller_plugin)
227 mbf_msgs::ExePathResult result;
228 result.outcome = mbf_msgs::ExePathResult::INTERNAL_ERROR;
229 result.message =
"Internal Error: \"controller_plugin\" pointer should not be a null pointer!";
243 const mbf_msgs::RecoveryGoal &goal = *(goal_handle.
getGoal().get());
245 std::string recovery_name;
253 mbf_msgs::RecoveryResult result;
254 result.outcome = mbf_msgs::RecoveryResult::INVALID_PLUGIN;
255 result.message =
"No plugins loaded at all!";
263 mbf_msgs::RecoveryResult result;
264 result.outcome = mbf_msgs::RecoveryResult::INVALID_PLUGIN;
265 result.message =
"No plugin loaded with the given name \"" + goal.behavior +
"\"!";
285 mbf_msgs::RecoveryResult result;
286 result.outcome = mbf_msgs::RecoveryResult::INTERNAL_ERROR;
287 result.message =
"Internal Error: \"recovery_plugin\" pointer should not be a null pointer!";
313 const std::string &plugin_name,
316 return boost::make_shared<mbf_abstract_nav::AbstractPlannerExecution>(plugin_name, plugin_ptr,
last_config_);
320 const std::string &plugin_name,
323 return boost::make_shared<mbf_abstract_nav::AbstractControllerExecution>(plugin_name, plugin_ptr,
vel_pub_,
goal_pub_,
328 const std::string &plugin_name,
331 return boost::make_shared<mbf_abstract_nav::AbstractRecoveryExecution>(plugin_name, plugin_ptr,
346 dsrv_ = boost::make_shared<dynamic_reconfigure::Server<mbf_abstract_nav::MoveBaseFlexConfig> >(
private_nh_);
351 mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
362 if (config.restore_defaults)
366 config.restore_defaults =
false;
ActionServerRecoveryPtr action_server_recovery_ptr_
shared pointer to the Recovery action server
actionlib::ActionServer< mbf_msgs::MoveBaseAction > ActionServerMoveBase
MoveBase action server.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
actionlib::ActionServer< mbf_msgs::RecoveryAction > ActionServerRecovery
Recovery action server.
ros::Publisher goal_pub_
current_goal publisher for all controller execution objects
virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle)
const TFPtr tf_listener_ptr_
shared pointer to the common TransformListener
#define ROS_DEBUG_STREAM_NAMED(name, args)
virtual ~AbstractNavigationServer()
Destructor.
boost::shared_ptr< ActionServerMoveBase > ActionServerMoveBasePtr
boost::shared_ptr< const Goal > getGoal() const
PluginType::Ptr getPlugin(const std::string &name)
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr)
Create a new abstract planner execution.
AbstractPluginManager< mbf_abstract_core::AbstractController > controller_plugin_manager_
virtual void startDynamicReconfigureServer()
Start a dynamic reconfigure server. This must be called only if the extending doesn't create its own...
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
Create a new abstract controller execution.
const std::string name_action_get_path
GetPath action topic name.
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
The AbstractNavigationServer is the abstract base class for all navigation servers in move_base_flex ...
virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
MoveBaseAction move_base_action_
#define ROS_INFO_STREAM_NAMED(name, args)
virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
actionlib::ActionServer< mbf_msgs::GetPathAction > ActionServerGetPath
GetPath action server.
actionlib::ActionServer< mbf_msgs::ExePathAction > ActionServerExePath
ExePath action server.
PlannerAction planner_action_
virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle)
ExePath action execution method. This method will be called if the action server receives a goal...
ActionServerGetPathPtr action_server_get_path_ptr_
shared pointer to the GetPath action server
const std::string name_action_exe_path
ExePath action topic name.
const std::vector< std::string > & getLoadedNames()
void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
AbstractPluginManager< mbf_abstract_core::AbstractPlanner > planner_plugin_manager_
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup.
ControllerAction controller_action_
#define ROS_FATAL_STREAM_NAMED(name, args)
mbf_abstract_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
void start(GoalHandle &goal_handle, typename AbstractControllerExecution::Ptr execution_ptr)
Start controller action. Override abstract action version to allow updating current plan without stop...
virtual void callActionRecovery(ActionServerRecovery::GoalHandle goal_handle)
Recovery action execution method. This method will be called if the action server receives a goal...
AbstractNavigationServer(const TFPtr &tf_listener_ptr)
Constructor, reads all parameters and initializes all action servers and creates the plugin instances...
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher vel_pub_
cmd_vel publisher for all controller execution objects
virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle)
bool hasPlugin(const std::string &name)
boost::shared_ptr< ActionServerGetPath > ActionServerGetPathPtr
virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
MoveBase action execution method. This method will be called if the action server receives a goal...
mbf_abstract_nav::MoveBaseFlexConfig last_config_
last configuration save
ActionServerMoveBasePtr action_server_move_base_ptr_
shared pointer to the MoveBase action server
boost::shared_ptr< ActionServerExePath > ActionServerExePathPtr
ActionServerExePathPtr action_server_exe_path_ptr_
shared pointer to the ExePath action server
const std::string name_action_recovery
Recovery action topic name.
virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
GetPath action execution method. This method will be called if the action server receives a goal...
boost::mutex configuration_mutex_
configuration mutex for derived classes and other threads.
AbstractPluginManager< mbf_abstract_core::AbstractRecovery > recovery_plugin_manager_
virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
virtual void startActionServers()
starts all action server.
const std::string name_action_move_base
MoveBase action topic name.
RecoveryAction recovery_action_
DynamicReconfigureServer dsrv_
dynamic reconfigure server
virtual void initializeServerComponents()
initializes all server components. Initializing the plugins of the Planner, the Controller, and the Recovery Behavior.
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr)
Create a new abstract recovery behavior execution.
boost::shared_ptr< ActionServerRecovery > ActionServerRecoveryPtr
void start(GoalHandle &goal_handle)
ros::NodeHandle private_nh_
Private node handle.
#define ROS_WARN_STREAM_NAMED(name, args)
std::string getType(const std::string &name)