Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
charging_dock.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_CORE__CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING_CORE__CHARGING_DOCK_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "tf2_ros/buffer.h"
25 
26 
27 namespace opennav_docking_core
28 {
29 
35 {
36 public:
37  using Ptr = std::shared_ptr<ChargingDock>;
38 
42  virtual ~ChargingDock() {}
43 
49  virtual void configure(
50  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
51  const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf) = 0;
52 
56  virtual void cleanup() = 0;
57 
61  virtual void activate() = 0;
62 
66  virtual void deactivate() = 0;
67 
76  virtual geometry_msgs::msg::PoseStamped getStagingPose(
77  const geometry_msgs::msg::Pose & pose, const std::string & frame) = 0;
78 
84  virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string id) = 0;
85 
94  virtual bool isDocked() = 0;
95 
104  virtual bool isCharging() = 0;
105 
115  virtual bool disableCharging() = 0;
116 
120  virtual bool hasStoppedCharging() = 0;
121 
125  virtual bool isCharger() {return true;}
126 
127  std::string getName() {return name_;}
128 
129 protected:
130  std::string name_;
131 };
132 
133 } // namespace opennav_docking_core
134 
135 #endif // OPENNAV_DOCKING_CORE__CHARGING_DOCK_HPP_
Abstract interface for a charging dock for the docking framework.
virtual void cleanup()=0
Method to cleanup resources used on shutdown.
virtual bool isCharger()
Gets if this is a charging-typed dock.
virtual bool hasStoppedCharging()=0
Similar to isCharging() but called when undocking.
virtual void activate()=0
Method to active Behavior and any threads involved in execution.
virtual bool isCharging()=0
Are we charging? If a charge dock requires any sort of negotiation to begin charging,...
virtual geometry_msgs::msg::PoseStamped getStagingPose(const geometry_msgs::msg::Pose &pose, const std::string &frame)=0
Method to obtain the dock's staging pose. This method should likely be using TF and the dock's pose i...
virtual bool disableCharging()=0
Undocking while current is still flowing can damage a charge dock so some charge docks provide the ab...
virtual ~ChargingDock()
Virtual destructor.
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)=0
virtual void deactivate()=0
Method to deactive Behavior and any threads involved in execution.
virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &pose, std::string id)=0
Method to obtain the refined pose of the dock, usually based on sensors.
virtual bool isDocked()=0
Have we made contact with dock? This can be implemented in a variety of ways: by establishing communi...