From a86f194a12b073ab6dc5ed40933ef5162fc4eb51 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Sat, 8 Jun 2024 12:08:01 -0700 Subject: [PATCH] migrate msgs --- nav2_msgs/action/DockRobot.action | 42 ++++++++++++++++++++++++++++ nav2_msgs/action/UndockRobot.action | 25 +++++++++++++++++ nav2_msgs/srv/ReloadDockDatabase.srv | 5 ++++ 3 files changed, 72 insertions(+) create mode 100644 nav2_msgs/action/DockRobot.action create mode 100644 nav2_msgs/action/UndockRobot.action create mode 100644 nav2_msgs/srv/ReloadDockDatabase.srv diff --git a/nav2_msgs/action/DockRobot.action b/nav2_msgs/action/DockRobot.action new file mode 100644 index 0000000000..fc85e6cca9 --- /dev/null +++ b/nav2_msgs/action/DockRobot.action @@ -0,0 +1,42 @@ +#goal definition + +bool use_dock_id True # Whether to use the dock_id or dock_pose fields +string dock_id # Dock name or ID to dock at, from given dock database + +geometry_msgs/PoseStamped dock_pose # Dock pose +string dock_type # If using dock_pose, what type of dock it is. Not necessary if only using one type of dock. + +float32 max_staging_time 1000.0 # Maximum time for navigation to get to the dock's staging pose. +bool navigate_to_staging_pose True # Whether or not to navigate to staging pose or assume robot is already at staging pose within tolerance to execute behavior + +--- +#result definition + +# Error codes +# Note: The expected priority order of the errors should match the message order +uint16 NONE=0 +uint16 DOCK_NOT_IN_DB=901 +uint16 DOCK_NOT_VALID=902 +uint16 FAILED_TO_STAGE=903 +uint16 FAILED_TO_DETECT_DOCK=904 +uint16 FAILED_TO_CONTROL=905 +uint16 FAILED_TO_CHARGE=906 +uint16 UNKNOWN=999 + +bool success True # docking success status +uint16 error_code 0 # Contextual error code, if any +uint16 num_retries 0 # Number of retries attempted + +--- +#feedback definition + +uint16 NONE=0 +uint16 NAV_TO_STAGING_POSE=1 +uint16 INITIAL_PERCEPTION=2 +uint16 CONTROLLING=3 +uint16 WAIT_FOR_CHARGE=4 +uint16 RETRY=5 + +uint16 state # Current docking state +builtin_interfaces/Duration docking_time # Docking time elapsed +uint16 num_retries 0 # Number of retries attempted diff --git a/nav2_msgs/action/UndockRobot.action b/nav2_msgs/action/UndockRobot.action new file mode 100644 index 0000000000..4ab21a75dd --- /dev/null +++ b/nav2_msgs/action/UndockRobot.action @@ -0,0 +1,25 @@ +#goal definition + +# If initialized on a dock so the server doesn't know what type of dock its on, +# you must specify what dock it is to know where to stage for undocking. +# If only one type of dock plugin is present, it is not necessary to set. +# If not set & server instance was used to dock, server will use current dock information from last docking request. +string dock_type + +float32 max_undocking_time 30.0 # Maximum time to undock + +--- +#result definition + +# Error codes +# Note: The expected priority order of the errors should match the message order +uint16 NONE=0 +uint16 DOCK_NOT_VALID=902 +uint16 FAILED_TO_CONTROL=905 +uint16 UNKNOWN=999 + +bool success True # docking success status +uint16 error_code 0 # Contextual error code, if any + +--- +#feedback definition diff --git a/nav2_msgs/srv/ReloadDockDatabase.srv b/nav2_msgs/srv/ReloadDockDatabase.srv new file mode 100644 index 0000000000..fb6f36d7a4 --- /dev/null +++ b/nav2_msgs/srv/ReloadDockDatabase.srv @@ -0,0 +1,5 @@ +# Reloads the dock's database with a new filepath + +string filepath +--- +bool success