35 #ifndef DWB_CRITICS__BASE_OBSTACLE_HPP_
36 #define DWB_CRITICS__BASE_OBSTACLE_HPP_
42 #include "dwb_core/trajectory_critic.hpp"
60 void onInit()
override;
61 double scoreTrajectory(
const dwb_msgs::msg::Trajectory2D & traj)
override;
63 std::vector<std::pair<std::string, std::vector<float>>> & cost_channels)
override;
69 virtual double scorePose(
const geometry_msgs::msg::Pose & pose);
Evaluates a Trajectory2D to produce a score.
Uses costmap 2d to assign negative costs if a circular robot would collide at any point of the trajec...
virtual double scorePose(const geometry_msgs::msg::Pose &pose)
Return the obstacle score for a particular pose.
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.
void addCriticVisualization(std::vector< std::pair< std::string, std::vector< float >>> &cost_channels) override
Add information to the given pointcloud for debugging costmap-grid based scores.
virtual bool isValidCost(const unsigned char cost)
Check to see whether a given cell cost is valid for driving through.
A 2D costmap provides a mapping between points in the world and their associated "costs".