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 
40 //register this planner as a RecoveryBehavior plugin
42 
43 namespace rotate_recovery {
44 RotateRecovery::RotateRecovery(): global_costmap_(NULL), local_costmap_(NULL),
45  tf_(NULL), initialized_(false), world_model_(NULL) {}
46 
48  costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap){
49  if(!initialized_){
50  name_ = name;
51  tf_ = tf;
52  global_costmap_ = global_costmap;
53  local_costmap_ = local_costmap;
54 
55  //get some parameters from the parameter server
56  ros::NodeHandle private_nh("~/" + name_);
57  ros::NodeHandle blp_nh("~/TrajectoryPlannerROS");
58 
59  //we'll simulate every degree by default
60  private_nh.param("sim_granularity", sim_granularity_, 0.017);
61  private_nh.param("frequency", frequency_, 20.0);
62 
63  blp_nh.param("acc_lim_th", acc_lim_th_, 3.2);
64  blp_nh.param("max_rotational_vel", max_rotational_vel_, 1.0);
65  blp_nh.param("min_in_place_rotational_vel", min_rotational_vel_, 0.4);
66  blp_nh.param("yaw_goal_tolerance", tolerance_, 0.10);
67 
69 
70  initialized_ = true;
71  }
72  else{
73  ROS_ERROR("You should not call initialize twice on this object, doing nothing");
74  }
75 }
76 
78  delete world_model_;
79 }
80 
82  if(!initialized_){
83  ROS_ERROR("This object must be initialized before runBehavior is called");
84  return;
85  }
86 
87  if(global_costmap_ == NULL || local_costmap_ == NULL){
88  ROS_ERROR("The costmaps passed to the RotateRecovery object cannot be NULL. Doing nothing.");
89  return;
90  }
91  ROS_WARN("Rotate recovery behavior started.");
92 
95  ros::Publisher vel_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 10);
96 
97  tf::Stamped<tf::Pose> global_pose;
98  local_costmap_->getRobotPose(global_pose);
99 
100  double current_angle = -1.0 * M_PI;
101 
102  bool got_180 = false;
103 
104  double start_offset = 0 - angles::normalize_angle(tf::getYaw(global_pose.getRotation()));
105  while(n.ok()){
106  local_costmap_->getRobotPose(global_pose);
107 
108  double norm_angle = angles::normalize_angle(tf::getYaw(global_pose.getRotation()));
109  current_angle = angles::normalize_angle(norm_angle + start_offset);
110 
111  //compute the distance left to rotate
112  double dist_left = M_PI - current_angle;
113 
114  double x = global_pose.getOrigin().x(), y = global_pose.getOrigin().y();
115 
116  //check if that velocity is legal by forward simulating
117  double sim_angle = 0.0;
118  while(sim_angle < dist_left){
119  double theta = tf::getYaw(global_pose.getRotation()) + sim_angle;
120 
121  //make sure that the point is legal, if it isn't... we'll abort
122  double footprint_cost = world_model_->footprintCost(x, y, theta, local_costmap_->getRobotFootprint(), 0.0, 0.0);
123  if(footprint_cost < 0.0){
124  ROS_ERROR("Rotate recovery can't rotate in place because there is a potential collision. Cost: %.2f", footprint_cost);
125  return;
126  }
127 
128  sim_angle += sim_granularity_;
129  }
130 
131  //compute the velocity that will let us stop by the time we reach the goal
132  double vel = sqrt(2 * acc_lim_th_ * dist_left);
133 
134  //make sure that this velocity falls within the specified limits
135  vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_);
136 
137  geometry_msgs::Twist cmd_vel;
138  cmd_vel.linear.x = 0.0;
139  cmd_vel.linear.y = 0.0;
140  cmd_vel.angular.z = vel;
141 
142  vel_pub.publish(cmd_vel);
143 
144  //makes sure that we won't decide we're done right after we start
145  if(current_angle < 0.0)
146  got_180 = true;
147 
148  //if we're done with our in-place rotation... then return
149  if(got_180 && current_angle >= (0.0 - tolerance_))
150  return;
151 
152  r.sleep();
153  }
154 }
155 };
tf::TransformListener * tf_
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.
costmap_2d::Costmap2DROS * global_costmap_
static double getYaw(const Quaternion &bt_q)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
costmap_2d::Costmap2DROS * local_costmap_
void runBehavior()
Run the RotateRecovery recovery behavior.
tf::TransformListener * tf_
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
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)
def normalize_angle(angle)
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(...)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the RotateRecovery recovery behavior.


rotate_recovery
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:46