Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
navigator.hpp
1 // Copyright (c) 2024 Open Navigation LLC
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 OPENNAV_DOCKING__NAVIGATOR_HPP_
16 #define OPENNAV_DOCKING__NAVIGATOR_HPP_
17 
18 #include <vector>
19 #include <memory>
20 #include <string>
21 #include <functional>
22 
23 #include "rclcpp/rclcpp.hpp"
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "pluginlib/class_loader.hpp"
26 #include "pluginlib/class_list_macros.hpp"
27 
28 #include "nav2_msgs/action/navigate_to_pose.hpp"
29 #include "nav2_util/node_utils.hpp"
30 #include "opennav_docking/utils.hpp"
31 #include "opennav_docking/types.hpp"
32 
33 namespace opennav_docking
34 {
39 class Navigator
40 {
41 public:
42  using Nav2Pose = nav2_msgs::action::NavigateToPose;
43  using ActionClient = rclcpp_action::Client<Nav2Pose>;
44 
49  explicit Navigator(const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent);
50 
54  ~Navigator() = default;
55 
59  void activate();
60 
64  void deactivate();
65 
75  void goToPose(
76  const geometry_msgs::msg::PoseStamped & pose,
77  rclcpp::Duration remaining_staging_duration,
78  std::function<bool()> isPreempted,
79  bool recursed = false);
80 
81 protected:
82  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
83  rclcpp::CallbackGroup::SharedPtr callback_group_;
84  rclcpp::executors::SingleThreadedExecutor executor_;
85  ActionClient::SharedPtr nav_to_pose_client_;
86  std::string navigator_bt_xml_;
87 };
88 
89 } // namespace opennav_docking
90 
91 #endif // OPENNAV_DOCKING__NAVIGATOR_HPP_
An object the call navigation to obtain initial staging pose.
Definition: navigator.hpp:40
Navigator(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent)
A constructor for opennav_docking::Navigator.
Definition: navigator.cpp:23
void activate()
An activation method.
Definition: navigator.cpp:32
~Navigator()=default
A destructor for opennav_docking::Navigator.
void goToPose(const geometry_msgs::msg::PoseStamped &pose, rclcpp::Duration remaining_staging_duration, std::function< bool()> isPreempted, bool recursed=false)
An method to go to a particular pose May throw exception if fails to navigate or communicate Blocks u...
Definition: navigator.cpp:53
void deactivate()
An deactivation method.
Definition: navigator.cpp:48