15 #include <nav_msgs/Odometry.h> 43 if ( ! planner_util->
getGoal(goal_pose)) {
47 double goal_x = goal_pose.getOrigin().getX();
48 double goal_y = goal_pose.getOrigin().getY();
72 nav_msgs::Odometry base_odom;
77 if ( ! planner_util->
getGoal(goal_pose)) {
81 double goal_x = goal_pose.getOrigin().getX();
82 double goal_y = goal_pose.getOrigin().getY();
92 ROS_DEBUG(
"Goal position reached (check), stopping and turning in place");
95 double goal_th =
tf::getYaw(goal_pose.getRotation());
110 geometry_msgs::Twist& cmd_vel,
111 Eigen::Vector3f acc_lim,
113 boost::function<
bool (Eigen::Vector3f pos,
115 Eigen::Vector3f vel_samples)> obstacle_check) {
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));
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));
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));
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;
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;
150 geometry_msgs::Twist& cmd_vel,
151 Eigen::Vector3f acc_lim,
154 boost::function<
bool (Eigen::Vector3f pos,
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;
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;
169 v_theta_samp = std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel);
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));
178 v_theta_samp = - v_theta_samp;
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));
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;
191 ROS_WARN(
"Rotation cmd in collision");
192 cmd_vel.angular.z = 0.0;
198 Eigen::Vector3f acc_lim,
203 boost::function<
bool (Eigen::Vector3f pos,
205 Eigen::Vector3f vel_samples)> obstacle_check) {
208 if ( ! planner_util->
getGoal(goal_pose)) {
218 ROS_INFO(
"Goal position reached, stopping and turning in place");
222 double goal_th =
tf::getYaw(goal_pose.getRotation());
226 cmd_vel.linear.x = 0.0;
227 cmd_vel.linear.y = 0.0;
228 cmd_vel.angular.z = 0.0;
234 nav_msgs::Odometry base_odom;
235 odom_helper_.
getOdom(base_odom);
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)
LatchedStopRotateController(const std::string &name="")
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)
bool latch_xy_goal_tolerance_
#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)
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 ¶m_name, T ¶m_val, const T &default_val) const
LocalPlannerLimits getCurrentLimits()
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...
virtual ~LatchedStopRotateController()
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 ...
double yaw_goal_tolerance
bool isPositionReached(LocalPlannerUtil *planner_util, tf::Stamped< tf::Pose > global_pose)