Nav2 Navigation Stack - rolling  main
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 <functional>
19 #include <memory>
20 #include <mutex>
21 #include <optional>
22 #include <string>
23 #include <vector>
24 
25 #include "rclcpp/rclcpp.hpp"
26 #include "nav2_ros_common/lifecycle_node.hpp"
27 #include "nav2_ros_common/node_utils.hpp"
28 #include "nav2_ros_common/simple_action_server.hpp"
29 #include "nav2_util/twist_publisher.hpp"
30 #include "nav2_util/odometry_utils.hpp"
31 #include "opennav_docking/controller.hpp"
32 #include "opennav_docking/utils.hpp"
33 #include "opennav_docking/types.hpp"
34 #include "opennav_docking/dock_database.hpp"
35 #include "opennav_docking/navigator.hpp"
36 #include "opennav_docking_core/charging_dock.hpp"
37 #include "tf2_ros/transform_listener.hpp"
38 
39 namespace opennav_docking
40 {
46 {
47 public:
50 
55  explicit DockingServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
56 
60  ~DockingServer() = default;
61 
66  void stashDockData(bool use_dock_id, Dock * dock, bool successful);
67 
72  void publishDockingFeedback(uint16_t state);
73 
79  Dock * generateGoalDock(std::shared_ptr<const DockRobot::Goal> goal);
80 
86  void doInitialPerception(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose);
87 
96  bool approachDock(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose, bool backward);
97 
102  void rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose);
103 
109  bool waitForCharge(Dock * dock);
110 
117  bool resetApproach(const geometry_msgs::msg::PoseStamped & staging_pose, bool backward);
118 
129  bool getCommandToPose(
130  geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose,
131  double linear_tolerance, double angular_tolerance, bool is_docking, bool backward);
132 
138  virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame(const std::string & frame);
139 
146  template<typename ActionT>
148  typename std::shared_ptr<const typename ActionT::Goal> goal,
149  const typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server);
150 
157  template<typename ActionT>
159  typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server,
160  const std::string & name);
161 
168  template<typename ActionT>
170  typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server,
171  const std::string & name);
172 
178  nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
179 
185  nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
186 
192  nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
193 
199  nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
200 
206  nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
207 
211  void publishZeroVelocity();
212 
213 protected:
217  void dockRobot();
218 
222  void undockRobot();
223 
228  rcl_interfaces::msg::SetParametersResult
229  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
230 
231  // Dynamic parameters handler
232  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
233 
234  // Mutex for dynamic parameters and dock database
235  std::shared_ptr<std::mutex> mutex_;
236 
237  // Frequency to run control loops
238  double controller_frequency_;
239  // Timeout for initially detecting the charge dock
240  double initial_perception_timeout_;
241  // Timeout after making contact with dock for charging to start
242  // If this is exceeded, the robot returns to the staging pose and retries
243  double wait_charge_timeout_;
244  // Timeout to approach into the dock and reset its approach is retrying
245  double dock_approach_timeout_;
246  // Timeout to rotate to the dock
247  double rotate_to_dock_timeout_;
248  // When undocking, these are the tolerances for arriving at the staging pose
249  double undock_linear_tolerance_, undock_angular_tolerance_;
250  // Maximum number of times the robot will return to staging pose and retry docking
251  int max_retries_, num_retries_;
252  // This is the root frame of the robot - typically "base_link"
253  std::string base_frame_;
254  // This is our fixed frame for controlling - typically "odom"
255  std::string fixed_frame_;
256  // Does the robot drive backwards onto the dock? Default is forwards
257  std::optional<bool> dock_backwards_;
258  // The tolerance to the dock's staging pose not requiring navigation
259  double dock_prestaging_tolerance_;
260  // Angular tolerance to exit the rotation loop when rotate_to_dock is enabled
261  double rotation_angular_tolerance_;
262 
263  // This is a class member so it can be accessed in publish feedback
264  rclcpp::Time action_start_time_;
265 
266  std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
267  std::unique_ptr<nav2_util::OdomSmoother> odom_sub_;
268  typename DockingActionServer::SharedPtr docking_action_server_;
269  typename UndockingActionServer::SharedPtr undocking_action_server_;
270 
271  std::unique_ptr<DockDatabase> dock_db_;
272  std::unique_ptr<Navigator> navigator_;
273  std::unique_ptr<Controller> controller_;
274  std::string curr_dock_type_;
275 
276  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
277  std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
278 };
279 
280 } // namespace opennav_docking
281 
282 #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.
virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame(const std::string &frame)
Get the robot pose (aka base_frame pose) in another frame.
bool resetApproach(const geometry_msgs::msg::PoseStamped &staging_pose, bool backward)
Reset the robot for another approach by controlling back to staging pose.
void dockRobot()
Main action callback method to complete docking request.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
bool approachDock(Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose, bool backward)
Use control law and dock perception to approach the charge dock.
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.
bool checkAndWarnIfCancelled(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server, const std::string &name)
Checks and logs warning if action canceled.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
bool checkAndWarnIfPreempted(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server, const std::string &name)
Checks and logs warning if action preempted.
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.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
void getPreemptedGoalIfRequested(typename std::shared_ptr< const typename ActionT::Goal > goal, const typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server)
Gets a preempted goal if immediately requested.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables.
void publishZeroVelocity()
Publish zero velocity at terminal condition.
void rotateToDock(const geometry_msgs::msg::PoseStamped &dock_pose)
Perform a pure rotation to dock orientation.
void undockRobot()
Main action callback method to complete undocking request.
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.
Definition: types.hpp:33