Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
navigate_through_poses.hpp
1 // Copyright (c) 2021-2023 Samsung Research
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_BT_NAVIGATOR__NAVIGATORS__NAVIGATE_THROUGH_POSES_HPP_
16 #define NAV2_BT_NAVIGATOR__NAVIGATORS__NAVIGATE_THROUGH_POSES_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include <memory>
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_action/rclcpp_action.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "nav2_core/behavior_tree_navigator.hpp"
25 #include "nav2_msgs/action/navigate_through_poses.hpp"
26 #include "nav2_msgs/msg/waypoint_status.hpp"
27 #include "nav_msgs/msg/path.hpp"
28 #include "nav2_util/robot_utils.hpp"
29 #include "nav2_util/geometry_utils.hpp"
30 #include "nav2_util/odometry_utils.hpp"
31 
32 namespace nav2_bt_navigator
33 {
34 
40  : public nav2_core::BehaviorTreeNavigator<nav2_msgs::action::NavigateThroughPoses>
41 {
42 public:
43  using ActionT = nav2_msgs::action::NavigateThroughPoses;
49 
55  bool configure(
56  rclcpp_lifecycle::LifecycleNode::WeakPtr node,
57  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) override;
58 
63  std::string getName() override {return std::string("navigate_through_poses");}
64 
70  std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) override;
71 
72 protected:
80  bool goalReceived(ActionT::Goal::ConstSharedPtr goal) override;
81 
86  void onLoop() override;
87 
91  void onPreempt(ActionT::Goal::ConstSharedPtr goal) override;
92 
100  void goalCompleted(
101  typename ActionT::Result::SharedPtr result,
102  const nav2_behavior_tree::BtStatus final_bt_status) override;
103 
108  bool initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal);
109 
110  rclcpp::Time start_time_;
111  std::string goals_blackboard_id_;
112  std::string path_blackboard_id_;
113  std::string waypoint_statuses_blackboard_id_;
114 
115  // Odometry smoother object
116  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
117 };
118 
119 } // namespace nav2_bt_navigator
120 
121 #endif // NAV2_BT_NAVIGATOR__NAVIGATORS__NAVIGATE_THROUGH_POSES_HPP_
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.
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.
bool initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal)
Goal pose initialization on the blackboard.
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 All methods...