Template Class Navigator
Defined in File navigator.hpp
Class Documentation
-
template<class ActionT>
class Navigator Navigator interface that acts as a base class for all BT-based Navigator action’s plugins.
Public Functions
-
virtual ~Navigator() = default
Virtual destructor.
-
inline bool on_configure(rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, const std::vector<std::string> &plugin_lib_names, const FeedbackUtils &feedback_utils, nav2_bt_navigator::NavigatorMuxer *plugin_muxer, std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
Configuration to setup the navigator’s backend BT and actions.
- Parameters:
parent_node – The ROS parent node to utilize
plugin_lib_names – a vector of plugin shared libraries to load
feedback_utils – Some utilities useful for navigators to have
plugin_muxer – The muxing object to ensure only one navigator can be active at a time
odom_smoother – Object to get current smoothed robot’s speed
- Returns:
bool If successful
-
inline bool on_activate()
Activation of the navigator’s backend BT and actions.
- Returns:
bool If successful
-
inline bool on_deactivate()
Deactivation of the navigator’s backend BT and actions.
- Returns:
bool If successful
-
inline bool on_cleanup()
Cleanup a navigator.
- Returns:
bool If successful
-
virtual std::string getName() = 0
Get the action name of this navigator to expose.
- Returns:
string Name of action to expose
-
virtual std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) = 0
Protected Functions
-
inline bool onGoalReceived(typename ActionT::Goal::ConstSharedPtr goal)
An intermediate goal reception function to mux navigators.
-
inline void onCompletion(typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status)
An intermediate completion function to mux navigators.
-
virtual bool goalReceived(typename ActionT::Goal::ConstSharedPtr goal) = 0
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.
-
virtual void onLoop() = 0
A callback that defines execution that happens on one iteration through the BT Can be used to publish action feedback.
-
virtual void onPreempt(typename ActionT::Goal::ConstSharedPtr goal) = 0
A callback that is called when a preempt is requested.
-
virtual void goalCompleted(typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status) = 0
A callback that is called when a the action is completed; Can fill in action result message or indicate that this action is done.
-
inline virtual bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr, std::shared_ptr<nav2_util::OdomSmoother>)
- Parameters:
Method – to configure resources.
-
inline virtual bool cleanup()
Method to cleanup resources.
-
inline virtual bool activate()
Method to activate any threads involved in execution.
-
inline virtual bool deactivate()
Method to deactivate and any threads involved in execution.
Protected Attributes
-
rclcpp::Logger logger_ = {rclcpp::get_logger("Navigator")}
-
rclcpp::Clock::SharedPtr clock_
-
FeedbackUtils feedback_utils_
-
NavigatorMuxer *plugin_muxer_
-
virtual ~Navigator() = default