Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
non_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__NON_CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING_CORE__NON_CHARGING_DOCK_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "opennav_docking_core/charging_dock.hpp"
22 
23 
24 namespace opennav_docking_core
25 {
26 
32 {
33 public:
34  using Ptr = std::shared_ptr<NonChargingDock>;
35 
39  virtual ~NonChargingDock() {}
40 
46  virtual void configure(
47  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
48  const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf) = 0;
49 
53  virtual void cleanup() = 0;
54 
58  virtual void activate() = 0;
59 
63  virtual void deactivate() = 0;
64 
73  virtual geometry_msgs::msg::PoseStamped getStagingPose(
74  const geometry_msgs::msg::Pose & pose, const std::string & frame) = 0;
75 
81  virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string id) = 0;
82 
91  virtual bool isDocked() = 0;
92 
101  bool isCharging() final
102  {
103  throw std::runtime_error("This dock is not a charging dock!");
104  }
105 
115  bool disableCharging() final
116  {
117  throw std::runtime_error("This dock is not a charging dock!");
118  }
119 
123  bool hasStoppedCharging() final
124  {
125  throw std::runtime_error("This dock is not a charging dock!");
126  }
127 
131  bool isCharger() final {return false;}
132 };
133 
134 } // namespace opennav_docking_core
135 
136 #endif // OPENNAV_DOCKING_CORE__NON_CHARGING_DOCK_HPP_
Abstract interface for a charging dock for the docking framework.
Abstract interface for a non-charging dock for the docking framework.
virtual ~NonChargingDock()
Virtual destructor.
virtual void deactivate()=0
Method to deactive Behavior and any threads involved in execution.
bool disableCharging() final
Undocking while current is still flowing can damage a charge dock so some charge docks provide the ab...
bool isCharger() final
Gets if this is a charging-typed dock.
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 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 void activate()=0
Method to active Behavior and any threads involved in execution.
virtual bool isDocked()=0
Have we made contact with dock? This can be implemented in a variety of ways: by establishing communi...
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)=0
bool hasStoppedCharging() final
Similar to isCharging() but called when undocking.
bool isCharging() final
Are we charging? If a charge dock requires any sort of negotiation to begin charging,...
virtual void cleanup()=0
Method to cleanup resources used on shutdown.