Class AdjustSpeedLimit

Inheritance Relationships

Base Type

Class Documentation

class AdjustSpeedLimit : public nav2_route::RouteOperation

A route operation to process on state changes to evaluate if speed limits should be adjusted based on graph edge metadata.

Public Functions

AdjustSpeedLimit() = default

Constructor.

virtual ~AdjustSpeedLimit() = default

destructor

virtual void configure(const rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber, const std::string &name) override

Configure.

inline virtual std::string getName() override

Get name of the plugin for parameter scope mapping.

Returns:

Name

inline virtual RouteOperationType processType() override

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)

virtual 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.

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_entered – Edge entered by node achievement, for additional context

  • edge_exited – Edge exited by node achievement, for additional context

  • route – Current route being tracked in full, for additional context

  • curr_pose – Current robot pose in the route frame, for additional context

Returns:

Whether to perform rerouting and report blocked edges in that case

Protected Attributes

std::string name_
std::string speed_tag_
rclcpp::Logger logger_ = {rclcpp::get_logger("AdjustSpeedLimit")}
rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_pub_