move_base.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef NAV_MOVE_BASE_ACTION_H_
38 #define NAV_MOVE_BASE_ACTION_H_
39 
40 #include <vector>
41 #include <string>
42 
43 #include <ros/ros.h>
44 
46 #include <move_base_msgs/MoveBaseAction.h>
47 
51 #include <geometry_msgs/PoseStamped.h>
53 #include <costmap_2d/costmap_2d.h>
54 #include <nav_msgs/GetPlan.h>
55 
57 #include <std_srvs/Empty.h>
58 
59 #include <dynamic_reconfigure/server.h>
60 #include "move_base/MoveBaseConfig.h"
61 
62 namespace move_base {
63  //typedefs to help us out with the action server so that we don't hace to type so much
65 
66  enum MoveBaseState {
67  PLANNING,
69  CLEARING
70  };
71 
72  enum RecoveryTrigger
73  {
74  PLANNING_R,
77  };
78 
83  class MoveBase {
84  public:
91 
95  virtual ~MoveBase();
96 
102  bool executeCycle(geometry_msgs::PoseStamped& goal);
103 
104  private:
111  bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
112 
119  bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
120 
127  bool makePlan(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
128 
135 
140 
146  void clearCostmapWindows(double size_x, double size_y);
147 
151  void publishZeroVelocity();
152 
156  void resetState();
157 
158  void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal);
159 
160  void planThread();
161 
162  void executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal);
163 
164  bool isQuaternionValid(const geometry_msgs::Quaternion& q);
165 
166  bool getRobotPose(geometry_msgs::PoseStamped& global_pose, costmap_2d::Costmap2DROS* costmap);
167 
168  double distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2);
169 
170  geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg);
171 
175  void wakePlanner(const ros::TimerEvent& event);
176 
178 
180 
183 
185  std::string robot_base_frame_, global_frame_;
186 
187  std::vector<boost::shared_ptr<nav_core::RecoveryBehavior> > recovery_behaviors_;
188  std::vector<std::string> recovery_behavior_names_;
189  unsigned int recovery_index_;
190 
191  geometry_msgs::PoseStamped global_pose_;
194  int32_t max_planning_retries_;
195  uint32_t planning_retries_;
203 
206 
208  geometry_msgs::PoseStamped oscillation_pose_;
212 
213  //set up plan triple buffer
214  std::vector<geometry_msgs::PoseStamped>* planner_plan_;
215  std::vector<geometry_msgs::PoseStamped>* latest_plan_;
216  std::vector<geometry_msgs::PoseStamped>* controller_plan_;
217 
218  //set up the planner's thread
220  boost::recursive_mutex planner_mutex_;
221  boost::condition_variable_any planner_cond_;
222  geometry_msgs::PoseStamped planner_goal_;
223  boost::thread* planner_thread_;
224 
225 
226  boost::recursive_mutex configuration_mutex_;
227  dynamic_reconfigure::Server<move_base::MoveBaseConfig> *dsrv_;
228 
229  void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level);
230 
231  move_base::MoveBaseConfig last_config_;
232  move_base::MoveBaseConfig default_config_;
235  };
236 };
237 #endif
238 
move_base::MoveBase::max_planning_retries_
int32_t max_planning_retries_
Definition: move_base.h:229
move_base::MoveBase::last_valid_control_
ros::Time last_valid_control_
Definition: move_base.h:242
move_base::MoveBase::make_plan_srv_
ros::ServiceServer make_plan_srv_
Definition: move_base.h:234
move_base::MoveBase::blp_loader_
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > blp_loader_
Definition: move_base.h:245
move_base::MoveBase::circumscribed_radius_
double circumscribed_radius_
Definition: move_base.h:227
move_base::MoveBase::global_frame_
std::string global_frame_
Definition: move_base.h:220
move_base::MoveBase::inscribed_radius_
double inscribed_radius_
Definition: move_base.h:227
move_base::MoveBase::resetState
void resetState()
Reset the state of the move_base action and send a zero velocity command to the base.
Definition: move_base.cpp:1182
ros::Publisher
move_base::MoveBase::runPlanner_
bool runPlanner_
Definition: move_base.h:254
move_base::MoveBase::recovery_trigger_
RecoveryTrigger recovery_trigger_
Definition: move_base.h:240
boost::shared_ptr< nav_core::BaseLocalPlanner >
move_base::MoveBase::getRobotPose
bool getRobotPose(geometry_msgs::PoseStamped &global_pose, costmap_2d::Costmap2DROS *costmap)
Definition: move_base.cpp:1202
move_base::MoveBase::dsrv_
dynamic_reconfigure::Server< move_base::MoveBaseConfig > * dsrv_
Definition: move_base.h:262
move_base::MoveBase::planner_mutex_
boost::recursive_mutex planner_mutex_
Definition: move_base.h:255
move_base::MoveBase::controller_plan_
std::vector< geometry_msgs::PoseStamped > * controller_plan_
Definition: move_base.h:251
ros.h
costmap_2d.h
move_base::MoveBase::make_plan_clear_costmap_
bool make_plan_clear_costmap_
Definition: move_base.h:236
move_base::MoveBase::executeCycle
bool executeCycle(geometry_msgs::PoseStamped &goal)
Performs a control cycle.
Definition: move_base.cpp:838
move_base::MoveBase::configuration_mutex_
boost::recursive_mutex configuration_mutex_
Definition: move_base.h:261
move_base::MoveBase::state_
MoveBaseState state_
Definition: move_base.h:239
move_base::MoveBase::controller_patience_
double controller_patience_
Definition: move_base.h:228
move_base::MoveBase::clearing_radius_
double clearing_radius_
Definition: move_base.h:231
move_base::MoveBase::planner_thread_
boost::thread * planner_thread_
Definition: move_base.h:258
move_base::CLEARING
@ CLEARING
Definition: move_base.h:104
move_base::MoveBase::isQuaternionValid
bool isQuaternionValid(const geometry_msgs::Quaternion &q)
Definition: move_base.cpp:548
move_base::CONTROLLING
@ CONTROLLING
Definition: move_base.h:103
simple_action_server.h
move_base::MoveBase::planner_frequency_
double planner_frequency_
Definition: move_base.h:227
move_base::MoveBase::setup_
bool setup_
Definition: move_base.h:268
move_base::MoveBase::conservative_reset_dist_
double conservative_reset_dist_
Definition: move_base.h:231
costmap_2d_ros.h
move_base::MoveBase::executeCb
void executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal)
Definition: move_base.cpp:687
move_base::MoveBase::oscillation_pose_
geometry_msgs::PoseStamped oscillation_pose_
Definition: move_base.h:243
move_base::MoveBase::last_oscillation_reset_
ros::Time last_oscillation_reset_
Definition: move_base.h:242
move_base::MoveBaseActionServer
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
Definition: move_base.h:99
move_base::MoveBase::~MoveBase
virtual ~MoveBase()
Destructor - Cleans up.
Definition: move_base.cpp:483
ros::ServiceServer
move_base::MoveBase::vel_pub_
ros::Publisher vel_pub_
Definition: move_base.h:232
move_base::MoveBase::action_goal_pub_
ros::Publisher action_goal_pub_
Definition: move_base.h:232
move_base::MoveBase::make_plan_add_unreachable_goal_
bool make_plan_add_unreachable_goal_
Definition: move_base.h:236
move_base::MoveBase::planner_cond_
boost::condition_variable_any planner_cond_
Definition: move_base.h:256
move_base::MoveBase::current_goal_pub_
ros::Publisher current_goal_pub_
Definition: move_base.h:232
move_base::MoveBase::bgp_loader_
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > bgp_loader_
Definition: move_base.h:244
base_local_planner.h
move_base::MoveBase::recovery_index_
unsigned int recovery_index_
Definition: move_base.h:224
move_base::MoveBase::recovery_behavior_names_
std::vector< std::string > recovery_behavior_names_
Definition: move_base.h:223
move_base::MoveBase::recovery_status_pub_
ros::Publisher recovery_status_pub_
Definition: move_base.h:232
move_base::MoveBase::loadRecoveryBehaviors
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
Definition: move_base.cpp:1055
move_base::MoveBase::oscillation_timeout_
double oscillation_timeout_
Definition: move_base.h:237
move_base::MoveBase::publishZeroVelocity
void publishZeroVelocity()
Publishes a velocity command of zero to the base.
Definition: move_base.cpp:540
move_base
Definition: move_base.h:62
move_base::MoveBase::controller_frequency_
double controller_frequency_
Definition: move_base.h:227
recovery_behavior.h
move_base::MoveBase::recovery_behavior_enabled_
bool recovery_behavior_enabled_
Definition: move_base.h:235
move_base::MoveBase::last_config_
move_base::MoveBaseConfig last_config_
Definition: move_base.h:266
tf2_ros::Buffer
move_base::MoveBase::wakePlanner
void wakePlanner(const ros::TimerEvent &event)
This is used to wake the planner at periodic intervals.
Definition: move_base.cpp:599
move_base::PLANNING
@ PLANNING
Definition: move_base.h:102
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner >
move_base::MoveBase::planner_
boost::shared_ptr< nav_core::BaseGlobalPlanner > planner_
Definition: move_base.h:219
move_base::MoveBase::planner_costmap_ros_
costmap_2d::Costmap2DROS * planner_costmap_ros_
Definition: move_base.h:217
class_loader.hpp
ros::TimerEvent
move_base::MoveBase::recovery_behaviors_
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
Definition: move_base.h:222
move_base::MoveBase::shutdown_costmaps_
bool shutdown_costmaps_
Definition: move_base.h:235
move_base::MoveBase::planner_plan_
std::vector< geometry_msgs::PoseStamped > * planner_plan_
Definition: move_base.h:249
move_base::MoveBase::MoveBase
MoveBase(tf2_ros::Buffer &tf)
Constructor for the actions.
Definition: move_base.cpp:87
move_base::MoveBase::last_valid_plan_
ros::Time last_valid_plan_
Definition: move_base.h:242
move_base::MoveBase::goalToGlobalFrame
geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg)
Definition: move_base.cpp:578
move_base::MoveBase::latest_plan_
std::vector< geometry_msgs::PoseStamped > * latest_plan_
Definition: move_base.h:250
move_base::MoveBase::controller_costmap_ros_
costmap_2d::Costmap2DROS * controller_costmap_ros_
Definition: move_base.h:217
move_base::PLANNING_R
@ PLANNING_R
Definition: move_base.h:109
ros::Time
move_base::MoveBase::new_global_plan_
bool new_global_plan_
Definition: move_base.h:269
move_base::MoveBase::clearing_rotation_allowed_
bool clearing_rotation_allowed_
Definition: move_base.h:235
base_global_planner.h
move_base::MoveBase::planThread
void planThread()
Definition: move_base.cpp:605
actionlib::SimpleActionServer
move_base::MoveBase::recovery_loader_
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
Definition: move_base.h:246
move_base::OSCILLATION_R
@ OSCILLATION_R
Definition: move_base.h:111
move_base::MoveBase::global_pose_
geometry_msgs::PoseStamped global_pose_
Definition: move_base.h:226
move_base::MoveBase::robot_base_frame_
std::string robot_base_frame_
Definition: move_base.h:220
tf
move_base::MoveBase::oscillation_distance_
double oscillation_distance_
Definition: move_base.h:237
move_base::MoveBase::planner_goal_
geometry_msgs::PoseStamped planner_goal_
Definition: move_base.h:257
move_base::MoveBase::default_config_
move_base::MoveBaseConfig default_config_
Definition: move_base.h:267
move_base::MoveBase::planning_retries_
uint32_t planning_retries_
Definition: move_base.h:230
move_base::MoveBase::tc_
boost::shared_ptr< nav_core::BaseLocalPlanner > tc_
Definition: move_base.h:216
move_base::MoveBase::c_freq_change_
bool c_freq_change_
Definition: move_base.h:268
move_base::MoveBase::goal_sub_
ros::Subscriber goal_sub_
Definition: move_base.h:233
move_base::MoveBaseState
MoveBaseState
Definition: move_base.h:101
move_base::MoveBase::planService
bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
A service call that can be made when the action is inactive that will return a plan.
Definition: move_base.cpp:386
move_base::MoveBase::tf_
tf2_ros::Buffer & tf_
Definition: move_base.h:212
move_base::MoveBase::as_
MoveBaseActionServer * as_
Definition: move_base.h:214
move_base::MoveBase::loadDefaultRecoveryBehaviors
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
Definition: move_base.cpp:1141
move_base::MoveBase::distance
double distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
Definition: move_base.cpp:833
move_base::MoveBase::clear_costmaps_srv_
ros::ServiceServer clear_costmaps_srv_
Definition: move_base.h:234
move_base::MoveBase::p_freq_change_
bool p_freq_change_
Definition: move_base.h:268
move_base::MoveBase::planner_patience_
double planner_patience_
Definition: move_base.h:228
costmap_2d::Costmap2DROS
move_base::MoveBase
A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location.
Definition: move_base.h:118
move_base::MoveBase::reconfigureCB
void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level)
Definition: move_base.cpp:218
move_base::MoveBase::clearCostmapsService
bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
A service call that clears the costmaps of obstacles.
Definition: move_base.cpp:375
ros::NodeHandle
ros::Subscriber
move_base::MoveBase::goalCB
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
Definition: move_base.cpp:311
move_base::RecoveryTrigger
RecoveryTrigger
Definition: move_base.h:107
move_base::MoveBase::clearCostmapWindows
void clearCostmapWindows(double size_x, double size_y)
Clears obstacles within a window around the robot.
Definition: move_base.cpp:320
move_base::CONTROLLING_R
@ CONTROLLING_R
Definition: move_base.h:110
move_base::MoveBase::makePlan
bool makePlan(const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Make a new global plan.
Definition: move_base.cpp:510


move_base
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:45