Skip to main content
Version: 0.14.0

Autonomy API

The Autonomy provides some relevant topics and services suitable for controlling and monitoring the robot as it is performing autonomous navigation.

Topics Published by Autonomy

The OutdoorNav software publishes to the topics in this section either all the time or while an autonomous navigation missions is running. They can be used to monitor the behaviour of OutdoorNav.

/assisted_teleop/cmd_vel

  Message Type: geometry_msgs/Twist

  Description: The safe output velocity from the assisted teleop node computes. If assisted teleop is enabled the UGV will use this velocity.

/assisted_teleop/footprint

  Message Type: geometry_msgs/Polygon

  Description: The footprint that the assisted teleop node uses to compute if it is in a collision state.

/assisted_teleop/obstacle_map

  Message Type: clearpath_safety_msgs/ObstacleMap

  Description: The radial mapping of detected obstacles used to populate the joystick on the OutdoorNav UI.

/assisted_teleop/safe_path

  Message Type: nav_msgs/Path

  Description: The path used by assisted teleop to lookahead for collisions.

/assisted_teleop/safety_footprints

  Message Type: nav_msgs/Path

  Description: Footprint sets used for detecting obstacles and slowing down the robot to a standstill. The footprints are modular in size according to the current velocity of the robot.

/assisted_teleop/state

  Message Type: clearpath_safety_msgs/AssistedTeleopState

  Description: The current state of the assisted teleop node including any error conditions that may occur.

/control_selection/control_state

  Message Type: clearpath_control_msgs/ControlSelectionState

  Description: Indicates the complete state of control selection including autonomy state and mode.

/control_selection/current_mode

  Message Type: clearpath_control_msgs/ControlMode

  Description: Current control mode (NEUTRAL, MANUAL, AUTONOMY).

/dock/feedback

  Message Type: clearpath_dock_msgs/DockActionFeedback

  Description: Feedback topic from the dock action.

/dock/result

  Message Type: clearpath_dock_msgs/DockActionResult

  Description: Result topic from the dock action.

/dock/properties

  Message Type: clearpath_dock_msgs/DockProperties

  Description: A list of docks, in which each dock includes information related to the location, id, etc...

/dock/state

  Message Type: clearpath_dock_msgs/DockState

  Description: The current state of the docking process.

/localization/odom

  Message Type: nav_msgs/Odometry

  Description: The robot's current pose and velocity.

/localization/status

  Message Type: clearpath_localization_msgs/LocalizationStatus

  Description: Current localization status. Includes accuracy, GNSS status, and whether the robot is dead reckoning.

/mission/feedback

  Message Type: clearpath_navigation_msgs/MissionActionFeedback

  Description: Feedback topic from the mission action.

