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.
/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.
/navigation/cmd_vel
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.
/navigation/distance_to_goal
Message Type: clearpath_navigation_msgs/DistanceToGoal
Description: The current Euclidean distance and the path distance, in meters, from the robot to its current goal.
/navigation/footprint
Message Type: geometry_msgs/Polygon
Description: The footprint of the robot.
/navigation/global_costmap
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.
/navigation/local_costmap
Message Type: nav_msgs/OccupancyGrid
Description: An occupancy grid consisting of the Free, Occupied or Unknown space that the robot uses to detect obstacles.
/navigation/local_plan
Message Type: nav_msgs/msg/Path
Description: The MPC local plan that the navigation uses to control the robot along the reference path.
/navigation/metrics
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.
/navigation/motion_state
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.
/navigation/odom_intent (IN DEVELOPMENT)
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.
/navigation/path
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.
/navigation/progress (BETA)
Message Type: clearpath_navigation_msgs/Progress
Description: The completion percentage of the current path, the current goal and the current mission.
/navigation/safety_footprints
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.
/navigation/scan_points (IN DEVELOPMENT)
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.
/navigation/state (BETA)
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.
/navigation/track_error
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).
/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.