51 std::vector<std::string> split;
52 boost::split(split, s, boost::is_any_of(
"/:"));
68 if (!nh.
hasParam(
"robot_base_frame"))
71 std::string planner_frame, controller_frame, value_to_use;
72 nh.
param(
"global_costmap/robot_base_frame", planner_frame, std::string(
""));
73 nh.
param(
"local_costmap/robot_base_frame", controller_frame, std::string(
""));
74 if (planner_frame != controller_frame)
76 if (planner_frame.length() == 0)
78 value_to_use = controller_frame;
80 else if (controller_frame.length() == 0)
82 value_to_use = planner_frame;
86 ROS_WARN_NAMED(
"LocoMoveBase",
"Two different robot_base_frames set for global and local planner. " 87 "This could be problematic. Using the global base frame.");
88 value_to_use = planner_frame;
93 value_to_use = planner_frame;
95 nh.
setParam(
"robot_base_frame", value_to_use);
99 std::string planner_class, planner_namespace;
100 std::vector<std::string> plugin_namespaces;
103 nh.
param(
"base_global_planner", planner_class, std::string(
"navfn/NavfnROS"));
105 if (planner_class ==
"nav_core_adapter::GlobalPlannerAdapter2")
108 nh.
param(planner_namespace +
"/planner_name", planner_class, std::string(
"global_planner::GlobalPlanner"));
110 nh.
setParam(planner_namespace +
"/plugin_class", planner_class);
111 plugin_namespaces.push_back(planner_namespace);
112 nh.
setParam(
"global_planner_namespaces", plugin_namespaces);
117 std::string adapter_namespace =
"global_planner_adapter";
118 plugin_namespaces.push_back(adapter_namespace);
119 nh.
setParam(
"global_planner_namespaces", plugin_namespaces);
120 nh.
setParam(adapter_namespace +
"/planner_name", planner_class);
121 nh.
setParam(adapter_namespace +
"/plugin_class",
"nav_core_adapter::GlobalPlannerAdapter2");
123 plugin_namespaces.clear();
127 nh.
param(
"base_local_planner", planner_class, std::string(
"base_local_planner/TrajectoryPlannerROS"));
129 if (planner_namespace ==
"LocalPlannerAdapter")
131 nh.
param(planner_namespace +
"/planner_name", planner_class, std::string(
"dwb_local_planner::DWBLocalPlanner"));
133 nh.
setParam(planner_namespace +
"/plugin_class", planner_class);
134 plugin_namespaces.push_back(planner_namespace);
135 nh.
setParam(
"local_planner_namespaces", plugin_namespaces);
137 else if (planner_namespace ==
"DWAPlannerROS")
139 ROS_WARN_NAMED(
"LocoMoveBase",
"Using DWB as the local planner instead of DWA.");
140 nh.
setParam(planner_namespace +
"/plugin_class",
"dwb_local_planner::DWBLocalPlanner");
141 plugin_namespaces.push_back(planner_namespace);
142 nh.
setParam(
"local_planner_namespaces", plugin_namespaces);
146 ROS_FATAL_NAMED(
"LocoMoveBase",
"%s is unsupported in LocoMoveBase because it is not forwards compatible.",
147 planner_class.c_str());
155 server_(
ros::NodeHandle(),
"move_base", false),
156 recovery_loader_(
"nav_core",
"nav_core::RecoveryBehavior"),
157 local_planning_ex_(private_nh_, false), global_planning_ex_(private_nh_)
228 std::shared_ptr<nav_core_adapter::CostmapAdapter> ptr =
233 ROS_FATAL_NAMED(
"LocoMoveBase",
"LocoMoveBase can only be used with the CostmapAdapter, not other Costmaps!");
236 return ptr->getCostmap2DROS();
303 ROS_WARN_NAMED(
"locomotor",
"Global planning missed its desired rate of %.4fHz... " 304 "the loop actually took %.4f seconds (>%.4f).",
358 "Sensor data is out of date, we're not going to allow commanding of the base for safety");
392 move_base_msgs::MoveBaseFeedback feedback;
407 ROS_WARN_NAMED(
"Locomotor",
"Local planning error. Creating new global plan.");
463 "All recovery behaviors have failed, locking the planner and disabling it.");
467 ROS_ERROR(
"Aborting because a valid control could not be found." 468 "Even after executing all recovery behaviors");
470 "Failed to find a valid control. Even after executing recovery behaviors."));
474 ROS_ERROR(
"Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
476 "Failed to find a valid plan. Even after executing recovery behaviors."));
480 ROS_ERROR(
"Aborting because the robot appears to be oscillating over and over." 481 "Even after executing all recovery behaviors");
483 "Robot is oscillating. Even after executing recovery behaviors."));
491 if (!node.
getParam(
"recovery_behaviors", behavior_list))
499 ROS_ERROR(
"The recovery behavior specification must be a list, but is of XmlRpcType %d. " 500 "We'll use the default recovery behaviors instead.",
505 for (
int i = 0; i < behavior_list.
size(); ++i)
509 ROS_ERROR(
"Recovery behaviors must be specified as maps, but they are XmlRpcType %d. " 510 "We'll use the default recovery behaviors instead.",
511 behavior_list[i].getType());
515 if (!behavior_list[i].hasMember(
"name") || !behavior_list[i].hasMember(
"type"))
517 ROS_ERROR(
"Recovery behaviors must have a name and a type and this does not. " 518 "Using the default recovery behaviors instead.");
523 std::string name_i = behavior_list[i][
"name"];
524 for (
int j = i + 1; j < behavior_list.
size(); j++)
531 std::string name_j = behavior_list[j][
"name"];
532 if (name_i == name_j)
534 ROS_ERROR(
"A recovery behavior with the name %s already exists, " 535 "this is not allowed. Using the default recovery behaviors instead.",
544 for (
int i = 0; i < behavior_list.
size(); ++i)
551 if (behavior.get() ==
nullptr)
553 ROS_ERROR(
"The ClassLoader returned a null pointer without throwing an exception. " 554 "This should not happen");
564 ROS_ERROR(
"Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
585 recovery_loader_.createInstance(
"clear_costmap_recovery/ClearCostmapRecovery"));
590 bool clearing_rotation_allowed;
591 n.
param(
"clearing_rotation_allowed", clearing_rotation_allowed,
true);
595 if (clearing_rotation_allowed)
603 recovery_loader_.createInstance(
"clear_costmap_recovery/ClearCostmapRecovery"));
608 if (clearing_rotation_allowed)
613 ROS_FATAL(
"Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s",
633 int main(
int argc,
char** argv)
virtual void setPlan(const nav_2d_msgs::Path2D &path)=0
nav_2d_msgs::Pose2DStamped getLocalRobotPose() const
ros::Timer control_loop_timer_
boost::shared_ptr< const Goal > acceptNewGoal()
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
void publishFeedback(const FeedbackConstPtr &feedback)
ros::NodeHandle private_nh_
nav_core2::LocalPlanner & getCurrentLocalPlanner()
#define ROS_INFO_NAMED(name,...)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_WARN_NAMED(name,...)
locomotor::Locomotor locomotor_
void controlLoopCallback(const ros::TimerEvent &event)
locomotor_msgs::ResultCode makeResultCode(int component=-1, int result_code=-1, const std::string &message="")
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
costmap_2d::Costmap2DROS * planner_costmap_ros_
locomotor::Executor local_planning_ex_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void requestLocalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
void onLocalCostmapUpdate(const ros::Duration &planning_time)
void initializeGlobalPlanners(Executor &ex)
void requestGlobalCostmapUpdate()
void onGlobalCostmapUpdate(const ros::Duration &planning_time)
ros::Time last_valid_plan_
Type const & getType() const
geometry_msgs::Pose2D oscillation_pose_
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration &planning_time)
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > server_
std::exception_ptr NavCore2ExceptionPtr
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
ROSCPP_DECL void spin(Spinner &spinner)
void onNavigationFailure(const locomotor_msgs::ResultCode result)
costmap_2d::Costmap2DROS * getCostmapPointer(const nav_core2::Costmap::Ptr &costmap)
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
#define ROS_DEBUG_NAMED(name,...)
void publishPath(const nav_2d_msgs::Path2D &global_plan)
double poseDistance(const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
ros::Time last_oscillation_reset_
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
void onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
void setGoal(nav_2d_msgs::Pose2DStamped goal)
double oscillation_timeout_
int max_planning_retries_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Duration desired_plan_duration_
void requestNavigationFailure(const locomotor_msgs::ResultCode &result)
void initializeLocalCostmap(Executor &ex)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
LocoMoveBase(const ros::NodeHandle &nh)
void initializeGlobalCostmap(Executor &ex)
void publishZeroVelocity()
ros::Duration desired_control_duration_
double controller_frequency_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string getNamespace(const std::string &s)
Reimplementation of ClassLoader::getName without needing a ClassLoader.
TFListenerPtr getTFListener() const
ros::Time last_valid_control_
void initializeLocalPlanners(Executor &ex)
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
void requestNavigationFailure(Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool hasMember(const std::string &name) const
void planLoopCallback(const ros::TimerEvent &event)
double planner_frequency_
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
bool getParam(const std::string &key, std::string &s) const
unsigned int recovery_index_
#define ROS_FATAL_NAMED(name,...)
ros::Subscriber goal_sub_
nav_core2::Costmap::Ptr getLocalCostmap() const
void onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
std::shared_ptr< Costmap > Ptr
void onNavigationCompleted()
void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration &planning_time)
bool hasParam(const std::string &key) const
std::shared_ptr< tf::TransformListener > TFListenerPtr
double oscillation_distance_
void registerGoalCallback(boost::function< void()> cb)
void onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
nav_core2::Costmap::Ptr getGlobalCostmap() const
ros::Timer plan_loop_timer_
costmap_2d::Costmap2DROS * controller_costmap_ros_
RecoveryTrigger recovery_trigger_
const ros::NodeHandle & loadBackwardsCompatibleParameters(const ros::NodeHandle &nh)
Copy parameter values to get backwards compatibility.
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void requestGlobalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
void onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
locomotor::Executor global_planning_ex_
void requestGlobalPlan(Executor &work_ex, Executor &result_ex, GlobalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr)
void requestLocalPlan(Executor &work_ex, Executor &result_ex, LocalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr, NavigationCompleteCallback complete_cb=nullptr)
bool recovery_behavior_enabled_
double controller_patience_