dwa_planner_ros.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, 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 Willow Garage, Inc. 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 
39 #include <Eigen/Core>
40 #include <cmath>
41 
42 #include <ros/console.h>
43 
45 
47 #include <nav_msgs/Path.h>
48 #include <tf2/utils.h>
49 
51 
52 //register this planner as a BaseLocalPlanner plugin
54 
55 namespace dwa_local_planner {
56 
57  void DWAPlannerROS::reconfigureCB(DWAPlannerConfig &config, uint32_t level) {
58  if (setup_ && config.restore_defaults) {
59  config = default_config_;
60  config.restore_defaults = false;
61  }
62  if ( ! setup_) {
63  default_config_ = config;
64  setup_ = true;
65  }
66 
67  // update generic local planner params
69  limits.max_vel_trans = config.max_vel_trans;
70  limits.min_vel_trans = config.min_vel_trans;
71  limits.max_vel_x = config.max_vel_x;
72  limits.min_vel_x = config.min_vel_x;
73  limits.max_vel_y = config.max_vel_y;
74  limits.min_vel_y = config.min_vel_y;
75  limits.max_vel_theta = config.max_vel_theta;
76  limits.min_vel_theta = config.min_vel_theta;
77  limits.acc_lim_x = config.acc_lim_x;
78  limits.acc_lim_y = config.acc_lim_y;
79  limits.acc_lim_theta = config.acc_lim_theta;
80  limits.acc_lim_trans = config.acc_lim_trans;
81  limits.xy_goal_tolerance = config.xy_goal_tolerance;
82  limits.yaw_goal_tolerance = config.yaw_goal_tolerance;
83  limits.prune_plan = config.prune_plan;
84  limits.trans_stopped_vel = config.trans_stopped_vel;
85  limits.theta_stopped_vel = config.theta_stopped_vel;
87 
88  // update dwa specific configuration
89  dp_->reconfigure(config);
90  }
91 
93  odom_helper_("odom"), setup_(false) {
94 
95  }
96 
98  std::string name,
100  costmap_2d::Costmap2DROS* costmap_ros) {
101  if (! isInitialized()) {
102 
103  ros::NodeHandle private_nh("~/" + name);
104  g_plan_pub_ = private_nh.advertise<nav_msgs::Path>("global_plan", 1);
105  l_plan_pub_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
106  tf_ = tf;
107  costmap_ros_ = costmap_ros;
109 
110  // make sure to update the costmap we'll use for this cycle
112 
114 
115  //create the actual planner that we'll use.. it'll configure itself from the parameter server
117 
118  if( private_nh.getParam( "odom_topic", odom_topic_ ))
119  {
121  }
122 
123  initialized_ = true;
124 
125  // Warn about deprecated parameters -- remove this block in N-turtle
126  nav_core::warnRenamedParameter(private_nh, "max_vel_trans", "max_trans_vel");
127  nav_core::warnRenamedParameter(private_nh, "min_vel_trans", "min_trans_vel");
128  nav_core::warnRenamedParameter(private_nh, "max_vel_theta", "max_rot_vel");
129  nav_core::warnRenamedParameter(private_nh, "min_vel_theta", "min_rot_vel");
130  nav_core::warnRenamedParameter(private_nh, "acc_lim_trans", "acc_limit_trans");
131  nav_core::warnRenamedParameter(private_nh, "theta_stopped_vel", "rot_stopped_vel");
132 
133  dsrv_ = new dynamic_reconfigure::Server<DWAPlannerConfig>(private_nh);
134  dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = boost::bind(&DWAPlannerROS::reconfigureCB, this, _1, _2);
135  dsrv_->setCallback(cb);
136  }
137  else{
138  ROS_WARN("This planner has already been initialized, doing nothing.");
139  }
140  }
141 
142  bool DWAPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
143  if (! isInitialized()) {
144  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
145  return false;
146  }
147  //when we get a new plan, we also want to clear any latch we may have on goal tolerances
149 
150  ROS_INFO("Got new plan");
151  return dp_->setPlan(orig_global_plan);
152  }
153 
155  if (! isInitialized()) {
156  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
157  return false;
158  }
160  ROS_ERROR("Could not get robot pose");
161  return false;
162  }
163 
165  ROS_INFO("Goal reached");
166  return true;
167  } else {
168  return false;
169  }
170  }
171 
172  void DWAPlannerROS::publishLocalPlan(std::vector<geometry_msgs::PoseStamped>& path) {
174  }
175 
176 
177  void DWAPlannerROS::publishGlobalPlan(std::vector<geometry_msgs::PoseStamped>& path) {
179  }
180 
182  //make sure to clean things up
183  delete dsrv_;
184  }
185 
186 
187 
188  bool DWAPlannerROS::dwaComputeVelocityCommands(geometry_msgs::PoseStamped &global_pose, geometry_msgs::Twist& cmd_vel) {
189  // dynamic window sampling approach to get useful velocity commands
190  if(! isInitialized()){
191  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
192  return false;
193  }
194 
195  geometry_msgs::PoseStamped robot_vel;
196  odom_helper_.getRobotVel(robot_vel);
197 
198  /* For timing uncomment
199  struct timeval start, end;
200  double start_t, end_t, t_diff;
201  gettimeofday(&start, NULL);
202  */
203 
204  //compute what trajectory to drive along
205  geometry_msgs::PoseStamped drive_cmds;
206  drive_cmds.header.frame_id = costmap_ros_->getBaseFrameID();
207 
208  // call with updated footprint
209  base_local_planner::Trajectory path = dp_->findBestPath(global_pose, robot_vel, drive_cmds);
210  //ROS_ERROR("Best: %.2f, %.2f, %.2f, %.2f", path.xv_, path.yv_, path.thetav_, path.cost_);
211 
212  /* For timing uncomment
213  gettimeofday(&end, NULL);
214  start_t = start.tv_sec + double(start.tv_usec) / 1e6;
215  end_t = end.tv_sec + double(end.tv_usec) / 1e6;
216  t_diff = end_t - start_t;
217  ROS_INFO("Cycle time: %.9f", t_diff);
218  */
219 
220  //pass along drive commands
221  cmd_vel.linear.x = drive_cmds.pose.position.x;
222  cmd_vel.linear.y = drive_cmds.pose.position.y;
223  cmd_vel.angular.z = tf2::getYaw(drive_cmds.pose.orientation);
224 
225  //if we cannot move... tell someone
226  std::vector<geometry_msgs::PoseStamped> local_plan;
227  if(path.cost_ < 0) {
228  ROS_DEBUG_NAMED("dwa_local_planner",
229  "The dwa local planner failed to find a valid plan, cost functions discarded all candidates. This can mean there is an obstacle too close to the robot.");
230  local_plan.clear();
231  publishLocalPlan(local_plan);
232  return false;
233  }
234 
235  ROS_DEBUG_NAMED("dwa_local_planner", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.",
236  cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
237 
238  // Fill out the local plan
239  for(unsigned int i = 0; i < path.getPointsSize(); ++i) {
240  double p_x, p_y, p_th;
241  path.getPoint(i, p_x, p_y, p_th);
242 
243  geometry_msgs::PoseStamped p;
244  p.header.frame_id = costmap_ros_->getGlobalFrameID();
245  p.header.stamp = ros::Time::now();
246  p.pose.position.x = p_x;
247  p.pose.position.y = p_y;
248  p.pose.position.z = 0.0;
249  tf2::Quaternion q;
250  q.setRPY(0, 0, p_th);
251  tf2::convert(q, p.pose.orientation);
252  local_plan.push_back(p);
253  }
254 
255  //publish information to the visualizer
256 
257  publishLocalPlan(local_plan);
258  return true;
259  }
260 
261 
262 
263 
264  bool DWAPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel) {
265  // dispatches to either dwa sampling control or stop and rotate control, depending on whether we have been close enough to goal
267  ROS_ERROR("Could not get robot pose");
268  return false;
269  }
270  std::vector<geometry_msgs::PoseStamped> transformed_plan;
271  if ( ! planner_util_.getLocalPlan(current_pose_, transformed_plan)) {
272  ROS_ERROR("Could not get local plan");
273  return false;
274  }
275 
276  //if the global plan passed in is empty... we won't do anything
277  if(transformed_plan.empty()) {
278  ROS_WARN_NAMED("dwa_local_planner", "Received an empty transformed plan.");
279  return false;
280  }
281  ROS_DEBUG_NAMED("dwa_local_planner", "Received a transformed plan with %zu points.", transformed_plan.size());
282 
283  // update plan in dwa_planner even if we just stop and rotate, to allow checkTrajectory
284  dp_->updatePlanAndLocalCosts(current_pose_, transformed_plan, costmap_ros_->getRobotFootprint());
285 
287  //publish an empty plan because we've reached our goal position
288  std::vector<geometry_msgs::PoseStamped> local_plan;
289  std::vector<geometry_msgs::PoseStamped> transformed_plan;
290  publishGlobalPlan(transformed_plan);
291  publishLocalPlan(local_plan);
294  cmd_vel,
295  limits.getAccLimits(),
296  dp_->getSimPeriod(),
297  &planner_util_,
298  odom_helper_,
300  boost::bind(&DWAPlanner::checkTrajectory, dp_, _1, _2, _3));
301  } else {
302  bool isOk = dwaComputeVelocityCommands(current_pose_, cmd_vel);
303  if (isOk) {
304  publishGlobalPlan(transformed_plan);
305  } else {
306  ROS_WARN_NAMED("dwa_local_planner", "DWA planner failed to produce path.");
307  std::vector<geometry_msgs::PoseStamped> empty_plan;
308  publishGlobalPlan(empty_plan);
309  }
310  return isOk;
311  }
312  }
313 
314 
315 };
boost::shared_ptr< DWAPlanner > dp_
The trajectory controller.
void reconfigureCB(DWAPlannerConfig &config, uint32_t level)
Callback to update the local planner&#39;s parameters based on dynamic reconfigure.
bool getLocalPlan(const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
void warnRenamedParameter(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name)
#define ROS_WARN_NAMED(name,...)
void reconfigureCB(LocalPlannerLimits &config, bool restore_defaults)
dynamic_reconfigure::Server< DWAPlannerConfig > * dsrv_
void initialize(tf2_ros::Buffer *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
std::string getGlobalFrameID()
bool isPositionReached(LocalPlannerUtil *planner_util, const geometry_msgs::PoseStamped &global_pose)
geometry_msgs::PoseStamped current_pose_
unsigned int getPointsSize() const
base_local_planner::OdometryHelperRos odom_helper_
void getPoint(unsigned int index, double &x, double &y, double &th) const
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose)
#define ROS_WARN(...)
base_local_planner::LatchedStopRotateController latchedStopRotateController_
ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a pl...
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
bool computeVelocityCommandsStopRotate(geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, const geometry_msgs::PoseStamped &global_pose, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check)
#define ROS_DEBUG_NAMED(name,...)
A class implementing a local planner using the Dynamic Window Approach.
Definition: dwa_planner.h:70
costmap_2d::Costmap2DROS * costmap_ros_
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
LocalPlannerLimits getCurrentLimits()
std::string getBaseFrameID()
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
double getYaw(const A &a)
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
dwa_local_planner::DWAPlannerConfig default_config_
tf2_ros::Buffer * tf_
Used for transforming point clouds.
void publishLocalPlan(std::vector< geometry_msgs::PoseStamped > &path)
static Time now()
void convert(const A &a, B &b)
void setOdomTopic(std::string odom_topic)
void publishGlobalPlan(std::vector< geometry_msgs::PoseStamped > &path)
~DWAPlannerROS()
Destructor for the wrapper.
void getRobotVel(geometry_msgs::PoseStamped &robot_vel)
bool dwaComputeVelocityCommands(geometry_msgs::PoseStamped &global_pose, geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Costmap2D * getCostmap()
DWAPlannerROS()
Constructor for DWAPlannerROS wrapper.
std::vector< geometry_msgs::Point > getRobotFootprint()
bool isGoalReached()
Check if the goal pose has been achieved.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
base_local_planner::LocalPlannerUtil planner_util_
bool checkTrajectory(const Eigen::Vector3f pos, const Eigen::Vector3f vel, const Eigen::Vector3f vel_samples)
Check if a trajectory is legal for a position/velocity pair.


dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:15