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

A navigator for navigating to a specified pose. More...

#include <nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp>

Inheritance diagram for nav2_bt_navigator::NavigateToPoseNavigator:
Inheritance graph
[legend]
Collaboration diagram for nav2_bt_navigator::NavigateToPoseNavigator:
Collaboration graph
[legend]

Public Types

using ActionT = nav2_msgs::action::NavigateToPose
 
- Public Types inherited from nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >
using Ptr = std::shared_ptr< nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose > >
 

Public Member Functions

 NavigateToPoseNavigator ()
 A constructor for NavigateToPoseNavigator.
 
bool configure (nav2::LifecycleNode::WeakPtr node, std::shared_ptr< nav2_util::OdomSmoother > odom_smoother) override
 A configure state transition to configure navigator's state. More...
 
bool cleanup () override
 A cleanup state transition to remove memory allocated.
 
void onGoalPoseReceived (const geometry_msgs::msg::PoseStamped::SharedPtr pose)
 A subscription and callback to handle the topic-based goal published from rviz. More...
 
std::string getName () override
 Get action name for this navigator. More...
 
std::string getDefaultBTFilepath (nav2::LifecycleNode::WeakPtr node) override
 Get navigator's default BT. More...
 
- Public Member Functions inherited from nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >
 BehaviorTreeNavigator ()
 A Navigator constructor.
 
virtual ~BehaviorTreeNavigator ()=default
 Virtual destructor.
 
bool on_configure (nav2::LifecycleNode::WeakPtr parent_node, const std::vector< std::string > &plugin_lib_names, const FeedbackUtils &feedback_utils, nav2_core::NavigatorMuxer *plugin_muxer, std::shared_ptr< nav2_util::OdomSmoother > odom_smoother) final
 Configuration to setup the navigator's backend BT and actions. More...
 
bool on_activate () final
 Activation of the navigator's backend BT and actions. More...
 
bool on_deactivate () final
 Deactivation of the navigator's backend BT and actions. More...
 
bool on_cleanup () final
 Cleanup a navigator. More...
 

Protected Member 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. More...
 
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. More...
 
bool initializeGoalPose (ActionT::Goal::ConstSharedPtr goal)
 Goal pose initialization on the blackboard. More...
 
- Protected Member Functions inherited from nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >
bool onGoalReceived (typename ActionT::Goal::ConstSharedPtr goal)
 An intermediate goal reception function to mux navigators.
 
void onCompletion (typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status)
 An intermediate completion function to mux navigators.
 
virtual bool activate ()
 Method to activate any threads involved in execution.
 
virtual bool deactivate ()
 Method to deactivate and any threads involved in execution.
 

Protected Attributes

rclcpp::Time start_time_
 
nav2::Subscription< geometry_msgs::msg::PoseStamped >::SharedPtr goal_sub_
 
nav2::ActionClient< ActionT >::SharedPtr self_client_
 
std::string goal_blackboard_id_
 
std::string path_blackboard_id_
 
std::shared_ptr< nav2_util::OdomSmootherodom_smoother_
 
- Protected Attributes inherited from nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >
std::unique_ptr< nav2_behavior_tree::BtActionServer< nav2_msgs::action::NavigateToPose, nav2::LifecycleNode > > bt_action_server_
 
rclcpp::Logger logger_
 
rclcpp::Clock::SharedPtr clock_
 
FeedbackUtils feedback_utils_
 
NavigatorMuxerplugin_muxer_
 

Detailed Description

A navigator for navigating to a specified pose.

Definition at line 38 of file navigate_to_pose.hpp.

Member Function Documentation

◆ configure()

bool nav2_bt_navigator::NavigateToPoseNavigator::configure ( nav2::LifecycleNode::WeakPtr  node,
std::shared_ptr< nav2_util::OdomSmoother odom_smoother 
)
overridevirtual

A configure state transition to configure navigator's state.

Parameters
nodeWeakptr to the lifecycle node
odom_smootherObject to get current smoothed robot's speed

Reimplemented from nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >.

Definition at line 25 of file navigate_to_pose.cpp.

References getName(), and onGoalPoseReceived().

Here is the call graph for this function:

◆ getDefaultBTFilepath()

std::string nav2_bt_navigator::NavigateToPoseNavigator::getDefaultBTFilepath ( nav2::LifecycleNode::WeakPtr  node)
overridevirtual

Get navigator's default BT.

Parameters
nodeWeakPtr to the lifecycle node
Returns
string Filepath to default XML

Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >.

Definition at line 59 of file navigate_to_pose.cpp.

◆ getName()

std::string nav2_bt_navigator::NavigateToPoseNavigator::getName ( )
inlineoverridevirtual

Get action name for this navigator.

Returns
string Name of action server

Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >.

Definition at line 75 of file navigate_to_pose.hpp.

Referenced by configure().

Here is the caller graph for this function:

◆ goalCompleted()

void nav2_bt_navigator::NavigateToPoseNavigator::goalCompleted ( typename ActionT::Result::SharedPtr  result,
const nav2_behavior_tree::BtStatus  final_bt_status 
)
overrideprotectedvirtual

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
resultAction template result message to populate
final_bt_statusResulting status of the behavior tree execution that may be referenced while populating the result.

Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >.

Definition at line 97 of file navigate_to_pose.cpp.

◆ goalReceived()

bool nav2_bt_navigator::NavigateToPoseNavigator::goalReceived ( ActionT::Goal::ConstSharedPtr  goal)
overrideprotectedvirtual

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
goalAction template's goal message
Returns
bool if goal was received successfully to be processed

Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateToPose >.

Definition at line 83 of file navigate_to_pose.cpp.

References initializeGoalPose().

Here is the call graph for this function:

◆ initializeGoalPose()

bool nav2_bt_navigator::NavigateToPoseNavigator::initializeGoalPose ( ActionT::Goal::ConstSharedPtr  goal)
protected

Goal pose initialization on the blackboard.

Parameters
goalAction template's goal message to process
Returns
bool if goal was initialized successfully to be processed

Definition at line 217 of file navigate_to_pose.cpp.

Referenced by goalReceived(), and onPreempt().

Here is the caller graph for this function:

◆ onGoalPoseReceived()

void nav2_bt_navigator::NavigateToPoseNavigator::onGoalPoseReceived ( const geometry_msgs::msg::PoseStamped::SharedPtr  pose)

A subscription and callback to handle the topic-based goal published from rviz.

Parameters
posePose received via atopic

Definition at line 261 of file navigate_to_pose.cpp.

Referenced by configure().

Here is the caller graph for this function:

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