35 #include "dwb_critics/rotate_to_goal.hpp"
38 #include "nav_2d_utils/parameters.hpp"
39 #include "dwb_core/exceptions.hpp"
40 #include "pluginlib/class_list_macros.hpp"
41 #include "dwb_core/trajectory_utils.hpp"
42 #include "angles/angles.h"
49 inline double hypot_sq(
double dx,
double dy)
51 return dx * dx + dy * dy;
54 void RotateToGoalCritic::onInit()
56 auto node = node_.lock();
58 throw std::runtime_error{
"Failed to lock node"};
61 xy_goal_tolerance_ = nav_2d_utils::searchAndGetParam(
63 dwb_plugin_name_ +
".xy_goal_tolerance", 0.25);
64 xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
65 double stopped_xy_velocity = nav_2d_utils::searchAndGetParam(
67 dwb_plugin_name_ +
".trans_stopped_velocity", 0.25);
68 stopped_xy_velocity_sq_ = stopped_xy_velocity * stopped_xy_velocity;
69 slowing_factor_ = nav_2d_utils::searchAndGetParam(
71 dwb_plugin_name_ +
"." + name_ +
".slowing_factor", 5.0);
72 lookahead_time_ = nav_2d_utils::searchAndGetParam(
74 dwb_plugin_name_ +
"." + name_ +
".lookahead_time", -1.0);
85 const geometry_msgs::msg::Pose2D & pose,
const nav_2d_msgs::msg::Twist2D & vel,
86 const geometry_msgs::msg::Pose2D & goal,
87 const nav_2d_msgs::msg::Path2D &)
89 double dxy_sq = hypot_sq(pose.x - goal.x, pose.y - goal.y);
90 in_window_ = in_window_ || dxy_sq <= xy_goal_tolerance_sq_;
91 current_xy_speed_sq_ = hypot_sq(vel.x, vel.y);
92 rotating_ = rotating_ || (in_window_ && current_xy_speed_sq_ <= stopped_xy_velocity_sq_);
93 goal_yaw_ = goal.theta;
102 }
else if (!rotating_) {
103 double speed_sq = hypot_sq(traj.velocity.x, traj.velocity.y);
104 if (speed_sq >= current_xy_speed_sq_) {
111 if (fabs(traj.velocity.x) > 0 || fabs(traj.velocity.y) > 0) {
113 IllegalTrajectoryException(name_,
"Nonrotation command near goal.");
121 if (traj.poses.empty()) {
126 if (lookahead_time_ >= 0.0) {
127 geometry_msgs::msg::Pose2D eval_pose = dwb_core::projectPose(traj, lookahead_time_);
128 end_yaw = eval_pose.theta;
130 end_yaw = traj.poses.back().theta;
132 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.
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.
bool prepare(const geometry_msgs::msg::Pose2D &pose, const nav_2d_msgs::msg::Twist2D &vel, const geometry_msgs::msg::Pose2D &goal, const nav_2d_msgs::msg::Path2D &global_plan) override
Prior to evaluating any trajectories, look at contextual information constant across all trajectories...