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;