15 #ifndef NAV2_BT_NAVIGATOR__NAVIGATORS__NAVIGATE_THROUGH_POSES_HPP_
16 #define NAV2_BT_NAVIGATOR__NAVIGATORS__NAVIGATE_THROUGH_POSES_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_action/rclcpp_action.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "nav2_bt_navigator/navigator.hpp"
25 #include "nav2_msgs/action/navigate_through_poses.hpp"
26 #include "nav_msgs/msg/path.hpp"
27 #include "nav2_util/robot_utils.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav2_util/odometry_utils.hpp"
31 namespace nav2_bt_navigator
42 using ActionT = nav2_msgs::action::NavigateThroughPoses;
43 typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;
57 rclcpp_lifecycle::LifecycleNode::WeakPtr node,
58 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
override;
64 std::string
getName()
override {
return std::string(
"navigate_through_poses");}
81 bool goalReceived(ActionT::Goal::ConstSharedPtr goal)
override;
92 void onPreempt(ActionT::Goal::ConstSharedPtr goal)
override;
102 typename ActionT::Result::SharedPtr result,
103 const nav2_behavior_tree::BtStatus final_bt_status)
override;
110 rclcpp::Time start_time_;
111 std::string goals_blackboard_id_;
112 std::string path_blackboard_id_;
115 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
A navigator for navigating to a a bunch of intermediary poses.
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.
void onPreempt(ActionT::Goal::ConstSharedPtr goal) override
A callback that is called when a preempt is requested.
std::string getName() override
Get action name for this navigator.
void initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal)
Goal pose initialization on the blackboard.
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 g...
NavigateThroughPosesNavigator()
A constructor for NavigateThroughPosesNavigator.
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 indica...
std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) override
Get navigator's default BT.
void onLoop() override
A callback that defines execution that happens on one iteration through the BT Can be used to publish...
Navigator interface that acts as a base class for all BT-based Navigator action's plugins.