Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
docking_server.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__DOCKING_SERVER_HPP_
16 #define OPENNAV_DOCKING__DOCKING_SERVER_HPP_
17 
18 #include <vector>
19 #include <memory>
20 #include <string>
21 #include <mutex>
22 #include <functional>
23 
24 #include "rclcpp/rclcpp.hpp"
25 #include "nav2_util/lifecycle_node.hpp"
26 #include "nav2_util/node_utils.hpp"
27 #include "nav2_util/simple_action_server.hpp"
28 #include "nav2_util/twist_publisher.hpp"
29 #include "opennav_docking/controller.hpp"
30 #include "opennav_docking/utils.hpp"
31 #include "opennav_docking/types.hpp"
32 #include "opennav_docking/dock_database.hpp"
33 #include "opennav_docking/navigator.hpp"
34 #include "opennav_docking_core/charging_dock.hpp"
35 #include "tf2_ros/transform_listener.h"
36 
37 namespace opennav_docking
38 {
44 {
45 public:
48 
53  explicit DockingServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
54 
58  ~DockingServer() = default;
59 
64  void stashDockData(bool use_dock_id, Dock * dock, bool successful);
65 
70  void publishDockingFeedback(uint16_t state);
71 
77  Dock * generateGoalDock(std::shared_ptr<const DockRobot::Goal> goal);
78 
84  void doInitialPerception(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose);
85 
93  bool approachDock(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose);
94 
100  bool waitForCharge(Dock * dock);
101 
107  bool resetApproach(const geometry_msgs::msg::PoseStamped & staging_pose);
108 
119  bool getCommandToPose(
120  geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose,
121  double linear_tolerance, double angular_tolerance, bool is_docking, bool backward);
122 
128  virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame(const std::string & frame);
129 
136  template<typename ActionT>
138  typename std::shared_ptr<const typename ActionT::Goal> goal,
139  const std::unique_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server);
140 
147  template<typename ActionT>
149  std::unique_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server,
150  const std::string & name);
151 
158  template<typename ActionT>
160  std::unique_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server,
161  const std::string & name);
162 
168  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
169 
175  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
176 
182  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
183 
189  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
190 
196  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
197 
201  void publishZeroVelocity();
202 
203 protected:
207  void dockRobot();
208 
212  void undockRobot();
213 
218  rcl_interfaces::msg::SetParametersResult
219  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
220 
221  // Dynamic parameters handler
222  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
223 
224  // Mutex for dynamic parameters and dock database
225  std::shared_ptr<std::mutex> mutex_;
226 
227  // Frequency to run control loops
228  double controller_frequency_;
229  // Timeout for initially detecting the charge dock
230  double initial_perception_timeout_;
231  // Timeout after making contact with dock for charging to start
232  // If this is exceeded, the robot returns to the staging pose and retries
233  double wait_charge_timeout_;
234  // Timeout to approach into the dock and reset its approach is retrying
235  double dock_approach_timeout_;
236  // When undocking, these are the tolerances for arriving at the staging pose
237  double undock_linear_tolerance_, undock_angular_tolerance_;
238  // Maximum number of times the robot will return to staging pose and retry docking
239  int max_retries_, num_retries_;
240  // This is the root frame of the robot - typically "base_link"
241  std::string base_frame_;
242  // This is our fixed frame for controlling - typically "odom"
243  std::string fixed_frame_;
244  // Does the robot drive backwards onto the dock? Default is forwards
245  bool dock_backwards_;
246  // The tolerance to the dock's staging pose not requiring navigation
247  double dock_prestaging_tolerance_;
248 
249  // This is a class member so it can be accessed in publish feedback
250  rclcpp::Time action_start_time_;
251 
252  std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
253  std::unique_ptr<DockingActionServer> docking_action_server_;
254  std::unique_ptr<UndockingActionServer> undocking_action_server_;
255 
256  std::unique_ptr<DockDatabase> dock_db_;
257  std::unique_ptr<Navigator> navigator_;
258  std::unique_ptr<Controller> controller_;
259  std::string curr_dock_type_;
260 
261  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
262  std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
263 };
264 
265 } // namespace opennav_docking
266 
267 #endif // OPENNAV_DOCKING__DOCKING_SERVER_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.
An action server which implements charger docking node for AMRs.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
bool checkAndWarnIfPreempted(std::unique_ptr< nav2_util::SimpleActionServer< ActionT >> &action_server, const std::string &name)
Checks and logs warning if action preempted.
virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame(const std::string &frame)
Get the robot pose (aka base_frame pose) in another frame.
void dockRobot()
Main action callback method to complete docking request.
bool resetApproach(const geometry_msgs::msg::PoseStamped &staging_pose)
Reset the robot for another approach by controlling back to staging pose.
void doInitialPerception(Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose)
Do initial perception, up to a timeout.
void publishDockingFeedback(uint16_t state)
Publish feedback from a docking action.
DockingServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for opennav_docking::DockingServer.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
bool getCommandToPose(geometry_msgs::msg::Twist &cmd, const geometry_msgs::msg::PoseStamped &pose, double linear_tolerance, double angular_tolerance, bool is_docking, bool backward)
Run a single iteration of the control loop to approach a pose.
bool waitForCharge(Dock *dock)
Wait for charging to begin.
Dock * generateGoalDock(std::shared_ptr< const DockRobot::Goal > goal)
Generate a dock from action goal.
~DockingServer()=default
A destructor for opennav_docking::DockingServer.
bool approachDock(Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose)
Use control law and dock perception to approach the charge dock.
void getPreemptedGoalIfRequested(typename std::shared_ptr< const typename ActionT::Goal > goal, const std::unique_ptr< nav2_util::SimpleActionServer< ActionT >> &action_server)
Gets a preempted goal if immediately requested.
void publishZeroVelocity()
Publish zero velocity at terminal condition.
void undockRobot()
Main action callback method to complete undocking request.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
void stashDockData(bool use_dock_id, Dock *dock, bool successful)
Called at the conclusion of docking actions. Saves relevant docking data for later undocking action.
bool checkAndWarnIfCancelled(std::unique_ptr< nav2_util::SimpleActionServer< ActionT >> &action_server, const std::string &name)
Checks and logs warning if action canceled.
Definition: types.hpp:33