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 
56 #include <pluginlib/class_loader.h>
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 
70  };
71 
73  {
77  };
78 
83  class MoveBase {
84  public:
91 
95  virtual ~MoveBase();
96 
103  bool executeCycle(geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& global_plan);
104 
105  private:
112  bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
113 
120  bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
121 
128  bool makePlan(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
129 
136 
141 
147  void clearCostmapWindows(double size_x, double size_y);
148 
152  void publishZeroVelocity();
153 
157  void resetState();
158 
159  void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal);
160 
161  void planThread();
162 
163  void executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal);
164 
165  bool isQuaternionValid(const geometry_msgs::Quaternion& q);
166 
167  double distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2);
168 
169  geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg);
170 
174  void wakePlanner(const ros::TimerEvent& event);
175 
177 
178  MoveBaseActionServer* as_;
179 
182 
185 
186  std::vector<boost::shared_ptr<nav_core::RecoveryBehavior> > recovery_behaviors_;
187  std::vector<std::string> recovery_behavior_names_;
188  unsigned int recovery_index_;
189 
201 
204 
206  geometry_msgs::PoseStamped oscillation_pose_;
210 
211  //set up plan triple buffer
212  std::vector<geometry_msgs::PoseStamped>* planner_plan_;
213  std::vector<geometry_msgs::PoseStamped>* latest_plan_;
214  std::vector<geometry_msgs::PoseStamped>* controller_plan_;
215 
216  //set up the planner's thread
218  boost::recursive_mutex planner_mutex_;
219  boost::condition_variable_any planner_cond_;
220  geometry_msgs::PoseStamped planner_goal_;
221  boost::thread* planner_thread_;
222 
223 
224  boost::recursive_mutex configuration_mutex_;
225  dynamic_reconfigure::Server<move_base::MoveBaseConfig> *dsrv_;
226 
227  void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level);
228 
229  move_base::MoveBaseConfig last_config_;
230  move_base::MoveBaseConfig default_config_;
233  };
234 };
235 #endif
236 
void executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal)
Definition: move_base.cpp:641
boost::condition_variable_any planner_cond_
Definition: move_base.h:219
boost::thread * planner_thread_
Definition: move_base.h:221
void wakePlanner(const ros::TimerEvent &event)
This is used to wake the planner at periodic intervals.
Definition: move_base.cpp:553
ros::ServiceServer make_plan_srv_
Definition: move_base.h:198
double distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
Definition: move_base.cpp:787
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > blp_loader_
Definition: move_base.h:208
MoveBaseActionServer * as_
Definition: move_base.h:178
bool isQuaternionValid(const geometry_msgs::Quaternion &q)
Definition: move_base.cpp:500
costmap_2d::Costmap2DROS * controller_costmap_ros_
Definition: move_base.h:181
int32_t max_planning_retries_
Definition: move_base.h:193
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:341
double clearing_radius_
Definition: move_base.h:195
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > bgp_loader_
Definition: move_base.h:207
boost::recursive_mutex configuration_mutex_
Definition: move_base.h:224
double planner_frequency_
Definition: move_base.h:191
double inscribed_radius_
Definition: move_base.h:191
ros::Publisher action_goal_pub_
Definition: move_base.h:196
virtual ~MoveBase()
Destructor - Cleans up.
Definition: move_base.cpp:434
ros::Time last_oscillation_reset_
Definition: move_base.h:205
bool recovery_behavior_enabled_
Definition: move_base.h:199
ros::Publisher vel_pub_
Definition: move_base.h:196
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
Definition: move_base.h:64
std::string global_frame_
Definition: move_base.h:184
tf::Stamped< tf::Pose > global_pose_
Definition: move_base.h:190
std::vector< geometry_msgs::PoseStamped > * planner_plan_
Definition: move_base.h:212
boost::shared_ptr< nav_core::BaseGlobalPlanner > planner_
Definition: move_base.h:183
double planner_patience_
Definition: move_base.h:192
bool clearing_rotation_allowed_
Definition: move_base.h:199
unsigned int recovery_index_
Definition: move_base.h:188
dynamic_reconfigure::Server< move_base::MoveBaseConfig > * dsrv_
Definition: move_base.h:225
RecoveryTrigger recovery_trigger_
Definition: move_base.h:203
ros::Publisher recovery_status_pub_
Definition: move_base.h:196
ros::ServiceServer clear_costmaps_srv_
Definition: move_base.h:198
move_base::MoveBaseConfig default_config_
Definition: move_base.h:230
ros::Time last_valid_plan_
Definition: move_base.h:205
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
Definition: move_base.cpp:1096
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
Definition: move_base.h:186
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
Definition: move_base.cpp:1010
void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level)
Definition: move_base.cpp:176
double controller_patience_
Definition: move_base.h:192
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
Definition: move_base.cpp:266
A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location...
Definition: move_base.h:83
RecoveryTrigger
Definition: move_base.h:72
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
Definition: move_base.h:209
double controller_frequency_
Definition: move_base.h:191
costmap_2d::Costmap2DROS * planner_costmap_ros_
Definition: move_base.h:181
boost::recursive_mutex planner_mutex_
Definition: move_base.h:218
void publishZeroVelocity()
Publishes a velocity command of zero to the base.
Definition: move_base.cpp:492
geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg)
Definition: move_base.cpp:530
double oscillation_distance_
Definition: move_base.h:200
boost::shared_ptr< nav_core::BaseLocalPlanner > tc_
Definition: move_base.h:180
void resetState()
Reset the state of the move_base action and send a zero velocity command to the base.
Definition: move_base.cpp:1137
ros::Publisher current_goal_pub_
Definition: move_base.h:196
geometry_msgs::PoseStamped planner_goal_
Definition: move_base.h:220
MoveBaseState state_
Definition: move_base.h:202
ros::Subscriber goal_sub_
Definition: move_base.h:197
tf::TransformListener & tf_
Definition: move_base.h:176
std::vector< geometry_msgs::PoseStamped > * latest_plan_
Definition: move_base.h:213
move_base::MoveBaseConfig last_config_
Definition: move_base.h:229
MoveBase(tf::TransformListener &tf)
Constructor for the actions.
Definition: move_base.cpp:49
std::vector< std::string > recovery_behavior_names_
Definition: move_base.h:187
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:330
uint32_t planning_retries_
Definition: move_base.h:194
double circumscribed_radius_
Definition: move_base.h:191
std::string robot_base_frame_
Definition: move_base.h:184
bool makePlan(const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Make a new global plan.
Definition: move_base.cpp:461
double conservative_reset_dist_
Definition: move_base.h:195
bool executeCycle(geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &global_plan)
Performs a control cycle.
Definition: move_base.cpp:792
ros::Time last_valid_control_
Definition: move_base.h:205
double oscillation_timeout_
Definition: move_base.h:200
geometry_msgs::PoseStamped oscillation_pose_
Definition: move_base.h:206
void clearCostmapWindows(double size_x, double size_y)
Clears obstacles within a window around the robot.
Definition: move_base.cpp:275
std::vector< geometry_msgs::PoseStamped > * controller_plan_
Definition: move_base.h:214


move_base
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:06:13