35 #ifndef DWB_CORE__TRAJECTORY_CRITIC_HPP_
36 #define DWB_CORE__TRAJECTORY_CRITIC_HPP_
43 #include "rclcpp/rclcpp.hpp"
44 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
45 #include "geometry_msgs/msg/pose2_d.hpp"
46 #include "nav_2d_msgs/msg/twist2_d.hpp"
47 #include "nav_2d_msgs/msg/path2_d.hpp"
48 #include "dwb_msgs/msg/trajectory2_d.hpp"
49 #include "sensor_msgs/msg/point_cloud.hpp"
50 #include "nav2_util/lifecycle_node.hpp"
81 using Ptr = std::shared_ptr<dwb_core::TrajectoryCritic>;
96 const nav2_util::LifecycleNode::SharedPtr & nh,
97 const std::string & name,
98 const std::string & ns,
99 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
103 costmap_ros_ = costmap_ros;
104 dwb_plugin_name_ = ns;
105 if (!nh->has_parameter(dwb_plugin_name_ +
"." + name_ +
".scale")) {
106 nh->declare_parameter(
107 dwb_plugin_name_ +
"." + name_ +
".scale",
108 rclcpp::ParameterValue(1.0));
110 nh->get_parameter(dwb_plugin_name_ +
"." + name_ +
".scale", scale_);
113 virtual void onInit() {}
134 const geometry_msgs::msg::Pose2D &,
const nav_2d_msgs::msg::Twist2D &,
135 const geometry_msgs::msg::Pose2D &,
136 const nav_2d_msgs::msg::Path2D &)
152 virtual void debrief(
const nav_2d_msgs::msg::Twist2D &) {}
172 std::string getName()
177 virtual double getScale()
const {
return scale_;}
178 void setScale(
const double scale) {scale_ = scale;}
182 std::string dwb_plugin_name_;
183 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
185 rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
Evaluates a Trajectory2D to produce a score.
virtual bool prepare(const geometry_msgs::msg::Pose2D &, const nav_2d_msgs::msg::Twist2D &, const geometry_msgs::msg::Pose2D &, const nav_2d_msgs::msg::Path2D &)
Prior to evaluating any trajectories, look at contextual information constant across all trajectories...
virtual double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj)=0
Return a raw score for the given trajectory.
virtual void reset()
Reset the state of the critic.
virtual void debrief(const nav_2d_msgs::msg::Twist2D &)
debrief informs the critic what the chosen cmd_vel was (if it cares)
virtual void addCriticVisualization(std::vector< std::pair< std::string, std::vector< float >>> &)
Add information to the given pointcloud for debugging costmap-grid based scores.
void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &name, const std::string &ns, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Initialize the critic with appropriate pointers and parameters.