Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Scores trajectories based on how far along the global path they end up. More...
#include <nav2_dwb_controller/dwb_critics/include/dwb_critics/goal_dist.hpp>
Public Member Functions | |
bool | prepare (const geometry_msgs::msg::Pose &pose, const nav_2d_msgs::msg::Twist2D &vel, const geometry_msgs::msg::Pose &goal, const nav_msgs::msg::Path &global_plan) override |
Prior to evaluating any trajectories, look at contextual information constant across all trajectories. More... | |
![]() | |
void | onInit () override |
double | scoreTrajectory (const dwb_msgs::msg::Trajectory2D &traj) override |
Return a raw score for the given trajectory. More... | |
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. More... | |
double | getScale () const override |
virtual double | scorePose (const geometry_msgs::msg::Pose &pose) |
Retrieve the score for a single pose. More... | |
double | getScore (unsigned int x, unsigned int y) |
Retrieve the score for a particular cell of the costmap. More... | |
void | setAsObstacle (unsigned int index) |
Sets the score of a particular cell to the obstacle cost. More... | |
![]() | |
void | initialize (const nav2::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. More... | |
virtual void | debrief (const nav_2d_msgs::msg::Twist2D &) |
debrief informs the critic what the chosen cmd_vel was (if it cares) | |
std::string | getName () |
void | setScale (const double scale) |
Protected Member Functions | |
bool | getLastPoseOnCostmap (const nav_msgs::msg::Path &global_plan, unsigned int &x, unsigned int &y) |
![]() | |
void | reset () override |
Clear the queueDWB_CRITICS_MAP_GRID_He and set cell_values_ to the appropriate number of unreachableCellScore. | |
void | propagateManhattanDistances () |
Go through the queue and set the cells to the Manhattan distance from their parents. | |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< dwb_core::TrajectoryCritic > |
![]() | |
enum class | ScoreAggregationType { Last , Sum , Product } |
Separate modes for aggregating scores across the multiple poses in a trajectory. More... | |
![]() | |
std::shared_ptr< MapGridQueue > | queue_ |
nav2_costmap_2d::Costmap2D * | costmap_ |
std::vector< double > | cell_values_ |
double | obstacle_score_ |
double | unreachable_score_ |
Special cell_values. | |
bool | stop_on_failure_ |
ScoreAggregationType | aggregationType_ |
![]() | |
std::string | name_ |
std::string | dwb_plugin_name_ |
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ |
double | scale_ |
nav2::LifecycleNode::WeakPtr | node_ |
Scores trajectories based on how far along the global path they end up.
This trajectory critic helps ensure progress along the global path. It finds the pose from the global path farthest from the robot that is still on the costmap, and aims for that point by assigning the lowest cost to the cell corresponding with that farthest pose.
Definition at line 50 of file goal_dist.hpp.
|
overridevirtual |
Prior to evaluating any trajectories, look at contextual information constant across all trajectories.
Subclasses may overwrite. Return false in case there is any error.
pose | Current pose (costmap frame) |
vel | Current velocity |
goal | The final goal (costmap frame) |
global_plan | Transformed global plan in costmap frame, possibly cropped to nearby points |
Reimplemented from dwb_core::TrajectoryCritic.
Definition at line 43 of file goal_dist.cpp.
References nav2_costmap_2d::Costmap2D::getIndex(), dwb_critics::MapGridCritic::propagateManhattanDistances(), and dwb_critics::MapGridCritic::reset().
Referenced by dwb_critics::GoalAlignCritic::prepare().