/mission/result

  Message Type: clearpath_navigation_msgs/MissionActionResult

  Description: Result topic from the mission action.

  Message Type: geometry_msgs/Twist

  Description: This output commanded velocity from the autonomy software (OutdoorNav) to control the velocity of the platform. It is commonly relayed directly into the UGV's velocity controller.

  Message Type: clearpath_navigation_msgs/DistanceToGoal

  Description: The current Euclidean distance and the path distance, in meters, from the robot to its current goal.

  Message Type: geometry_msgs/Polygon

  Description: The footprint of the robot.

  Message Type: nav_msgs/OccupancyGrid

  Description: An occupancy grid consisting of the Free, Occupied or Unknown space that the robot uses to plan paths in the environment.

  Message Type: nav_msgs/OccupancyGrid

  Description: An occupancy grid consisting of the Free, Occupied or Unknown space that the robot uses to detect obstacles.

  Message Type: nav_msgs/Path

  Description: The MPC local plan that the navigation uses to control the robot along the reference path.

  Message Type: clearpath_navigation_msgs/Metrics

  Description: This topic provides metric information regarding the lifetime of the navigation. This includes the total distance travelled, duration run, as well as mission information such as how many missions have been sent, how many have been completed and the number of replanning maneuvers, recoveries and number of tasks executed.

  Message Type: clearpath_navigation_msgs/MotionState

  Description: This topic provides information about the motion state of the robot. This includes information about whether the robot is moving or stopped. Whether it is about to make a turn and the direction of the turn, and the direction of travel of the robot in regards to its physical orientation.

  Message Type: clearpath_navigation_msgs/OdomIntent

  Description: The robot's current pose and velocity as well as an intended pose and velocity in the immediate future.

  Message Type: geometry_msgs/PoseArray

  Description: The path that the robot is currently traversing. This is initialized with the initial path and may be updated with paths generated from replanning maneuvers.

  Message Type: clearpath_navigation_msgs/Progress

  Description: The completion percentage of the current path, the current goal and the current mission.

  Message Type: geometry_msgs/PolygonStamped

  Description: Footprint sets used for detecting obstacles and slowing down the robot to a standstill. The footprints are modular in size according to the current velocity of the robot.

  Message Type: clearpath_navigation_msgs/ScanPoints

  Description: Scans and pointclouds from the various ROS message formats converted into a simple PointVector format that can be easily consumed by the UI.

  Message Type: clearpath_navigation_msgs/NavigationState

  Description: The current navigation state. The available states are COMPUTE PATH, EXECUTE, REPLAN, NAVIGATING AROUND OBSTACLE, RECOVERY, IDLE, PAUSE, ESTOP, LOST. Multiple simultaneous states are possible.

  Message Type: clearpath_navigation_msgs/TrackError

  Description: The current crosstrack error (ie. the off-path distance between the robot and the reference path) and as well as the heading error (ie. the difference between the current heading and the path direction).

/onav_log/delete_record

  Message Type: clearpath_logger_msgs/DeleteLog

  Description: Deletes a log as specified by the UUID provided. If the purge flag is set the log will be removed from the internal records entirely. If not, then the record will be marked as deleted and the meta data preserved, though the log data will still be deleted.

/onav_log/download_kmz

  Message Type: clearpath_logger_msgs/DownloadLog

  Description: Converts the record with the given UUID into a KMZ file.

/onav_log/download_zip

  Message Type: clearpath_logger_msgs/DownloadLog

  Description: Zips the raw contents of the record.

/onav_log/get_all_logs

  Message Type: clearpath_logger_msgs/GetAllLogs

  Description: Returns an array of all Event logs recorded in the database.

/onav_log/record_custom_event

  Message Type: clearpath_logger_msgs/RecordCustomEvent

  Description: Adds a custom event to the currently recording log. Automatic telemetry, like power and location are added to the event if possible.

/onav_log/record_error_event

  Message Type: clearpath_logger_msgs/RecordErrorEvent

  Description: Add an error/debugging event to the currently recording log.

/onav_log/record_event

  Message Type: clearpath_logger_msgs/RecordEvent

  Description: Add a fully formed event to the currently recording log.

/onav_log/record_location_event

  Message Type: clearpath_logger_msgs/RecordLocationEvent

  Description: Adds a location event to the currently recording log. Automatic telemetry like power is added to the event if possible.

/onav_log/record_media_event

  Message Type: clearpath_logger_msgs/RecordMediaEvent

  Description: Adds a media-recording event to the currently recording log. The media file is symlinked into the log directory. Automatic telemetry like power is added to the event if possible.

/onav_log/record_power_event

  Message Type: clearpath_logger_msgs/RecordPowerEvent

  Description: Add a power event to the currently recording log. Automatic telemetry like location is added to the event if possible.

/onav_log/start_recording

  Message Type: clearpath_logger_msgs/StartRecording

  Description: Start recording a new log.

/onav_log/stop_recording

  Message Type: clearpath_logger_msgs/StopRecording

  Description: Stop recording the active log.

/safety/safety_stop

  Message Type: clearpath_safety_msgs/Safety

  Description: Flag denoting if autonomy should be stopped due to any of the following reasons: emergency stop active, one of the sensors has triggered the safety monitor watchdog.

/safety/watchdog_status (IN DEVELOPMENT)

  Message Type: clearpath_safety_msgs/WatchdogStatus

  Description: Provides a list of status flags for each of the possible sensors that may trigger a safety stop. The watchdog will trigger if the sensor times out (ie. does not publish a relevant ROS message for 1 second).

