Definitions
Message Definitions
clearpath_control_msgs/ControlMode.msg
# Control mode message
int8 NEUTRAL=0
int8 MANUAL=1
int8 AUTONOMY=2
int8 mode
clearpath_control_msgs/ControlSelectionState.msg
# The complete state of the control selection module. This message includes the autonomy state as well as the navigation mode.
ControlState autonomy
ControlMode mode
clearpath_control_msgs/ControlState.msg
# The autonomy state message, The autonomy can be either enabled/disabled and active/paused.
bool enabled
bool paused
clearpath_dock_msgs/DockInfo.msg
# Message definition containing the information of a single dock. This includes identifiers, lat/lon and orientation of the location of a dock.
string name
string uuid
string frame
string target_template
# ISO 8601 date/time format of last successfull dock location setting
string last_location_set_time
# maximum allowable distance to allow for predocking. (ie. the distance within which the dock waypoint must be located)
float32 max_predock_distance
# the distance from the dock that the robot will navigate to prior to start docking
float32 predock_distance
# location of the dock
float64 latitude
float64 longitude
float64 heading
clearpath_dock_msgs/DockProperties.msg
# Message definition containing the properties for each of the docks available.
clearpath_dock_msgs/DockInfo[] docks
clearpath_dock_msgs/DockState.msg
# Message definition containing information on what state the docking process is in.
uint8 UNDOCKED = 0
uint8 DOCKED = 1
uint8 IN_PROGRESS = 2
uint8 FAILED = 3
uint8 CANCELLED = 4
uint8 state
clearpath_dock_msgs/TargetTrackerState.msg
# Message definition containing the state information of the target tracker.
# This includes whether or not the tracker is active, whether the target is visible/lost, and the target pose and score of that pose.
bool active
# flag indicates if the target is visible or not
bool target_locked
geometry_msgs/PoseWithCovarianceStamped target_pose
float32 score
# the distance of the sensor_link to the dock target
float64 distance_to_target
clearpath_localization_msgs/LocalizationStatus.msg
# Localization status message for all sources of localization
std_msgs/Header header
float32 accuracy # IN DEVELOPMENT
# status information related to the GPS receiver units
GNSSStatus position_gnss
GNSSStatus heading_gnss
GNSSStatus base_station_gnss
bool dead_reckoning
clearpath_localization_msgs/GNSSStatus.msg
# GNSS receiver status message
uint8 POSITION_RECEIVER = 0
uint8 HEADING_RECEIVER = 1
uint8 BASE_STATION_RECEIVER = 2
uint8 receiver_type
uint8 POSITION_NO_FIX = 0
uint8 POSITION_SPP = 1
uint8 POSITION_SBAS = 2
uint8 POSITION_RTK_FLOAT = 3
uint8 POSITION_RTK_FIXED = 4
uint8 position_fix_type
uint8 HEADING_NOT_APPLICABLE = 0
uint8 HEADING_NO_SOLUTION = 1
uint8 HEADING_RTK_FLOAT = 2
uint8 HEADING_RTK_FIXED = 3
uint8 heading_fix_type
uint8 num_connected_sats # Number of satellites connected to the antenna/receiver
uint8 num_sats_solution # Number of sats used in solution
float32[] cn0 # The carrier-to-noise ratio of each connected satellite
float64 correction_age # Age of RTK corrections. -1 indicates none received
clearpath_mission_manager_msgs/msg/NetworkEdgeReq.msg
string start_point_id
string end_point_id
float32 speed_limit
float32 radius
clearpath_mission_manager_msgs/msg/NetworkMapState.msg
# The UUID of the map
string uuid
# True if the map actually exists and was found
bool exists
# The number of disconnected sub-graphs of the map
# Normally this will be 1 (i.e. the map is a single graph that is connected)
# but there are circumstances where the user may intentionally want 2+ disconnected graphs
# (e.g. a separate graph for each side of a fence, where the only connection between the two
# sides is an out-of-bounds, teleop-only road)
int32 num_subgraphs
# If the map has any disconnected vertices, we enumerate them here by their ID
# If size_exceeded is true, this list may be empty or incomplete (see below)
string[] disconnected_point_ids
# True if the map is too big for the validation to run on it
# Maps with more than 1000 vertices or 8000 edges will not be fully tests
bool size_exceeded
clearpath_mission_manager_msgs/msg/NetworkMapValidityState.msg
# Reports the validity of all network of paths maps registered with the mission manager
clearpath_mission_manager_msgs/NetworkMapState[] map_states
clearpath_mission_manager_msgs/msg/StorageState.msg
# The entire contents of the Mission database
# Note that all of the following cases are valid:
# - a Task can be referenced in multiple Waypoints
# - a Waypoint can be referenced in multiple Missions
# - a Waypoint can be orphaned (i.e. not included in any Missions)
# - a Task can be orphaned (i.e. not included in any Waypoints)
# All missions defined in the database
clearpath_navigation_msgs/Mission[] missions
# All waypoints defined in the database
clearpath_navigation_msgs/Waypoint[] waypoints
# All tasks defined in the database
clearpath_navigation_msgs/Task[] tasks
# All network of paths missions in the database
clearpath_navigation_msgs/NetworkMission[] network_missions
# All network of paths maps in the database
clearpath_navigation_msgs/NetworkMap[] network_maps
clearpath_mission_scheduler_msgs/msg/NextSchedule.msg
# The ID of the next schedule to start
# Empty if nothing is scheduled
string uuid
# The time until the schedule starts (rounded to the nearest second)
duration time_to_start
clearpath_mission_scheduler_msgs/msg/Schedule.msg
# Single-execution mode; the schedule starts at the designated time and runs once
uint8 MODE_ONCE=0
# Looping mode; the schedule starts at the designated time, and every loop_interval seconds after
# for the designated number of repeats
uint8 MODE_LOOP=1
# Single-shot execution, but does NOT get added to the persistent storage
# Equivalent to MODE_ONCE, but for one-off, throw-away schedules (e.g. "Run X in 5 minutes")
uint8 MODE_TRANSIENT=2
# The human-readable name for this schedule
# Should be unique, but there's no hard requirement for it to be so
string name
# The unique ID of this schedule
# A string of the form "12345678-90ab-cdef-1234-567890abcdef"
string uuid
# The time that this mission starts every day
clearpath_mission_scheduler_msgs/UtcTime start_time
# Either MODE_ONCE or MODE_LOOP to indicate the execution mode
uint8 mode
# In MODE_LOOP, how many times do we repeat the missions?
uint8 loop_repeats
# In MODE_LOOP, how long do we wait between executions?
duration loop_interval
# The ordered list of Mission UUIDs to execute
string[] mission_ids
# The minimum battery charge needed before we execute the missions
# Must be in the range 0-1
float32 min_battery
# If the missions take longer than this to execute, assume the schedule has failed and alert the user
# Set to zero to disable the timeout
duration timeout
# Is this schedule enabled?
# Only enabled schedules will execute
bool enabled
clearpath_mission_scheduler_msgs/msg/StorageState.msg
# Single-execution mode; the schedule starts at the designated time and runs once
uint8 MODE_ONCE=0
# Looping mode; the schedule starts at the designated time, and every loop_interval seconds after
# for the designated number of repeats
uint8 MODE_LOOP=1
# Single-shot execution, but does NOT get added to the persistent storage
# Equivalent to MODE_ONCE, but for one-off, throw-away schedules (e.g. "Run X in 5 minutes")
uint8 MODE_TRANSIENT=2
# The human-readable name for this schedule
# Should be unique, but there's no hard requirement for it to be so
string name
# The unique ID of this schedule
# A string of the form "12345678-90ab-cdef-1234-567890abcdef"
string uuid
# The time that this mission starts every day
clearpath_mission_scheduler_msgs/UtcTime start_time
# Either MODE_ONCE or MODE_LOOP to indicate the execution mode
uint8 mode
# In MODE_LOOP, how many times do we repeat the missions?
uint8 loop_repeats
# In MODE_LOOP, how long do we wait between executions?
duration loop_interval
# The ordered list of Mission UUIDs to execute
string[] mission_ids
# The minimum battery charge needed before we execute the missions
# Must be in the range 0-1
float32 min_battery
# If the missions take longer than this to execute, assume the schedule has failed and alert the user
# Set to zero to disable the timeout
duration timeout
# Is this schedule enabled?
# Only enabled schedules will execute
bool enabled
clearpath_mission_scheduler_msgs/msg/UtcTime.msg
# Represents a moment in time on a 24-hour clock
# The hour, 0-23
uint8 hour
# The minute, 0-59
uint8 minute
# The second, 0-59
uint8 second
# Milliseconds, 0-999 (not typically needed)
uint16 millisecond
clearpath_navigation_msgs/Mission.msg
# Message definition for an OutdoorNav mission
std_msgs/Header header
# The human-readable name of this mission
string name
# A UUID string used to uniquely identify this mission
string uuid
# The ordered list of Waypoints that make up the mission
clearpath_navigation_msgs/Waypoint[] waypoints
# Configuration parameters for the mission
# Additional details TBD
string onav_config
clearpath_navigation_msgs/DistanceToGoal.msg
# Message includes Euclidean and Path distance to goal
float32 euclidean
float32 path
clearpath_navigation_msgs/Metrics.msg
# Message containing some metric information related to the autonomy metrics.
float64 total_distance_travelled # [m]
float64 total_duration # [s]
uint64 num_missions_sent
uint64 num_missions_completed
uint64 num_replans
uint64 num_recoveries
uint64 num_tasks_executed
clearpath_navigation_msgs/MotionState.msg
# Motion state message to indicate the current motion, expected motion and the direction of travel of the robot.
# State pertaining to current motion of the robot.
uint8 MOTION_NORMAL=10
uint8 MOTION_STOPPED=11
uint8 MOTION_REVERSE=12
uint8 MOTION_SLOWING=13 # Currently unused
uint8 motion
# State pertaining to the robot's movement along the path. Predictive, ie state
# will be INDICATOR_LEFT_TURN if in or approaching a left turn.
uint8 INDICATOR_NORMAL=20
uint8 INDICATOR_LEFT_TURN=21
uint8 INDICATOR_RIGHT_TURN=22
uint8 INDICATOR_CLOCKWISE=23
uint8 INDICATOR_COUNTERCLOCKWISE=24
uint8 INDICATOR_HAZARD=25 # Currently unused
uint8 indicator
# Direction of travel of the robot relative to its physical forward direction.
uint8 DIRECTION_FORWARD=30
uint8 DIRECTION_REVERSE=31
uint8 direction
clearpath_navigation_msgs/NavigationState.msg
# Message containing the current navigation state(s). Navigation may be in multiple states.
uint8 STATE_IDLE = 0
uint8 STATE_COMPUTE_PATH = 1
uint8 STATE_EXECUTE_PATH = 2
uint8 STATE_REPLAN = 3
uint8 STATE_NAVIGATING_AROUND_OBSTACLE = 4
uint8 STATE_RECOVERY = 5
uint8 STATE_LOST = 6
uint8 STATE_DONE = 7
uint8 STATE_SAFETY_STOP = 8
uint8 STATE_PAUSE = 9
uint8 STATE_DISABLE = 10
uint8[] states
clearpath_navigation_msgs/OdomIntent.msg
# Message containing current and predicted odom related information
std_msgs/Header header
# Current and predicted odom
perception_navigation_msgs/Odom2DLean odom
perception_navigation_msgs/Odom2DLean predicted_odom
# Time offset corresponding to prediction
float32 dt
clearpath_navigation_msgs/PointVector.msg
# Vector of point vectors (for GUI)
std_msgs/Header header
clearpath_navigation_msgs/Vector2D[] cloud
clearpath_navigation_msgs/Progress.msg (BETA)
# Message containing the completion percentage of the currently executed path and the current goal.
float32 path_progress
float32 goal_progress
float32 mission_progress
clearpath_navigation_msgs/ScanPoints.msg
# Message definition for the detection points used by the navigation that relate to the detected obstacles.
std_msgs/Header header
string[] frames_vector
clearpath_navigation_msgs/PointVector[] cloud_vector
clearpath_navigation_msgs/Task.msg
# A single task that can be executed at a Waypoint
# The human-readable name of this task
string name
# A UUID string to uniquely identify this Task
string uuid
# The ROS action that this task executes
string action_server_name
# The version of this task
string version
# Numerical/boolean data to be passed to the action_server_name
# The exact meaning of these values is dependent on the underlying service
float64[] floats
# String data to be passed to the action_server_name
# The exact meaning of these values is dependent on the underlying service
string[] strings
# Boolean value which determines whether a mission using this task can continue
# if this task fails to execute
bool allow_failure
clearpath_navigation_msgs/TrackError.msg
# The path error message containing the off-path cross track error and the relative heading error to the path direction
std_msgs/Header header
float32 cross_track_error
float32 heading_error
clearpath_navigation_msgs/Vector2D.msg
# 2D Vector of floats (used for GUI)
float32[2] point
clearpath_navigation_msgs/Waypoints.msg
# A single Waypoint along a Mission
# A UUID string to uniquely identify this Waypoint
string uuid
# The human-readable name of this Waypoint
string name
# The latitude (in degrees) of this Waypoint
float64 latitude
# The longitude (in degrees) of this Waypoint
float64 longitude
# The compass heading (in degrees) of this Waypoint
float64 heading
# A radius in meters indicating the acceptable radius from the target location
# Posititon tolerance is disabled if this value is negative
float64 position_tolerance
# A tolerance in degrees indicating the acceptable deviation from the heading
# Heading tolerance is disabled if this value is negative
float64 yaw_tolerance
# The ordered set of Tasks to execute once the goal position & orientation are reached
clearpath_navigation_msgs/Task[] tasks
clearpath_platform_msgs/PlatformID.msg
# Platform ID message containing the model, serial #, hardware and firmware versions
string model
string serial_id
string hardware_revision
string firmware_revision
clearpath_safety_msgs/Safety.msg
# Safety monitor message telling us if the safety monitor has been triggered and a message
# indicating what caused the trigger
uint8 SAFETY_ESTOP = 0
uint8 SAFETY_SENSOR_TIMEOUT = 1
bool safety_monitor_triggered
uint8 trigger_type
string message
clearpath_safety_msgs/AssistedTeleopState.msg
# Assisted teleoperation message indicating the current state of the protection
uint8 STATE_ACTIVE = 0
uint8 STATE_DISABLED = 1
uint8 STATE_COLLISION_IMMINENT = 2
uint8 STATE_STOPPED = 3
uint8 STATE_COLLISION = 4
uint8 STATE_ERROR = 5
uint8 state
uint8 ASSIST_ON = 100
uint8 ASSIST_OFF_SERVICE = 101
uint8 ASSIST_OFF_JOYSTICK_OVERRIDE = 102
uint8 ASSIST_OFF_SENSOR_TIMEOUT = 103
uint8 assist_off_trigger
string error_message
clearpath_safety_msgs/ObstacleMap.msg
# Assisted teleoperation message indicating the threat level of obstacles surrounding the platform
float32[] threat_level
clearpath_safety_msgs/WatchdogStatus.msg
# Watchdog status message containing information related to sensor monitoring, emergency stop and safety stops
bool[] gps_watchdog_triggered
bool[] lidar_watchdog_triggered
bool[] camera_watchdog_triggered
Standard ROS Messages
- actionlib_msgs/GoalID
- diagnostic_msgs/DiagnosticArray
- geometry_msgs/PolygonStamped
- geometry_msgs/Polygon
- geometry_msgs/PoseArray
- geometry_msgs/Twist
- nav_msgs/OccupancyGrid
- nav_msgs/Odometry
- nav_msgs/Path
- sensor_msgs/Imu
- sensor_msgs/LaserScan
- sensor_msgs/NavSatFix
- sensor_msgs/PointCloud2
- std_msgs/Bool
- std_msgs/Empty
- std_msgs/String
- tf2_msgs/TFMessage
- wireless_msgs/Connection
Service Definitions
clearpath_control_msgs/srv/SetControlMode.srv
# Service definition to set the control mode
clearpath_control_msgs/ControlMode mode
---
clearpath_dock_msgs/srv/AddDock.srv
# A dock information message that will be added to the docks list
clearpath_dock_msgs/DockInfo dock
---
# True if the location was updated/added successfully, otherwise False
bool success