locomove_base.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef LOCOMOVE_BASE_LOCOMOVE_BASE_H
36 #define LOCOMOVE_BASE_LOCOMOVE_BASE_H
37 
39 #include <locomotor/locomotor.h>
40 #include <move_base_msgs/MoveBaseAction.h>
42 #include <string>
43 #include <vector>
44 
45 namespace locomove_base
46 {
48 {
50 };
51 
53 {
54 public:
55  explicit LocoMoveBase(const ros::NodeHandle& nh);
56  void setGoal(nav_2d_msgs::Pose2DStamped goal);
57  void resetState();
58 protected:
59  void requestNavigationFailure(const locomotor_msgs::ResultCode& result);
60 
61  void planLoopCallback(const ros::TimerEvent& event);
63 
64  void onGlobalCostmapUpdate(const ros::Duration& planning_time);
66 
67  void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration& planning_time);
69 
70  void controlLoopCallback(const ros::TimerEvent& event);
71 
72  void onLocalCostmapUpdate(const ros::Duration& planning_time);
74 
75  void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration& planning_time);
77 
78  void onNavigationCompleted();
79  void onNavigationFailure(const locomotor_msgs::ResultCode result);
80 
81  void publishZeroVelocity();
82 
89 
94 
95  void recovery();
96 
99 
100  // Simple Goal Handling
101  void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal);
103 
104  // MoveBaseAction
105  void executeCB();
106  void preemptCB();
108 
109  // Recoveries
112  std::vector<boost::shared_ptr<nav_core::RecoveryBehavior> > recovery_behaviors_;
113  unsigned int recovery_index_;
115 
116  // Timer Stuff
117  double planner_frequency_ { 10.0 }, controller_frequency_ { 20.0 };
120 
121  // The Two Executors
123 
124  // Patience
126  double planner_patience_ { 5.0 }, controller_patience_ { 15.0 };
128  int max_planning_retries_ {-1}, // disabled by default
130 
131  // Oscillation variables
134  geometry_msgs::Pose2D oscillation_pose_;
135 
136  // Costmap Pointer Copies
140 
141  // Debug Publishing
143 };
144 } // namespace locomove_base
145 
146 #endif // LOCOMOVE_BASE_LOCOMOVE_BASE_H
locomove_base::LocoMoveBase::desired_control_duration_
ros::Duration desired_control_duration_
Definition: locomove_base.h:118
locomove_base
Definition: locomove_base.h:45
locomove_base::PLANNING_R
@ PLANNING_R
Definition: locomove_base.h:49
locomove_base::LocoMoveBase::onNewLocalPlan
void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration &planning_time)
Definition: locomove_base.cpp:366
ros::Publisher
locomove_base::LocoMoveBase::plan_loop_timer_
ros::Timer plan_loop_timer_
Definition: locomove_base.h:119
locomove_base::LocoMoveBase::LocoMoveBase
LocoMoveBase(const ros::NodeHandle &nh)
Definition: locomove_base.cpp:154
locomove_base::LocoMoveBase::recovery
void recovery()
Definition: locomove_base.cpp:440
locomove_base::LocoMoveBase::loadRecoveryBehaviors
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
Definition: locomove_base.cpp:492
locomotor::Executor
locomove_base::LocoMoveBase::controller_frequency_
double controller_frequency_
Definition: locomove_base.h:117
locomove_base::LocoMoveBase::planner_costmap_ros_
costmap_2d::Costmap2DROS * planner_costmap_ros_
Definition: locomove_base.h:138
locomove_base::LocoMoveBase::oscillation_distance_
double oscillation_distance_
Definition: locomove_base.h:132
locomove_base::LocoMoveBase::goal_sub_
ros::Subscriber goal_sub_
Definition: locomove_base.h:102
locomove_base::LocoMoveBase::planner_frequency_
double planner_frequency_
Definition: locomove_base.h:117
locomove_base::LocoMoveBase::loadDefaultRecoveryBehaviors
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
Definition: locomove_base.cpp:577
locomove_base::LocoMoveBase::planLoopCallback
void planLoopCallback(const ros::TimerEvent &event)
Definition: locomove_base.cpp:268
locomove_base::LocoMoveBase::recovery_behaviors_
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
Definition: locomove_base.h:112
locomove_base::LocoMoveBase::getCostmapPointer
costmap_2d::Costmap2DROS * getCostmapPointer(const nav_core2::Costmap::Ptr &costmap)
Definition: locomove_base.cpp:230
locomove_base::LocoMoveBase::control_loop_timer_
ros::Timer control_loop_timer_
Definition: locomove_base.h:119
locomove_base::LocoMoveBase::onLocalCostmapUpdate
void onLocalCostmapUpdate(const ros::Duration &planning_time)
Definition: locomove_base.cpp:343
locomotor::Locomotor
locomove_base::LocoMoveBase::last_valid_plan_
ros::Time last_valid_plan_
Definition: locomove_base.h:127
simple_action_server.h
locomove_base::LocoMoveBase::executeCB
void executeCB()
Definition: locomove_base.cpp:629
locomove_base::LocoMoveBase::requestNavigationFailure
void requestNavigationFailure(const locomotor_msgs::ResultCode &result)
Definition: locomove_base.cpp:262
locomove_base::LocoMoveBase::onNavigationCompleted
void onNavigationCompleted()
Definition: locomove_base.cpp:419
locomove_base::LocoMoveBase::global_planning_ex_
locomotor::Executor global_planning_ex_
Definition: locomove_base.h:122
locomove_base::LocoMoveBase::oscillation_timeout_
double oscillation_timeout_
Definition: locomove_base.h:132
locomove_base::LocoMoveBase::resetState
void resetState()
Definition: locomove_base.cpp:243
locomove_base::LocoMoveBase::server_
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > server_
Definition: locomove_base.h:107
locomove_base::LocoMoveBase::onNavigationFailure
void onNavigationFailure(const locomotor_msgs::ResultCode result)
Definition: locomove_base.cpp:430
locomove_base::LocoMoveBase::recovery_loader_
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
Definition: locomove_base.h:111
nav_core2::NavCore2ExceptionPtr
std::exception_ptr NavCore2ExceptionPtr
locomove_base::LocoMoveBase::last_valid_control_
ros::Time last_valid_control_
Definition: locomove_base.h:127
locomove_base::LocoMoveBase::controller_costmap_ros_
costmap_2d::Costmap2DROS * controller_costmap_ros_
Definition: locomove_base.h:139
locomove_base::LocoMoveBase::onGlobalCostmapUpdate
void onGlobalCostmapUpdate(const ros::Duration &planning_time)
Definition: locomove_base.cpp:280
locomove_base::LocoMoveBase::onGlobalCostmapException
void onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:288
locomove_base::LocoMoveBase::controlLoopCallback
void controlLoopCallback(const ros::TimerEvent &event)
Definition: locomove_base.cpp:336
locomove_base::LocoMoveBase::onNewGlobalPlan
void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration &planning_time)
Definition: locomove_base.cpp:298
locomove_base::LocoMoveBase::max_planning_retries_
int max_planning_retries_
Definition: locomove_base.h:128
locomove_base::LocoMoveBase::has_global_plan_
bool has_global_plan_
Definition: locomove_base.h:125
locomove_base::LocoMoveBase::goal_pub_
ros::Publisher goal_pub_
Definition: locomove_base.h:142
locomove_base::LocoMoveBase::local_planning_ex_
locomotor::Executor local_planning_ex_
Definition: locomove_base.h:122
locomove_base::LocoMoveBase::onGlobalPlanningException
void onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:318
recovery_behavior.h
locomove_base::LocoMoveBase::recovery_index_
unsigned int recovery_index_
Definition: locomove_base.h:113
locomove_base::LocoMoveBase::preemptCB
void preemptCB()
Definition: locomove_base.cpp:635
locomove_base::LocoMoveBase::planner_patience_
double planner_patience_
Definition: locomove_base.h:126
goal
goal
pluginlib::ClassLoader< nav_core::RecoveryBehavior >
ros::TimerEvent
locomove_base::LocoMoveBase::last_oscillation_reset_
ros::Time last_oscillation_reset_
Definition: locomove_base.h:133
locomove_base::LocoMoveBase::requestGlobalCostmapUpdate
void requestGlobalCostmapUpdate()
Definition: locomove_base.cpp:273
locomove_base::LocoMoveBase::recovery_behavior_enabled_
bool recovery_behavior_enabled_
Definition: locomove_base.h:114
locomove_base::LocoMoveBase::controller_patience_
double controller_patience_
Definition: locomove_base.h:126
locomove_base::LocoMoveBase::oscillation_pose_
geometry_msgs::Pose2D oscillation_pose_
Definition: locomove_base.h:134
nav_core2::Costmap::Ptr
std::shared_ptr< Costmap > Ptr
locomove_base::LocoMoveBase::recovery_trigger_
RecoveryTrigger recovery_trigger_
Definition: locomove_base.h:110
ros::Time
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction >
locomove_base::LocoMoveBase::planning_retries_
int planning_retries_
Definition: locomove_base.h:129
locomotor.h
locomove_base::LocoMoveBase::desired_plan_duration_
ros::Duration desired_plan_duration_
Definition: locomove_base.h:118
locomove_base::LocoMoveBase::locomotor_
locomotor::Locomotor locomotor_
Definition: locomove_base.h:98
locomove_base::LocoMoveBase::setGoal
void setGoal(nav_2d_msgs::Pose2DStamped goal)
Definition: locomove_base.cpp:215
locomove_base::RecoveryTrigger
RecoveryTrigger
Definition: locomove_base.h:47
locomove_base::LocoMoveBase::private_nh_
ros::NodeHandle private_nh_
Definition: locomove_base.h:97
locomove_base::LocoMoveBase::onLocalCostmapException
void onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:359
ros::Duration
ros::Timer
locomove_base::LocoMoveBase::onLocalPlanningException
void onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:401
locomove_base::CONTROLLING_R
@ CONTROLLING_R
Definition: locomove_base.h:49
costmap_2d::Costmap2DROS
locomove_base::LocoMoveBase::goalCB
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
Definition: locomove_base.cpp:624
locomove_base::LocoMoveBase::publishZeroVelocity
void publishZeroVelocity()
Definition: locomove_base.cpp:257
locomove_base::OSCILLATION_R
@ OSCILLATION_R
Definition: locomove_base.h:49
ros::NodeHandle
ros::Subscriber
locomove_base::LocoMoveBase
Definition: locomove_base.h:52


locomove_base
Author(s):
autogenerated on Sun May 18 2025 02:47:39