15 #ifndef OPENNAV_DOCKING__DOCKING_SERVER_HPP_
16 #define OPENNAV_DOCKING__DOCKING_SERVER_HPP_
25 #include "rclcpp/rclcpp.hpp"
26 #include "nav2_util/lifecycle_node.hpp"
27 #include "nav2_util/node_utils.hpp"
28 #include "nav2_util/simple_action_server.hpp"
29 #include "nav2_util/twist_publisher.hpp"
30 #include "nav_2d_utils/odom_subscriber.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.h"
39 namespace opennav_docking
55 explicit DockingServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
96 bool approachDock(
Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose,
bool backward);
102 void rotateToDock(
const geometry_msgs::msg::PoseStamped & dock_pose);
117 bool resetApproach(
const geometry_msgs::msg::PoseStamped & staging_pose,
bool backward);
130 geometry_msgs::msg::Twist & cmd,
const geometry_msgs::msg::PoseStamped & pose,
131 double linear_tolerance,
double angular_tolerance,
bool is_docking,
bool backward);
146 template<
typename ActionT>
148 typename std::shared_ptr<const typename ActionT::Goal> goal,
157 template<
typename ActionT>
160 const std::string & name);
168 template<
typename ActionT>
171 const std::string & name);
178 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
185 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
192 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
199 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
206 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
228 rcl_interfaces::msg::SetParametersResult
232 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
235 std::shared_ptr<std::mutex> mutex_;
238 double controller_frequency_;
240 double initial_perception_timeout_;
243 double wait_charge_timeout_;
245 double dock_approach_timeout_;
247 double rotate_to_dock_timeout_;
249 double undock_linear_tolerance_, undock_angular_tolerance_;
251 int max_retries_, num_retries_;
253 std::string base_frame_;
255 std::string fixed_frame_;
257 std::optional<bool> dock_backwards_;
259 double dock_prestaging_tolerance_;
261 double rotation_angular_tolerance_;
264 rclcpp::Time action_start_time_;
266 std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
267 std::unique_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
268 std::unique_ptr<DockingActionServer> docking_action_server_;
269 std::unique_ptr<UndockingActionServer> undocking_action_server_;
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_;
276 std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
277 std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
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.
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.
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.
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.
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 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.
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.