Go to the documentation of this file.
52 return dx * dx + dy * dy;
73 const geometry_msgs::Pose2D& goal,
74 const nav_2d_msgs::Path2D& global_plan)
76 double dxy_sq =
hypot_sq(pose.x - goal.x, pose.y - goal.y);
93 double speed_sq =
hypot_sq(traj.velocity.x, traj.velocity.y);
102 if (fabs(traj.velocity.x) >
EPSILON || fabs(traj.velocity.y) >
EPSILON)
112 if (traj.poses.empty())
121 end_yaw = eval_pose.theta;
125 end_yaw = traj.poses.back().theta;
param_t searchAndGetParam(const ros::NodeHandle &nh, const std::string ¶m_name, const param_t &default_value)
static double shortest_angular_distance(double from, double to)
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
virtual double scoreRotation(const dwb_msgs::Trajectory2D &traj)
Assuming that this is an actual rotation when near the goal, score the trajectory.
geometry_msgs::Pose2D projectPose(const dwb_msgs::Trajectory2D &trajectory, const double time_offset)
double xy_goal_tolerance_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
double current_xy_speed_sq_
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
ros::NodeHandle critic_nh_
T param(const std::string ¶m_name, const T &default_val) const
double hypot_sq(double dx, double dy)
Forces the commanded trajectories to only be rotations if within a certain distance window.
dwb_critics
Author(s): David V. Lu!!
autogenerated on Sun May 18 2025 02:47:34