Class NavigateThroughPosesNavigator

Inheritance Relationships

Base Type

  • public nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateThroughPoses >

Class Documentation

class NavigateThroughPosesNavigator : public nav2_core::BehaviorTreeNavigator<nav2_msgs::action::NavigateThroughPoses>

A navigator for navigating to a a bunch of intermediary poses.

Public Types

using ActionT = nav2_msgs::action::NavigateThroughPoses
typedef std::vector<geometry_msgs::msg::PoseStamped> Goals

Public Functions

inline NavigateThroughPosesNavigator()

A constructor for NavigateThroughPosesNavigator.

bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr node, std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) override

A configure state transition to configure navigator’s state.

Parameters:
  • node – Weakptr to the lifecycle node

  • odom_smoother – Object to get current smoothed robot’s speed

inline std::string getName() override

Get action name for this navigator.

Returns:

string Name of action server

std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) override

Get navigator’s default BT.

Parameters:

node – WeakPtr to the lifecycle node

Returns:

string Filepath to default XML

Protected Functions

bool goalReceived(ActionT::Goal::ConstSharedPtr goal) override

A callback to be called when a new goal is received by the BT action server Can be used to check if goal is valid and put values on the blackboard which depend on the received goal.

Parameters:

goal – Action template’s goal message

Returns:

bool if goal was received successfully to be processed

void onLoop() override

A callback that defines execution that happens on one iteration through the BT Can be used to publish action feedback.

void onPreempt(ActionT::Goal::ConstSharedPtr goal) override

A callback that is called when a preempt is requested.

void goalCompleted(typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status) override

A callback that is called when a the action is completed, can fill in action result message or indicate that this action is done.

Parameters:
  • result – Action template result message to populate

  • final_bt_status – Resulting status of the behavior tree execution that may be referenced while populating the result.

bool initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal)

Goal pose initialization on the blackboard.

Returns:

bool if goal was initialized successfully to be processed

Protected Attributes

rclcpp::Time start_time_
std::string goals_blackboard_id_
std::string path_blackboard_id_
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_