34 #ifndef DWB_CRITICS_ROTATE_TO_GOAL_H_ 35 #define DWB_CRITICS_ROTATE_TO_GOAL_H_ 74 void reset()
override;
75 bool prepare(
const geometry_msgs::Pose2D& pose,
const nav_2d_msgs::Twist2D& vel,
76 const geometry_msgs::Pose2D& goal,
const nav_2d_msgs::Path2D& global_plan)
override;
87 virtual double scoreRotation(
const dwb_msgs::Trajectory2D& traj);
100 #endif // DWB_CRITICS_ROTATE_TO_GOAL_H_
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
double xy_goal_tolerance_sq_
Cached squared tolerance.
double stopped_xy_velocity_sq_
bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override
Forces the commanded trajectories to only be rotations if within a certain distance window...
double xy_goal_tolerance_
virtual double scoreRotation(const dwb_msgs::Trajectory2D &traj)
Assuming that this is an actual rotation when near the goal, score the trajectory.
double current_xy_speed_sq_