Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Scores edges by the time to traverse an edge. It uses previous times to navigate the edge primarily, then secondarily uses maximum speed and absolute speed limits to estimate with edge length. More...
#include <nav2_route/include/nav2_route/plugins/edge_cost_functions/time_scorer.hpp>
Public Member Functions | |
TimeScorer ()=default | |
Constructor. | |
virtual | ~TimeScorer ()=default |
destructor | |
void | configure (const rclcpp_lifecycle::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override |
Configure. | |
bool | score (const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override |
Main scoring plugin API. More... | |
std::string | getName () override |
Get name of the plugin for parameter scope mapping. More... | |
![]() | |
EdgeCostFunction ()=default | |
Constructor. | |
virtual | ~EdgeCostFunction ()=default |
Virtual destructor. | |
virtual void | prepare () |
Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests, or otherwise prepare for scoring. | |
Protected Attributes | |
std::string | name_ |
std::string | speed_tag_ |
std::string | prev_time_tag_ |
float | weight_ |
float | max_vel_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< nav2_route::EdgeCostFunction > |
Scores edges by the time to traverse an edge. It uses previous times to navigate the edge primarily, then secondarily uses maximum speed and absolute speed limits to estimate with edge length.
Definition at line 34 of file time_scorer.hpp.
|
overridevirtual |
Get name of the plugin for parameter scope mapping.
Implements nav2_route::EdgeCostFunction.
Definition at line 77 of file time_scorer.cpp.
Referenced by configure().
|
overridevirtual |
Main scoring plugin API.
edge | The edge pointer to score, which has access to the start/end nodes and their associated metadata and actions |
cost | of the edge scored |
Implements nav2_route::EdgeCostFunction.
Definition at line 51 of file time_scorer.cpp.