Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
opennav_docking::DockingServer Class Reference

An action server which implements charger docking node for AMRs. More...

#include <nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp>

Inheritance diagram for opennav_docking::DockingServer:
Inheritance graph
[legend]
Collaboration diagram for opennav_docking::DockingServer:
Collaboration graph
[legend]

Public Types

using DockingActionServer = nav2_util::SimpleActionServer< DockRobot >
 
using UndockingActionServer = nav2_util::SimpleActionServer< UndockRobot >
 

Public Member Functions

 DockingServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A constructor for opennav_docking::DockingServer. More...
 
 ~DockingServer ()=default
 A destructor for opennav_docking::DockingServer.
 
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.
 
void publishDockingFeedback (uint16_t state)
 Publish feedback from a docking action. More...
 
DockgenerateGoalDock (std::shared_ptr< const DockRobot::Goal > goal)
 Generate a dock from action goal. More...
 
void doInitialPerception (Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose)
 Do initial perception, up to a timeout. More...
 
bool approachDock (Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose)
 Use control law and dock perception to approach the charge dock. More...
 
bool waitForCharge (Dock *dock)
 Wait for charging to begin. More...
 
bool resetApproach (const geometry_msgs::msg::PoseStamped &staging_pose)
 Reset the robot for another approach by controlling back to staging pose. More...
 
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. More...
 
virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame (const std::string &frame)
 Get the robot pose (aka base_frame pose) in another frame. More...
 
template<typename ActionT >
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. More...
 
template<typename ActionT >
bool checkAndWarnIfCancelled (std::unique_ptr< nav2_util::SimpleActionServer< ActionT >> &action_server, const std::string &name)
 Checks and logs warning if action canceled. More...
 
template<typename ActionT >
bool checkAndWarnIfPreempted (std::unique_ptr< nav2_util::SimpleActionServer< ActionT >> &action_server, const std::string &name)
 Checks and logs warning if action preempted. More...
 
nav2_util::CallbackReturn on_configure (const rclcpp_lifecycle::State &state) override
 Configure member variables. More...
 
nav2_util::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 Activate member variables. More...
 
nav2_util::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 Deactivate member variables. More...
 
nav2_util::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 Reset member variables. More...
 
nav2_util::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called when in shutdown state. More...
 
void publishZeroVelocity ()
 Publish zero velocity at terminal condition.
 
