Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
simple_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__SIMPLE_NON_CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING__SIMPLE_NON_CHARGING_DOCK_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <vector>
21 
22 #include "std_srvs/srv/trigger.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "sensor_msgs/msg/battery_state.hpp"
25 #include "sensor_msgs/msg/joint_state.hpp"
26 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
27 #include "tf2/utils.hpp"
28 #include "nav2_ros_common/lifecycle_node.hpp"
29 
30 #include "opennav_docking_core/non_charging_dock.hpp"
31 #include "opennav_docking/pose_filter.hpp"
32 
33 namespace opennav_docking
34 {
35 
37 {
38 public:
43  : NonChargingDock()
44  {}
45 
51  virtual void configure(
52  const nav2::LifecycleNode::WeakPtr & parent,
53  const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf);
54 
58  void cleanup() override;
59 
63  void activate() override;
64 
68  void deactivate() override;
69 
78  virtual geometry_msgs::msg::PoseStamped getStagingPose(
79  const geometry_msgs::msg::Pose & pose, const std::string & frame);
80 
86  virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string id);
87 
91  virtual bool isDocked();
92 
96  bool startDetectionProcess() override;
97 
101  bool stopDetectionProcess() override;
102 
103 protected:
104  void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state);
105 
106  // Optionally subscribe to a detected dock pose topic
107  nav2::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
108  nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
109  nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
110  nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
111  // If subscribed to a detected pose topic, will contain latest message
112  geometry_msgs::msg::PoseStamped detected_dock_pose_;
113  // This is the actual dock pose once it has the specified translation/rotation applied
114  // If not subscribed to a topic, this is simply the database dock pose
115  geometry_msgs::msg::PoseStamped dock_pose_;
116 
117  // Optionally subscribe to joint state message, used to determine if stalled
118  nav2::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_;
119  std::vector<std::string> stall_joint_names_;
120  double stall_velocity_threshold_, stall_effort_threshold_;
121  bool is_stalled_;
122 
123  // An external reference (such as image_proc::TrackMarkerNode) can be used to detect dock
124  bool use_external_detection_pose_;
125  double external_detection_timeout_;
126  tf2::Quaternion external_detection_rotation_;
127  double external_detection_translation_x_;
128  double external_detection_translation_y_;
129 
130  // Filtering of detected poses
131  std::shared_ptr<PoseFilter> filter_;
132 
133  // If not using an external pose reference, this is the distance threshold
134  double docking_threshold_;
135  std::string base_frame_id_;
136  // Offset for staging pose relative to dock pose
137  double staging_x_offset_;
138  double staging_yaw_offset_;
139 
140  nav2::LifecycleNode::SharedPtr node_;
141  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
142 
143  // Detector control parameters
144  std::string detector_service_name_;
145  double detector_service_timeout_{5.0};
146  bool subscribe_toggle_{false};
147 
148  // Client used to call the Trigger service
149  nav2::ServiceClient<std_srvs::srv::Trigger>::SharedPtr detector_client_;
150 
151  // Detection state flags
152  bool detection_active_{false};
153  bool initial_pose_received_{false};
154 };
155 
156 } // namespace opennav_docking
157 
158 #endif // OPENNAV_DOCKING__SIMPLE_NON_CHARGING_DOCK_HPP_
bool stopDetectionProcess() override
Stop external detection process.
virtual geometry_msgs::msg::PoseStamped getStagingPose(const geometry_msgs::msg::Pose &pose, const std::string &frame)
Method to obtain the dock's staging pose. This method should likely be using TF and the dock's pose i...
virtual void configure(const nav2::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)
virtual bool isDocked()
Have we made contact with dock? This can be implemented in a variety of ways: by establishing communi...
bool startDetectionProcess() override
Start external detection process (service call + subscribe).
void cleanup() override
Method to cleanup resources used on shutdown.
void activate() override
Method to active Behavior and any threads involved in execution.
virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &pose, std::string id)
Method to obtain the refined pose of the dock, usually based on sensors.
void deactivate() override
Method to deactivate Behavior and any threads involved in execution.
Abstract interface for a non-charging dock for the docking framework.