Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_route::TimeMarker Class Reference

A route operation to add accurate times to the graph's edges after navigation to use in later iterations for a more refined estimate of actual travel time. More...

#include <nav2_route/include/nav2_route/plugins/route_operations/time_marker.hpp>

Inheritance diagram for nav2_route::TimeMarker:
Inheritance graph
[legend]
Collaboration diagram for nav2_route::TimeMarker:
Collaboration graph
[legend]

Public Member Functions

 TimeMarker ()=default
 Constructor.
 
virtual ~TimeMarker ()=default
 destructor
 
void configure (const nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override
 Configure.
 
std::string getName () override
 Get name of the plugin for parameter scope mapping. More...
 
RouteOperationType processType () override
 Indication that the adjust speed limit route operation is performed on all state changes. More...
 
OperationResult perform (NodePtr node_achieved, EdgePtr edge_entered, EdgePtr edge_exited, const Route &route, const geometry_msgs::msg::PoseStamped &curr_pose, const Metadata *mdata=nullptr) override
 The main speed limit operation to adjust the maximum speed of the vehicle. More...
 
- Public Member Functions inherited from nav2_route::RouteOperation
 RouteOperation ()=default
 Constructor.
 
virtual ~RouteOperation ()=default
 Destructor.
 

Protected Attributes

std::string name_
 
std::string time_tag_
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Time edge_start_time_
 
unsigned int curr_edge_
 

Additional Inherited Members

- Public Types inherited from nav2_route::RouteOperation
using Ptr = std::shared_ptr< nav2_route::RouteOperation >
 

Detailed Description

A route operation to add accurate times to the graph's edges after navigation to use in later iterations for a more refined estimate of actual travel time.

Definition at line 35 of file time_marker.hpp.

Member Function Documentation

◆ getName()

std::string nav2_route::TimeMarker::getName ( )
inlineoverridevirtual

Get name of the plugin for parameter scope mapping.

Returns
Name

Implements nav2_route::RouteOperation.

Definition at line 60 of file time_marker.hpp.

Referenced by configure().

Here is the caller graph for this function:

◆ perform()

OperationResult nav2_route::TimeMarker::perform ( NodePtr  node_achieved,
EdgePtr  edge_entered,
EdgePtr  edge_exited,
const Route route,
const geometry_msgs::msg::PoseStamped &  curr_pose,
const Metadata mdata = nullptr 
)
overridevirtual

The main speed limit operation to adjust the maximum speed of the vehicle.

Parameters
mdataMetadata corresponding to the operation in the navigation graph. If metadata is invalid or irrelevant, a nullptr is given
node_achievedNode achieved, for additional context
edge_enteredEdge entered by node achievement, for additional context
edge_exitedEdge exited by node achievement, for additional context
routeCurrent route being tracked in full, for additional context
curr_poseCurrent robot pose in the route frame, for additional context
Returns
Whether to perform rerouting and report blocked edges in that case

Implements nav2_route::RouteOperation.

Definition at line 38 of file time_marker.cpp.

◆ processType()

RouteOperationType nav2_route::TimeMarker::processType ( )
inlineoverridevirtual

Indication that the adjust speed limit route operation is performed on all state changes.

Returns
The type of operation (on graph call, on status changes, or constantly)

Reimplemented from nav2_route::RouteOperation.

Definition at line 67 of file time_marker.hpp.


The documentation for this class was generated from the following files: