35 #include "dwb_critics/rotate_to_goal.hpp"
38 #include "dwb_core/exceptions.hpp"
39 #include "pluginlib/class_list_macros.hpp"
40 #include "dwb_core/trajectory_utils.hpp"
41 #include "angles/angles.h"
48 inline double hypot_sq(
double dx,
double dy)
50 return dx * dx + dy * dy;
53 void RotateToGoalCritic::onInit()
55 auto node = node_.lock();
57 throw std::runtime_error{
"Failed to lock node"};
60 xy_goal_tolerance_ = node->declare_or_get_parameter(
61 dwb_plugin_name_ +
".xy_goal_tolerance", 0.25);
62 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
63 double stopped_xy_velocity = node->declare_or_get_parameter(
64 dwb_plugin_name_ +
".trans_stopped_velocity", 0.25);
65 stopped_xy_velocity_sq_ = stopped_xy_velocity * stopped_xy_velocity;
66 slowing_factor_ = node->declare_or_get_parameter(
67 dwb_plugin_name_ +
"." + name_ +
".slowing_factor", 5.0);
68 lookahead_time_ = node->declare_or_get_parameter(
69 dwb_plugin_name_ +
"." + name_ +
".lookahead_time", -1.0);
80 const geometry_msgs::msg::Pose & pose,
const nav_2d_msgs::msg::Twist2D & vel,
81 const geometry_msgs::msg::Pose & goal,
82 const nav_msgs::msg::Path &)
84 double dxy_sq = hypot_sq(pose.position.x - goal.position.x, pose.position.y - goal.position.y);
85 in_window_ = in_window_ || dxy_sq <= xy_goal_tolerance_sq_;
86 current_xy_speed_sq_ = hypot_sq(vel.x, vel.y);
87 rotating_ = rotating_ || (in_window_ && current_xy_speed_sq_ <= stopped_xy_velocity_sq_);
88 goal_yaw_ = tf2::getYaw(goal.orientation);
97 }
else if (!rotating_) {
98 double speed_sq = hypot_sq(traj.velocity.x, traj.velocity.y);
99 if (speed_sq >= current_xy_speed_sq_) {
106 if (fabs(traj.velocity.x) > 0 || fabs(traj.velocity.y) > 0) {
108 IllegalTrajectoryException(name_,
"Nonrotation command near goal.");
116 if (traj.poses.empty()) {
121 if (lookahead_time_ >= 0.0) {
122 geometry_msgs::msg::Pose eval_pose = dwb_core::projectPose(traj, lookahead_time_);
123 end_yaw = tf2::getYaw(eval_pose.orientation);
125 end_yaw = tf2::getYaw(traj.poses.back().orientation);
127 return fabs(angles::shortest_angular_distance(end_yaw, goal_yaw_));
Thrown when one of the critics encountered a fatal error.
Evaluates a Trajectory2D to produce a score.
Forces the commanded trajectories to only be rotations if within a certain distance window.
bool prepare(const geometry_msgs::msg::Pose &pose, const nav_2d_msgs::msg::Twist2D &vel, const geometry_msgs::msg::Pose &goal, const nav_msgs::msg::Path &global_plan) override
Prior to evaluating any trajectories, look at contextual information constant across all trajectories...
void reset() override
Reset the state of the critic.
virtual double scoreRotation(const dwb_msgs::msg::Trajectory2D &traj)
Assuming that this is an actual rotation when near the goal, score the trajectory.
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.