Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
navigate_to_pose.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_TO_POSE_HPP_
16 #define NAV2_BT_NAVIGATOR__NAVIGATORS__NAVIGATE_TO_POSE_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_to_pose.hpp"
26 #include "nav2_util/geometry_utils.hpp"
27 #include "nav2_util/robot_utils.hpp"
28 #include "nav_msgs/msg/path.hpp"
29 #include "nav2_util/odometry_utils.hpp"
30 
31 namespace nav2_bt_navigator
32 {
33 
39  : public nav2_core::BehaviorTreeNavigator<nav2_msgs::action::NavigateToPose>
40 {
41 public:
42  using ActionT = nav2_msgs::action::NavigateToPose;
43 
49 
55  bool configure(
56  rclcpp_lifecycle::LifecycleNode::WeakPtr node,
57  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) override;
58 
62  bool cleanup() override;
63 
69  void onGoalPoseReceived(const geometry_msgs::msg::PoseStamped::SharedPtr pose);
70 
75  std::string getName() override {return std::string("navigate_to_pose");}
76 
82  std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) override;
83 
84 protected:
92  bool goalReceived(ActionT::Goal::ConstSharedPtr goal) override;
93 
98  void onLoop() override;
99 
103  void onPreempt(ActionT::Goal::ConstSharedPtr goal) override;
104 
112  void goalCompleted(
113  typename ActionT::Result::SharedPtr result,
114  const nav2_behavior_tree::BtStatus final_bt_status) override;
115 
121  bool initializeGoalPose(ActionT::Goal::ConstSharedPtr goal);
122 
123  rclcpp::Time start_time_;
124 
125  rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr goal_sub_;
126  rclcpp_action::Client<ActionT>::SharedPtr self_client_;
127 
128  std::string goal_blackboard_id_;
129  std::string path_blackboard_id_;
130 
131  // Odometry smoother object
132  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
133 };
134 
135 } // namespace nav2_bt_navigator
136 
137 #endif // NAV2_BT_NAVIGATOR__NAVIGATORS__NAVIGATE_TO_POSE_HPP_
A navigator for navigating to a specified pose.
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...
void onGoalPoseReceived(const geometry_msgs::msg::PoseStamped::SharedPtr pose)
A subscription and callback to handle the topic-based goal published from rviz.
void onPreempt(ActionT::Goal::ConstSharedPtr goal) override
A callback that is called when a preempt is requested.
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...
bool initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
Goal pose initialization on the blackboard.
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.
NavigateToPoseNavigator()
A constructor for NavigateToPoseNavigator.
std::string getName() override
Get action name for this navigator.
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...
bool cleanup() override
A cleanup state transition to remove memory allocated.
Navigator interface that acts as a base class for all BT-based Navigator action's plugins All methods...