latched_stop_rotate_controller.cpp
Go to the documentation of this file.
1 /*
2  * latched_stop_rotate_controller.cpp
3  *
4  * Created on: Apr 16, 2012
5  * Author: tkruse
6  */
7 
9 
10 #include <cmath>
11 
12 #include <Eigen/Core>
13 
14 #include <angles/angles.h>
15 #include <nav_msgs/Odometry.h>
16 
19 
20 namespace base_local_planner {
21 
23  ros::NodeHandle private_nh("~/" + name);
24  private_nh.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false);
25 
26  rotating_to_goal_ = false;
27 }
28 
30 
31 
38  tf::Stamped<tf::Pose> global_pose) {
39  double xy_goal_tolerance = planner_util->getCurrentLimits().xy_goal_tolerance;
40 
41  //we assume the global goal is the last point in the global plan
42  tf::Stamped<tf::Pose> goal_pose;
43  if ( ! planner_util->getGoal(goal_pose)) {
44  return false;
45  }
46 
47  double goal_x = goal_pose.getOrigin().getX();
48  double goal_y = goal_pose.getOrigin().getY();
49 
50  //check to see if we've reached the goal position
52  base_local_planner::getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) {
53  xy_tolerance_latch_ = true;
54  return true;
55  }
56  return false;
57 }
58 
59 
65  OdometryHelperRos& odom_helper,
66  tf::Stamped<tf::Pose> global_pose) {
67  double xy_goal_tolerance = planner_util->getCurrentLimits().xy_goal_tolerance;
68  double rot_stopped_vel = planner_util->getCurrentLimits().rot_stopped_vel;
69  double trans_stopped_vel = planner_util->getCurrentLimits().trans_stopped_vel;
70 
71  //copy over the odometry information
72  nav_msgs::Odometry base_odom;
73  odom_helper.getOdom(base_odom);
74 
75  //we assume the global goal is the last point in the global plan
76  tf::Stamped<tf::Pose> goal_pose;
77  if ( ! planner_util->getGoal(goal_pose)) {
78  return false;
79  }
80 
81  double goal_x = goal_pose.getOrigin().getX();
82  double goal_y = goal_pose.getOrigin().getY();
83 
85 
86  //check to see if we've reached the goal position
88  base_local_planner::getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) {
89  //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll
90  //just rotate in place
92  ROS_DEBUG("Goal position reached (check), stopping and turning in place");
93  xy_tolerance_latch_ = true;
94  }
95  double goal_th = tf::getYaw(goal_pose.getRotation());
96  double angle = base_local_planner::getGoalOrientationAngleDifference(global_pose, goal_th);
97  //check to see if the goal orientation has been reached
98  if (fabs(angle) <= limits.yaw_goal_tolerance) {
99  //make sure that we're actually stopped before returning success
100  if (base_local_planner::stopped(base_odom, rot_stopped_vel, trans_stopped_vel)) {
101  return true;
102  }
103  }
104  }
105  return false;
106 }
107 
109  const tf::Stamped<tf::Pose>& robot_vel,
110  geometry_msgs::Twist& cmd_vel,
111  Eigen::Vector3f acc_lim,
112  double sim_period,
113  boost::function<bool (Eigen::Vector3f pos,
114  Eigen::Vector3f vel,
115  Eigen::Vector3f vel_samples)> obstacle_check) {
116 
117  //slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible
118  //but we'll use a tenth of a second to be consistent with the implementation of the local planner.
119  double vx = sign(robot_vel.getOrigin().x()) * std::max(0.0, (fabs(robot_vel.getOrigin().x()) - acc_lim[0] * sim_period));
120  double vy = sign(robot_vel.getOrigin().y()) * std::max(0.0, (fabs(robot_vel.getOrigin().y()) - acc_lim[1] * sim_period));
121 
122  double vel_yaw = tf::getYaw(robot_vel.getRotation());
123  double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim[2] * sim_period));
124 
125  //we do want to check whether or not the command is valid
126  double yaw = tf::getYaw(global_pose.getRotation());
127  bool valid_cmd = obstacle_check(Eigen::Vector3f(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw),
128  Eigen::Vector3f(robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw),
129  Eigen::Vector3f(vx, vy, vth));
130 
131  //if we have a valid command, we'll pass it on, otherwise we'll command all zeros
132  if(valid_cmd){
133  ROS_DEBUG_NAMED("latched_stop_rotate", "Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth);
134  cmd_vel.linear.x = vx;
135  cmd_vel.linear.y = vy;
136  cmd_vel.angular.z = vth;
137  return true;
138  }
139  ROS_WARN("Stopping cmd in collision");
140  cmd_vel.linear.x = 0.0;
141  cmd_vel.linear.y = 0.0;
142  cmd_vel.angular.z = 0.0;
143  return false;
144 }
145 
147  const tf::Stamped<tf::Pose>& global_pose,
148  const tf::Stamped<tf::Pose>& robot_vel,
149  double goal_th,
150  geometry_msgs::Twist& cmd_vel,
151  Eigen::Vector3f acc_lim,
152  double sim_period,
154  boost::function<bool (Eigen::Vector3f pos,
155  Eigen::Vector3f vel,
156  Eigen::Vector3f vel_samples)> obstacle_check) {
157  double yaw = tf::getYaw(global_pose.getRotation());
158  double vel_yaw = tf::getYaw(robot_vel.getRotation());
159  cmd_vel.linear.x = 0;
160  cmd_vel.linear.y = 0;
161  double ang_diff = angles::shortest_angular_distance(yaw, goal_th);
162 
163  double v_theta_samp = std::min(limits.max_rot_vel, std::max(limits.min_rot_vel, fabs(ang_diff)));
164 
165  //take the acceleration limits of the robot into account
166  double max_acc_vel = fabs(vel_yaw) + acc_lim[2] * sim_period;
167  double min_acc_vel = fabs(vel_yaw) - acc_lim[2] * sim_period;
168 
169  v_theta_samp = std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel);
170 
171  //we also want to make sure to send a velocity that allows us to stop when we reach the goal given our acceleration limits
172  double max_speed_to_stop = sqrt(2 * acc_lim[2] * fabs(ang_diff));
173  v_theta_samp = std::min(max_speed_to_stop, fabs(v_theta_samp));
174 
175  v_theta_samp = std::min(limits.max_rot_vel, std::max(limits.min_rot_vel, v_theta_samp));
176 
177  if (ang_diff < 0) {
178  v_theta_samp = - v_theta_samp;
179  }
180 
181  //we still want to lay down the footprint of the robot and check if the action is legal
182  bool valid_cmd = obstacle_check(Eigen::Vector3f(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw),
183  Eigen::Vector3f(robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw),
184  Eigen::Vector3f( 0.0, 0.0, v_theta_samp));
185 
186  if (valid_cmd) {
187  ROS_DEBUG_NAMED("dwa_local_planner", "Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd);
188  cmd_vel.angular.z = v_theta_samp;
189  return true;
190  }
191  ROS_WARN("Rotation cmd in collision");
192  cmd_vel.angular.z = 0.0;
193  return false;
194 
195 }
196 
198  Eigen::Vector3f acc_lim,
199  double sim_period,
200  LocalPlannerUtil* planner_util,
201  OdometryHelperRos& odom_helper_,
202  tf::Stamped<tf::Pose> global_pose,
203  boost::function<bool (Eigen::Vector3f pos,
204  Eigen::Vector3f vel,
205  Eigen::Vector3f vel_samples)> obstacle_check) {
206  //we assume the global goal is the last point in the global plan
207  tf::Stamped<tf::Pose> goal_pose;
208  if ( ! planner_util->getGoal(goal_pose)) {
209  ROS_ERROR("Could not get goal pose");
210  return false;
211  }
212 
214 
215  //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll
216  //just rotate in place
218  ROS_INFO("Goal position reached, stopping and turning in place");
219  xy_tolerance_latch_ = true;
220  }
221  //check to see if the goal orientation has been reached
222  double goal_th = tf::getYaw(goal_pose.getRotation());
223  double angle = base_local_planner::getGoalOrientationAngleDifference(global_pose, goal_th);
224  if (fabs(angle) <= limits.yaw_goal_tolerance) {
225  //set the velocity command to zero
226  cmd_vel.linear.x = 0.0;
227  cmd_vel.linear.y = 0.0;
228  cmd_vel.angular.z = 0.0;
229  rotating_to_goal_ = false;
230  } else {
231  ROS_DEBUG("Angle: %f Tolerance: %f", angle, limits.yaw_goal_tolerance);
232  tf::Stamped<tf::Pose> robot_vel;
233  odom_helper_.getRobotVel(robot_vel);
234  nav_msgs::Odometry base_odom;
235  odom_helper_.getOdom(base_odom);
236 
237  //if we're not stopped yet... we want to stop... taking into account the acceleration limits of the robot
238  if ( ! rotating_to_goal_ && !base_local_planner::stopped(base_odom, limits.rot_stopped_vel, limits.trans_stopped_vel)) {
239  if ( ! stopWithAccLimits(
240  global_pose,
241  robot_vel,
242  cmd_vel,
243  acc_lim,
244  sim_period,
245  obstacle_check)) {
246  ROS_INFO("Error when stopping.");
247  return false;
248  }
249  ROS_DEBUG("Stopping...");
250  }
251  //if we're stopped... then we want to rotate to goal
252  else {
253  //set this so that we know its OK to be moving
254  rotating_to_goal_ = true;
255  if ( ! rotateToGoal(
256  global_pose,
257  robot_vel,
258  goal_th,
259  cmd_vel,
260  acc_lim,
261  sim_period,
262  limits,
263  obstacle_check)) {
264  ROS_INFO("Error when rotating.");
265  return false;
266  }
267  ROS_DEBUG("Rotating...");
268  }
269  }
270 
271  return true;
272 
273 }
274 
275 
276 } /* namespace base_local_planner */
bool getGoal(tf::Stamped< tf::Pose > &goal_pose)
void getRobotVel(tf::Stamped< tf::Pose > &robot_vel)
double getGoalPositionDistance(const tf::Stamped< tf::Pose > &global_pose, double goal_x, double goal_y)
return squared distance to check if the goal position has been achieved
static double getYaw(const Quaternion &bt_q)
bool isGoalReached(LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, tf::Stamped< tf::Pose > global_pose)
void getOdom(nav_msgs::Odometry &base_odom)
#define ROS_WARN(...)
bool stopped(const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity)
Check whether the robot is stopped or not.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
#define ROS_DEBUG_NAMED(name,...)
bool computeVelocityCommandsStopRotate(geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, LocalPlannerUtil *planner_util, OdometryHelperRos &odom_helper, tf::Stamped< tf::Pose > global_pose, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check)
#define ROS_INFO(...)
bool stopWithAccLimits(const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &robot_vel, geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check)
Stop the robot taking into account acceleration limits.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool rotateToGoal(const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &robot_vel, double goal_th, geometry_msgs::Twist &cmd_vel, Eigen::Vector3f acc_lim, double sim_period, base_local_planner::LocalPlannerLimits &limits, boost::function< bool(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f vel_samples)> obstacle_check)
Once a goal position is reached... rotate to the goal orientation.
Helper class implementing infrastructure code many local planner implementations may need...
#define ROS_ERROR(...)
def shortest_angular_distance(from_angle, to_angle)
double getGoalOrientationAngleDifference(const tf::Stamped< tf::Pose > &global_pose, double goal_th)
return angle difference to goal to check if the goal orientation has been achieved ...
#define ROS_DEBUG(...)
bool isPositionReached(LocalPlannerUtil *planner_util, tf::Stamped< tf::Pose > global_pose)


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25