rotate_recovery.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 *********************************************************************/
39 #include <ros/ros.h>
40 #include <geometry_msgs/Twist.h>
41 #include <geometry_msgs/Point.h>
42 #include <angles/angles.h>
43 #include <algorithm>
44 #include <string>
45 
46 
47 // register this planner as a RecoveryBehavior plugin
49 
50 namespace rotate_recovery
51 {
52 RotateRecovery::RotateRecovery(): local_costmap_(NULL), initialized_(false), world_model_(NULL)
53 {
54 }
55 
58 {
59  if (!initialized_)
60  {
61  local_costmap_ = local_costmap;
62 
63  // get some parameters from the parameter server
64  ros::NodeHandle private_nh("~/" + name);
65  ros::NodeHandle blp_nh("~/TrajectoryPlannerROS");
66 
67  // we'll simulate every degree by default
68  private_nh.param("sim_granularity", sim_granularity_, 0.017);
69  private_nh.param("frequency", frequency_, 20.0);
70 
71  blp_nh.param("acc_lim_th", acc_lim_th_, 3.2);
72  blp_nh.param("max_rotational_vel", max_rotational_vel_, 1.0);
73  blp_nh.param("min_in_place_rotational_vel", min_rotational_vel_, 0.4);
74  blp_nh.param("yaw_goal_tolerance", tolerance_, 0.10);
75 
77 
78  initialized_ = true;
79  }
80  else
81  {
82  ROS_ERROR("You should not call initialize twice on this object, doing nothing");
83  }
84 }
85 
87 {
88  delete world_model_;
89 }
90 
92 {
93  if (!initialized_)
94  {
95  ROS_ERROR("This object must be initialized before runBehavior is called");
96  return;
97  }
98 
99  if (local_costmap_ == NULL)
100  {
101  ROS_ERROR("The costmap passed to the RotateRecovery object cannot be NULL. Doing nothing.");
102  return;
103  }
104  ROS_WARN("Rotate recovery behavior started.");
105 
107  ros::NodeHandle n;
108  ros::Publisher vel_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 10);
109 
110  tf::Stamped<tf::Pose> global_pose;
111  local_costmap_->getRobotPose(global_pose);
112 
113  double current_angle = tf::getYaw(global_pose.getRotation());
114  double start_angle = current_angle;
115 
116  bool got_180 = false;
117 
118  while (n.ok() &&
119  (!got_180 ||
120  std::fabs(angles::shortest_angular_distance(current_angle, start_angle)) > tolerance_))
121  {
122  // Update Current Angle
123  local_costmap_->getRobotPose(global_pose);
124  current_angle = tf::getYaw(global_pose.getRotation());
125 
126  // compute the distance left to rotate
127  double dist_left;
128  if (!got_180)
129  {
130  // If we haven't hit 180 yet, we need to rotate a half circle plus the distance to the 180 point
131  double distance_to_180 = std::fabs(angles::shortest_angular_distance(current_angle, start_angle + M_PI));
132  dist_left = M_PI + distance_to_180;
133 
134  if (distance_to_180 < tolerance_)
135  {
136  got_180 = true;
137  }
138  }
139  else
140  {
141  // If we have hit the 180, we just have the distance back to the start
142  dist_left = std::fabs(angles::shortest_angular_distance(current_angle, start_angle));
143  }
144 
145  double x = global_pose.getOrigin().x(), y = global_pose.getOrigin().y();
146 
147  // check if that velocity is legal by forward simulating
148  double sim_angle = 0.0;
149  while (sim_angle < dist_left)
150  {
151  double theta = current_angle + sim_angle;
152 
153  // make sure that the point is legal, if it isn't... we'll abort
154  double footprint_cost = world_model_->footprintCost(x, y, theta, local_costmap_->getRobotFootprint(), 0.0, 0.0);
155  if (footprint_cost < 0.0)
156  {
157  ROS_ERROR("Rotate recovery can't rotate in place because there is a potential collision. Cost: %.2f",
158  footprint_cost);
159  return;
160  }
161 
162  sim_angle += sim_granularity_;
163  }
164 
165  // compute the velocity that will let us stop by the time we reach the goal
166  double vel = sqrt(2 * acc_lim_th_ * dist_left);
167 
168  // make sure that this velocity falls within the specified limits
169  vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_);
170 
171  geometry_msgs::Twist cmd_vel;
172  cmd_vel.linear.x = 0.0;
173  cmd_vel.linear.y = 0.0;
174  cmd_vel.angular.z = vel;
175 
176  vel_pub.publish(cmd_vel);
177 
178  r.sleep();
179  }
180 }
181 }; // namespace rotate_recovery
void publish(const boost::shared_ptr< M > &message) const
base_local_planner::CostmapModel * world_model_
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
~RotateRecovery()
Destructor for the rotate recovery behavior.
static double getYaw(const Quaternion &bt_q)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
void runBehavior()
Run the RotateRecovery recovery behavior.
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
costmap_2d::Costmap2DROS * local_costmap_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
bool sleep()
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
bool ok() const
Costmap2D * getCostmap()
std::vector< geometry_msgs::Point > getRobotFootprint()
A recovery behavior that rotates the robot in-place to attempt to clear out space.
#define ROS_ERROR(...)
def shortest_angular_distance(from_angle, to_angle)
void initialize(std::string name, tf::TransformListener *, costmap_2d::Costmap2DROS *, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the RotateRecovery recovery behavior.


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