Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
breadth-first scoring of all the cells in the costmap More...
#include <nav2_dwb_controller/dwb_critics/include/dwb_critics/map_grid.hpp>
Classes | |
class | MapGridQueue |
Subclass of CostmapQueue that avoids Obstacles and Unknown Values. More... | |
Public Member Functions | |
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::Pose2D &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_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. More... | |
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. 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 Types | |
enum class | ScoreAggregationType { Last , Sum , Product } |
Separate modes for aggregating scores across the multiple poses in a trajectory. More... | |
Protected Member Functions | |
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. | |
Protected Attributes | |
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_ |
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< dwb_core::TrajectoryCritic > |
breadth-first scoring of all the cells in the costmap
This TrajectoryCritic assigns a score to every cell in the costmap based on the distance to the cell from some set of source points. The cells corresponding with the source points are marked with some initial score, and then every other cell is updated with a score based on its relation to the closest source cell, based on a breadth-first exploration of the cells of the costmap.
This approach was chosen for computational efficiency, such that each trajectory need not be compared to the list of source points.
Definition at line 61 of file map_grid.hpp.
|
strongprotected |
Separate modes for aggregating scores across the multiple poses in a trajectory.
Last returns the score associated with the last pose in the trajectory Sum returns the sum of all the scores Product returns the product of all the (non-zero) scores
Definition at line 105 of file map_grid.hpp.
|
overridevirtual |
Add information to the given pointcloud for debugging costmap-grid based scores.
addCriticVisualization is an optional debugging mechanism for providing rich information about the cost for certain trajectories. Some critics will have scoring mechanisms wherein there will be some score for each cell in the costmap. This could be as straightforward as the cost in the costmap, or it could be the number of cells away from the goal pose.
Prior to calling this, dwb_core will load the PointCloud's header and the points in row-major order. The critic may then add a ChannelFloat to the channels member of the PC with the same number of values as the points array. This information may then be converted and published as a PointCloud2.
pc | PointCloud to add channels to |
Reimplemented from dwb_core::TrajectoryCritic.
Definition at line 169 of file map_grid.cpp.
References getScore(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().
|
inline |
Retrieve the score for a particular cell of the costmap.
x | x-coordinate within the costmap |
y | y-coordinate within the costmap |
Definition at line 85 of file map_grid.hpp.
References nav2_costmap_2d::Costmap2D::getIndex().
Referenced by addCriticVisualization(), and scorePose().
|
virtual |
Retrieve the score for a single pose.
pose | The pose to score, assumed to be in the same frame as the costmap |
Reimplemented in dwb_critics::PathAlignCritic, and dwb_critics::GoalAlignCritic.
Definition at line 158 of file map_grid.cpp.
References getScore(), and nav2_costmap_2d::Costmap2D::worldToMap().
Referenced by dwb_critics::GoalAlignCritic::scorePose(), dwb_critics::PathAlignCritic::scorePose(), and scoreTrajectory().
|
overridevirtual |
Return a raw score for the given trajectory.
scores < 0 are considered invalid/errors, such as collisions This is the raw score in that the scale should not be applied to it.
Implements dwb_core::TrajectoryCritic.
Definition at line 117 of file map_grid.cpp.
References scorePose(), and unreachable_score_.
void dwb_critics::MapGridCritic::setAsObstacle | ( | unsigned int | index | ) |
Sets the score of a particular cell to the obstacle cost.
index | Index of the cell to mark |
Definition at line 94 of file map_grid.cpp.