Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
A navigator for navigating to a a bunch of intermediary poses. More...
#include <nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp>
Public Types | |
using | ActionT = nav2_msgs::action::NavigateThroughPoses |
typedef std::vector< geometry_msgs::msg::PoseStamped > | Goals |
![]() | |
using | Ptr = std::shared_ptr< nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateThroughPoses > > |
Public Member Functions | |
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. More... | |
std::string | getName () override |
Get action name for this navigator. More... | |
std::string | getDefaultBTFilepath (rclcpp_lifecycle::LifecycleNode::WeakPtr node) override |
Get navigator's default BT. More... | |
![]() | |
BehaviorTreeNavigator () | |
A Navigator constructor. | |
virtual | ~BehaviorTreeNavigator ()=default |
Virtual destructor. | |
bool | on_configure (rclcpp_lifecycle::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 | initializeGoalPoses (ActionT::Goal::ConstSharedPtr goal) |
Goal pose initialization on the blackboard. More... | |
![]() | |
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 | cleanup () |
Method to cleanup resources. | |
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_ |
std::string | goals_blackboard_id_ |
std::string | path_blackboard_id_ |
std::shared_ptr< nav2_util::OdomSmoother > | odom_smoother_ |
![]() | |
std::unique_ptr< nav2_behavior_tree::BtActionServer< nav2_msgs::action::NavigateThroughPoses > > | bt_action_server_ |
rclcpp::Logger | logger_ |
rclcpp::Clock::SharedPtr | clock_ |
FeedbackUtils | feedback_utils_ |
NavigatorMuxer * | plugin_muxer_ |
A navigator for navigating to a a bunch of intermediary poses.
Definition at line 38 of file navigate_through_poses.hpp.
|
overridevirtual |
A configure state transition to configure navigator's state.
node | Weakptr to the lifecycle node |
odom_smoother | Object to get current smoothed robot's speed |
Reimplemented from nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateThroughPoses >.
Definition at line 26 of file navigate_through_poses.cpp.
|
overridevirtual |
Get navigator's default BT.
node | WeakPtr to the lifecycle node |
Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateThroughPoses >.
Definition at line 52 of file navigate_through_poses.cpp.
|
inlineoverridevirtual |
Get action name for this navigator.
Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateThroughPoses >.
Definition at line 64 of file navigate_through_poses.hpp.
|
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.
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. |
Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateThroughPoses >.
Definition at line 88 of file navigate_through_poses.cpp.
|
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.
goal | Action template's goal message |
Implements nav2_core::BehaviorTreeNavigator< nav2_msgs::action::NavigateThroughPoses >.
Definition at line 73 of file navigate_through_poses.cpp.
References initializeGoalPoses().
|
protected |
Goal pose initialization on the blackboard.
Definition at line 213 of file navigate_through_poses.cpp.
Referenced by goalReceived(), and onPreempt().