35 #include "dwb_critics/prefer_forward.hpp"
37 #include "pluginlib/class_list_macros.hpp"
38 #include "nav2_util/node_utils.hpp"
42 using nav2_util::declare_parameter_if_not_declared;
47 void PreferForwardCritic::onInit()
49 auto node = node_.lock();
51 throw std::runtime_error{
"Failed to lock node"};
54 declare_parameter_if_not_declared(
56 dwb_plugin_name_ +
"." + name_ +
".penalty", rclcpp::ParameterValue(1.0));
57 declare_parameter_if_not_declared(
59 dwb_plugin_name_ +
"." + name_ +
".strafe_x", rclcpp::ParameterValue(0.1));
60 declare_parameter_if_not_declared(
61 node, dwb_plugin_name_ +
"." + name_ +
".strafe_theta",
62 rclcpp::ParameterValue(0.2));
63 declare_parameter_if_not_declared(
64 node, dwb_plugin_name_ +
"." + name_ +
".theta_scale",
65 rclcpp::ParameterValue(10.0));
67 node->get_parameter(dwb_plugin_name_ +
"." + name_ +
".penalty", penalty_);
68 node->get_parameter(dwb_plugin_name_ +
"." + name_ +
".strafe_x", strafe_x_);
69 node->get_parameter(dwb_plugin_name_ +
"." + name_ +
".strafe_theta", strafe_theta_);
70 node->get_parameter(dwb_plugin_name_ +
"." + name_ +
".theta_scale", theta_scale_);
76 if (traj.velocity.x < 0.0) {
80 if (traj.velocity.x < strafe_x_ && fabs(traj.velocity.theta) < strafe_theta_) {
85 return fabs(traj.velocity.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.