34 #ifndef MIR_DWB_CRITICS_PATH_PROGRESS_H_ 35 #define MIR_DWB_CRITICS_PATH_PROGRESS_H_ 52 bool prepare(
const geometry_msgs::Pose2D &pose,
53 const nav_2d_msgs::Twist2D &vel,
54 const geometry_msgs::Pose2D &goal,
55 const nav_2d_msgs::Path2D &global_plan)
override;
58 void reset()
override;
62 bool getGoalPose(
const geometry_msgs::Pose2D &robot_pose,
63 const nav_2d_msgs::Path2D &global_plan,
66 double &desired_angle);
68 unsigned int getGoalIndex(
const std::vector<geometry_msgs::Pose2D> &plan,
69 unsigned int start_index,
70 unsigned int last_valid_index)
const;
81 #endif // MIR_DWB_CRITICS_PATH_PROGRESS_H_
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
unsigned int getGoalIndex(const std::vector< geometry_msgs::Pose2D > &plan, unsigned int start_index, unsigned int last_valid_index) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
double xy_local_goal_tolerance_
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool getGoalPose(const geometry_msgs::Pose2D &robot_pose, const nav_2d_msgs::Path2D &global_plan, unsigned int &x, unsigned int &y, double &desired_angle)
Calculates an intermediate goal along the global path and scores trajectories on the distance to that...
std::vector< geometry_msgs::Pose2D > reached_intermediate_goals_