Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Uses costmap 2d to assign negative costs if a circular robot would collide at any point of the trajectory. More...
#include <nav2_dwb_controller/dwb_critics/include/dwb_critics/base_obstacle.hpp>
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... | |
virtual double | scorePose (const geometry_msgs::msg::Pose2D &pose) |
Return the obstacle score for a particular pose. More... | |
virtual bool | isValidCost (const unsigned char cost) |
Check to see whether a given cell cost is valid for driving through. 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 void | reset () |
Reset the state of the critic. 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 () |
virtual double | getScale () const |
void | setScale (const double scale) |
Protected Attributes | |
nav2_costmap_2d::Costmap2D * | costmap_ |
bool | sum_scores_ |
![]() | |
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 > |
Uses costmap 2d to assign negative costs if a circular robot would collide at any point of the trajectory.
This class can only be used to figure out if a circular robot is in collision. If the cell corresponding with any of the poses in the Trajectory is an obstacle, inscribed obstacle or unknown, it will return a negative cost. Otherwise it will return either the final pose's cost, or the sum of all poses, depending on the sum_scores parameter.
Other classes (like ObstacleFootprintCritic) can do more advanced checking for collisions.
Definition at line 57 of file base_obstacle.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 98 of file base_obstacle.cpp.
References nav2_costmap_2d::Costmap2D::getCost(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().
|
virtual |
Check to see whether a given cell cost is valid for driving through.
cost | Cost of the cell |
Definition at line 91 of file base_obstacle.cpp.
Referenced by scorePose().
|
virtual |
Return the obstacle score for a particular pose.
pose | Pose to check |
Reimplemented in dwb_critics::ObstacleFootprintCritic.
Definition at line 76 of file base_obstacle.cpp.
References nav2_costmap_2d::Costmap2D::getCost(), isValidCost(), and nav2_costmap_2d::Costmap2D::worldToMap().
Referenced by 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 64 of file base_obstacle.cpp.
References scorePose().