/target_tracker/state

  Message Type: clearpath_dock_msgs/TargetTrackerState

  Description: The state information for target tracker used as part of docking.

/undock/feedback

  Message Type: clearpath_dock_msgs/UndockActionFeedback

  Description: Feedback topic from the undock action.

/undock/result

  Message Type: clearpath_dock_msgs/UndockActionResult

  Description: Result topic from the undock action.


Topics Subscribed to by Autonomy

The OutdoorNav software subscribes to the topics in this section. They can be used to control the behaviour of OutdoorNav.

/platform/cmd_vel

  Message Type: geometry_msgs/Twist

  Description: Platform-level commanded velocity. This should be the velocity tracked by the platforms velocity controller.

/mission/cancel

  Message Type: actionlib_msgs/GoalID

  Description: This topic is used to cancel all the missions that have been sent to the OutdoorNav software.

/mission/goal

  Message Type: clearpath_navigation_msgs/msg/MissionActionGoal

  Description: This topic is used to send a goal to the OutdoorNav software. The goal can consist of a series of Waypoints and must include a Goal point.

/dock/cancel

  Message Type: actionlib_msgs/GoalID

  Description: This topic is used to cancel the docking process that has been initialized by a previously sent goal.

/dock/goal

  Message Type: clearpath_dock_msgs/msg/DockActionGoal

  Description: This topic is used to send a goal to the docking process. The goal consists of the UUID of the dock to dock at as well as wether or not local docking should be performed.

/undock/cancel

  Message Type: actionlib_msgs/GoalID

  Description: This topic is used to cancel the undocking process that has been initialized by a previously sent goal.

/undock/goal

  Message Type: clearpath_dock_msgs/msg/UndockActionGoal

  Description: This topic is used to send a goal to the undocking process. The goal is empty since we always consider undocking to be a local undocking process.


Services Exported by Autonomy

/control_selection/set_mode

  Service Type: clearpath_control_msgs/srv/SetControlMode

  Description: Change the current control mode from NEUTRAL to MANUAL or AUTONOMY.

/control_selection/autonomy_pause

  Service Type: std_srvs/SetBool

  Description: Pause the autonomy when it is currently in AUTONOMY mode. Will only pause when autonomy is active.

/control_selection/autonomy_resume

  Service Type: std_srvs/SetBool

  Description: Resume the autonomy when it is current mode is in AUTONOMY. Will only resume if the robot is in a paused state.

/dock/add

  Service Type: clearpath_dock_msgs/srv/AddDock

  Description: Add a dock to the database of docks. Complete list of dock information is required as input. The new dock will appear on the UI.

/dock/remove

  Service Type: clearpath_dock_msgs/srv/RemoveDock

  Description: Remove and existing dock from the database. Input to this service requires ether the UUID or the semantic name of the dock.

/dock/clear_data

  Service Type: std_srvs/srv/Trigger

  Description: Remove all existing dock data from storage.

/dock/set_location/by_id

  Service Type: clearpath_dock_msgs/srv/SetDockLocationByID

  Description: Can be used to either set up a new dock (empty string in the uuid field), or update the location of an existing dock (where the uuid field is required).

/dock/set_location/by_name

  Service Type: clearpath_dock_msgs/srv/SetDockLocationByName

  Description: Can be used to update the location of an existing dock. Requires the semantic name of the dock to be input into the name field.

/localization/set_datum

  Service Type: clearpath_localization_msgs/srv/SetDatum

  Description: This service is used to manually set the datum parameters of OutdoorNav running on the UGV. After setting the datum parameter, this service also reinitializes the states of the localization according to the current sensor readings. If you are sending a mission to the UGV without using the UI and through the API, you must call this service before sending the mission.

