Program Listing for File docking_server.hpp

Return to documentation for file (include/opennav_docking/docking_server.hpp)

// Copyright (c) 2024 Open Navigation LLC
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OPENNAV_DOCKING__DOCKING_SERVER_HPP_
#define OPENNAV_DOCKING__DOCKING_SERVER_HPP_

#include <vector>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/simple_action_server.hpp"
#include "opennav_docking/controller.hpp"
#include "opennav_docking/utils.hpp"
#include "opennav_docking/types.hpp"
#include "opennav_docking/dock_database.hpp"
#include "opennav_docking/navigator.hpp"
#include "opennav_docking_core/charging_dock.hpp"
#include "tf2_ros/transform_listener.h"

namespace opennav_docking
{
class DockingServer : public nav2_util::LifecycleNode
{
public:
  using DockingActionServer = nav2_util::SimpleActionServer<DockRobot>;
  using UndockingActionServer = nav2_util::SimpleActionServer<UndockRobot>;

  explicit DockingServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

  ~DockingServer() = default;

  void stashDockData(bool use_dock_id, Dock * dock, bool successful);

  void publishDockingFeedback(uint16_t state);

  Dock * generateGoalDock(std::shared_ptr<const DockRobot::Goal> goal);

  void doInitialPerception(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose);

  bool approachDock(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose);

  bool waitForCharge(Dock * dock);

  bool resetApproach(const geometry_msgs::msg::PoseStamped & staging_pose);

  bool getCommandToPose(
    geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose,
    double linear_tolerance, double angular_tolerance, bool backward);

  virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame(const std::string & frame);

  template<typename ActionT>
  void getPreemptedGoalIfRequested(
    typename std::shared_ptr<const typename ActionT::Goal> goal,
    const std::unique_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server);

  template<typename ActionT>
  bool checkAndWarnIfCancelled(
    std::unique_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server,
    const std::string & name);

  template<typename ActionT>
  bool checkAndWarnIfPreempted(
    std::unique_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server,
    const std::string & name);

  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;

  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;

  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;

  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;

  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;

  void publishZeroVelocity();

protected:
  void dockRobot();

  void undockRobot();

  rcl_interfaces::msg::SetParametersResult
  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);

  // Dynamic parameters handler
  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
  std::mutex dynamic_params_lock_;

  // Frequency to run control loops
  double controller_frequency_;
  // Timeout for initially detecting the charge dock
  double initial_perception_timeout_;
  // Timeout after making contact with dock for charging to start
  // If this is exceeded, the robot returns to the staging pose and retries
  double wait_charge_timeout_;
  // Timeout to approach into the dock and reset its approach is retrying
  double dock_approach_timeout_;
  // When undocking, these are the tolerances for arriving at the staging pose
  double undock_linear_tolerance_, undock_angular_tolerance_;
  // Maximum number of times the robot will return to staging pose and retry docking
  int max_retries_, num_retries_;
  // This is the root frame of the robot - typically "base_link"
  std::string base_frame_;
  // This is our fixed frame for controlling - typically "odom"
  std::string fixed_frame_;
  // Does the robot drive backwards onto the dock? Default is forwards
  bool dock_backwards_;
  // The tolerance to the dock's staging pose not requiring navigation
  double dock_prestaging_tolerance_;

  // This is a class member so it can be accessed in publish feedback
  rclcpp::Time action_start_time_;

  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr vel_publisher_;

  std::unique_ptr<DockingActionServer> docking_action_server_;
  std::unique_ptr<UndockingActionServer> undocking_action_server_;

  std::unique_ptr<DockDatabase> dock_db_;
  std::unique_ptr<Navigator> navigator_;
  std::unique_ptr<Controller> controller_;
  std::string curr_dock_type_;

  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
  std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
};

}  // namespace opennav_docking

#endif  // OPENNAV_DOCKING__DOCKING_SERVER_HPP_