35 #ifndef DWB_CRITICS__PREFER_FORWARD_HPP_
36 #define DWB_CRITICS__PREFER_FORWARD_HPP_
39 #include "dwb_core/trajectory_critic.hpp"
57 : penalty_(1.0), strafe_x_(0.1), strafe_theta_(0.2), theta_scale_(10.0) {}
58 void onInit()
override;
59 double scoreTrajectory(
const dwb_msgs::msg::Trajectory2D & traj)
override;
62 double penalty_, strafe_x_, strafe_theta_, theta_scale_;
Evaluates a Trajectory2D to produce a score.
Penalize trajectories with move backwards and/or turn too much.
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.