/localization/reset

  Service Type: clearpath_localization_msgs/srv/ResetLocalization

  Description: This service can be used to trigger a reset of the UGVs localization.

  Service Type: std_srvs/SetBool

  Description: Modify the state of the collision avoidance feature. If True, collision avoidance is ENABLED and the robot will use its lidar(s) to detect and maneuver around obstacles. If False, collision avoidance is DISABLED and the robot will NOT use its lidar(s) to detect and maneuver around obstacles. Disabling this feature is not recommended and should be used with caution.

note
  1. This feature does not take effect immediately when the service is called, but only takes effect at the next Goal.

  2. Disabling collision avoidance also disables the continuous planner, in such a case where the continuous planner is enabled. When re-enabling the collision avoidance, the continuous planner must also be re-enabled using the following API service.

  Service Type: std_srvs/SetBool

  Description: Modify the state of the continuous planning feature. If True, continuous planning is ENABLED and the robot will proactively attempt to generate a path around detected obstacles. If False, continuous planning is DISABLED and the robot will stop in front of obstacles before generating a path around the obstacle.

note
  1. This feature takes effect immediately once the service is called.
  2. This service needs to be called if you are re-enabling the collision avoidance and want the continuous planner to be active. Disabling collision avoidance will have disabled the continous planner.

  Service Type: clearpath_navigation_msgs/srv/SetPathSmoother

  Description: Modify the state of the path smoothing feature. If True, path smoothing is ENABLED and curved paths will be generated according to the specified turning radius. If False, path smoothing is DISABLED and point-to-point paths will be generated.

note

This feature takes effect immediately once the service is called.

  Service Type: clearpath_navigation_msgs/srv/SetPathShifter

  Description: Modify the state of the path shifting feature. If True, path shifting is ENABLED and the reference path will be automatically shifted as it veers off the reference path (to prevent oscillations). If False, path shifting is DISABLED and normal behaviour is active.

note

This feature takes effect immediately once the service is called.

  Service Type: clearpath_navigation_msgs/srv/SetStopDistance

  Description: Modify the state of the stop distance feature. If True, the stop distance feature is ENABLED and the robot will stop the specified distance from obstacles. If False, the stop distance feature is DISABLED and the robot will stop the default distance from obstacles.

  Service Type: clearpath_navigation_msgs/srv/SetDelayCompensation

  Description: Modify the state of the delay compensation feature. If True, delay compensation is ENABLED and the controller will compensate for low-level mechanical delays. If False, delay compensation is DISABLED and the normal behaviour is expected.


Actions Exported by Autonomy

/autonomy/dock/local

  Action Type: clearpath_dock_msgs/action/LocalDock

  Description: Send the robot to the charging dock, if the UGV is facing and within range of a dock.

/autonomy/dock/network

  Action Type: clearpath_dock_msgs/action/NetworkDock

  Description: Send the robot to the charging dock by navigating through an existing network map.

/autonomy/dock/radius

  Action Type: clearpath_dock_msgs/action/RadiusDock

  Description: Send the robot to the charging dock if the UGV is within a certain radius of the dock.

/autonomy/inspect_poi

  Action Type: clearpath_camera_msgs/action/InspectPOIAction

  Description: Action call to move the PTZ camera to look at a POI.

/localization/survey

  Action Type: clearpath_localization_msgs/action/SurveyBaseStation

  Description: Start surveying the base station, if available.

/autonomy/mission

  Action Type: clearpath_navigation_msgs/action/Mission

  Description: Send goals for execution by the robot. This will include the goal, the waypoint(s), tasks, goal tolerances, goal heading, a from_start flag, and an optional start_waypoint_uuid.

/autonomy/mission/by_id

  Action Type: clearpath_navigation_msgs/action/ExecuteMissionByUuid

  Description: Send goals for execution by the robot according to the specific mission uuid. This will include the goal, the waypoint(s), tasks, goal tolerances, goal heading, an optional start_waypoint_uuid, and a from_start flag.

/autonomy/network_goto

  Action Type: clearpath_navigation_msgs/action/ExecuteNetworkGoTo

  Description: Send the UGV to a location within the network.

/undock

  Action Type: clearpath_dock_msgs/action/Dock

  Description: Undock the robot to the charging dock, if the docking package has been included.