- Public Member Functions inherited from nav2_util::LifecycleNode
 LifecycleNode (const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has no integer or floating point range constraints. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has a floating point range constraint. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has an integer range constraint. More...
 
std::shared_ptr< nav2_util::LifecycleNodeshared_from_this ()
 Get a shared pointer of this.
 
nav2_util::CallbackReturn on_error (const rclcpp_lifecycle::State &)
 Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
 
void autostart ()
 Automatically configure and active the node.
 
virtual void on_rcl_preshutdown ()
 Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
 
void createBond ()
 Create bond connection to lifecycle manager.
 
void destroyBond ()
 Destroy bond connection to lifecycle manager.
 

Protected Member Functions

void dockRobot ()
 Main action callback method to complete docking request.
 
void undockRobot ()
 Main action callback method to complete undocking request.
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a parameter change is detected. More...
 
- Protected Member Functions inherited from nav2_util::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

Protected Attributes

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
 
std::shared_ptr< std::mutex > mutex_
 
double controller_frequency_
 
double initial_perception_timeout_
 
double wait_charge_timeout_
 
double dock_approach_timeout_
 
double undock_linear_tolerance_
 
double undock_angular_tolerance_
 
int max_retries_
 
int num_retries_
 
std::string base_frame_
 
std::string fixed_frame_
 
bool dock_backwards_
 
double dock_prestaging_tolerance_
 
rclcpp::Time action_start_time_
 
std::unique_ptr< nav2_util::TwistPublishervel_publisher_
 
std::unique_ptr< DockingActionServerdocking_action_server_
 
std::unique_ptr< UndockingActionServerundocking_action_server_
 
std::unique_ptr< DockDatabasedock_db_
 
std::unique_ptr< Navigatornavigator_
 
std::unique_ptr< Controllercontroller_
 
std::string curr_dock_type_
 
std::shared_ptr< tf2_ros::Buffer > tf2_buffer_
 
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
 
- Protected Attributes inherited from nav2_util::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::unique_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Detailed Description

An action server which implements charger docking node for AMRs.

Definition at line 43 of file docking_server.hpp.

Constructor & Destructor Documentation

◆ DockingServer()

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

A constructor for opennav_docking::DockingServer.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 27 of file docking_server.cpp.

Member Function Documentation

◆ approachDock()

bool opennav_docking::DockingServer::approachDock ( Dock dock,
geometry_msgs::msg::PoseStamped &  dock_pose 
)

Use control law and dock perception to approach the charge dock.

Parameters
dockDock instance, gets queried for refined pose and docked state.
dock_poseInitial dock pose, will be refined by perception.
Returns
True if dock successfully approached, False if cancelled. For any internal error, will throw.

Definition at line 405 of file docking_server.cpp.

References checkAndWarnIfCancelled(), checkAndWarnIfPreempted(), and publishDockingFeedback().

Referenced by dockRobot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ checkAndWarnIfCancelled()

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

Checks and logs warning if action canceled.

Parameters
action_serverAction server to check for cancellation on
nameName of action to put in warning message
Returns
True if action has been cancelled

Definition at line 179 of file docking_server.cpp.

Referenced by approachDock(), dockRobot(), doInitialPerception(), resetApproach(), undockRobot(), and waitForCharge().

Here is the caller graph for this function:

◆ checkAndWarnIfPreempted()

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

Checks and logs warning if action preempted.

Parameters
action_serverAction server to check for preemption on
nameName of action to put in warning message
Returns
True if action has been preempted

Definition at line 191 of file docking_server.cpp.

Referenced by approachDock(), dockRobot(), doInitialPerception(), resetApproach(), undockRobot(), and waitForCharge().

Here is the caller graph for this function:

◆ doInitialPerception()

void opennav_docking::DockingServer::doInitialPerception ( Dock dock,
geometry_msgs::msg::PoseStamped &  dock_pose 
)

Do initial perception, up to a timeout.

Parameters
dockDock instance, gets queried for refined pose.
dock_poseInitial dock pose, will be refined by perception.

Definition at line 384 of file docking_server.cpp.

References checkAndWarnIfCancelled(), checkAndWarnIfPreempted(), and publishDockingFeedback().

Referenced by dockRobot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dynamicParametersCallback()

rcl_interfaces::msg::SetParametersResult opennav_docking::DockingServer::dynamicParametersCallback ( std::vector< rclcpp::Parameter >  parameters)
protected

Callback executed when a parameter change is detected.

Parameters
eventParameterEvent message

Definition at line 719 of file docking_server.cpp.

Referenced by on_activate().

Here is the caller graph for this function:

◆ generateGoalDock()

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

Generate a dock from action goal.

Parameters
goalAction goal
Returns
Raw dock pointer to manage;

Definition at line 374 of file docking_server.cpp.

Referenced by dockRobot().

Here is the caller graph for this function:

◆ getCommandToPose()

bool opennav_docking::DockingServer::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.

Parameters
cmdThe return command.
poseThe pose to command towards.
linear_tolerancePose is reached when linear distance is within this tolerance.
angular_tolerancePose is reached when angular distance is within this tolerance.
is_dockingIf true, the robot is docking. If false, the robot is undocking.
backwardIf true, the robot will drive backwards.
Returns
True if pose is reached.

Definition at line 538 of file docking_server.cpp.

References getRobotPoseInFrame().

Referenced by resetApproach(), and undockRobot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPreemptedGoalIfRequested()

template<typename ActionT >
void opennav_docking::DockingServer::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.

Parameters
Goalgoal to check or replace if required with preemption
action_serverAction server to check for preemptions on
Returns
SUCCESS or FAILURE

Definition at line 169 of file docking_server.cpp.

Referenced by dockRobot(), and undockRobot().

Here is the caller graph for this function:

◆ getRobotPoseInFrame()

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

Get the robot pose (aka base_frame pose) in another frame.

Parameters
frameThe frame_id to get the robot pose in.
Returns
Computed robot pose, throws TF2 error if failure.

Definition at line 693 of file docking_server.cpp.

Referenced by dockRobot(), getCommandToPose(), and undockRobot().

Here is the caller graph for this function:

◆ on_activate()

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

Activate member variables.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 101 of file docking_server.cpp.

References nav2_util::LifecycleNode::createBond(), dynamicParametersCallback(), and nav2_util::LifecycleNode::shared_from_this().

Here is the call graph for this function:

◆ on_cleanup()

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

Reset member variables.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 147 of file docking_server.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ on_configure()

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

Configure member variables.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 46 of file docking_server.cpp.

References dockRobot(), on_cleanup(), nav2_util::LifecycleNode::shared_from_this(), and undockRobot().

Here is the call graph for this function:

◆ on_deactivate()

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

Deactivate member variables.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 126 of file docking_server.cpp.

References nav2_util::LifecycleNode::destroyBond().

Here is the call graph for this function:

◆ on_shutdown()

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

Called when in shutdown state.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 162 of file docking_server.cpp.

◆ publishDockingFeedback()

void opennav_docking::DockingServer::publishDockingFeedback ( uint16_t  state)

Publish feedback from a docking action.

Parameters
stateCurrent state - should be one of those defined in message.

Definition at line 709 of file docking_server.cpp.

Referenced by approachDock(), dockRobot(), doInitialPerception(), resetApproach(), and waitForCharge().

Here is the caller graph for this function:

◆ resetApproach()

bool opennav_docking::DockingServer::resetApproach ( const geometry_msgs::msg::PoseStamped &  staging_pose)

Reset the robot for another approach by controlling back to staging pose.

Parameters
staging_poseThe target pose that will reset for another approach.
Returns
True if reset is successful.

Definition at line 503 of file docking_server.cpp.

References checkAndWarnIfCancelled(), checkAndWarnIfPreempted(), getCommandToPose(), and publishDockingFeedback().

Referenced by dockRobot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ waitForCharge()

bool opennav_docking::DockingServer::waitForCharge ( Dock dock)

Wait for charging to begin.

Parameters
dockDock instance, used to query isCharging().
Returns
True if charging successfully started within alloted time.

Definition at line 471 of file docking_server.cpp.

References checkAndWarnIfCancelled(), checkAndWarnIfPreempted(), and publishDockingFeedback().

Referenced by dockRobot().

Here is the call graph for this function:
Here is the caller graph for this function:

The documentation for this class was generated from the following files: