44 const geometry_msgs::Pose2D &goal,
const nav_2d_msgs::Path2D &global_plan) {
49 if (global_plan.poses.empty()) {
55 double distance_min = std::numeric_limits<double>::infinity();
56 bool started_path =
false;
57 for (
unsigned int i = 0; i < adjusted_global_plan.poses.size(); i++) {
58 double g_x = adjusted_global_plan.poses[i].x;
59 double g_y = adjusted_global_plan.poses[i].y;
60 unsigned int map_x, map_y;
63 if (distance_min > distance) {
66 distance_min = distance;
72 }
else if (started_path) {
80 ROS_ERROR_NAMED(
"PathAngleCritic",
"None of the points of the global plan were in the local costmap.");
87 double diff = fabs(remainder(traj.poses.back().theta -
desired_angle_, 2 * M_PI));
Scores trajectories based on the difference between the path's current angle and the trajectory's ang...
nav_core2::BasicCostmap costmap
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
static const unsigned char NO_INFORMATION
double poseDistance(const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
nav_core2::Costmap::Ptr costmap_
nav_2d_msgs::Path2D adjustPlanResolution(const nav_2d_msgs::Path2D &global_plan_in, double resolution)
virtual double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
#define ROS_ERROR_NAMED(name,...)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual 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
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)