34 #ifndef DWB_CRITICS__ROTATE_TO_GOAL_HPP_
35 #define DWB_CRITICS__ROTATE_TO_GOAL_HPP_
39 #include "dwb_core/trajectory_critic.hpp"
73 void onInit()
override;
74 void reset()
override;
76 const geometry_msgs::msg::Pose & pose,
const nav_2d_msgs::msg::Twist2D & vel,
77 const geometry_msgs::msg::Pose & goal,
const nav_msgs::msg::Path & global_plan)
override;
78 double scoreTrajectory(
const dwb_msgs::msg::Trajectory2D & traj)
override;
87 virtual double scoreRotation(
const dwb_msgs::msg::Trajectory2D & traj);
93 double xy_goal_tolerance_;
94 double xy_goal_tolerance_sq_;
95 double current_xy_speed_sq_, stopped_xy_velocity_sq_;
96 double slowing_factor_;
97 double lookahead_time_;
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.