UAVCAN v0 Specification 7.List of standard data types

Contents

List of standard data types

  • uavcan
    • CoarseOrientation
    • Timestamp
  • uavcan.equipment.actuator
    • ArrayCommand
    • Status
    • Command
  • uavcan.equipment.ahrs
    • Solution
    • MagneticFieldStrength
    • MagneticFieldStrength2
    • RawIMU
  • uavcan.equipment.air_data
    • TrueAirspeed
    • IndicatedAirspeed
    • AngleOfAttack
    • Sideslip
    • RawAirData
    • StaticPressure
    • StaticTemperature
  • uavcan.equipment.camera_gimbal
    • AngularCommand
    • GEOPOICommand
    • Status
    • Mode
  • uavcan.equipment.device
    • Temperature
  • uavcan.equipment.esc
    • RawCommand
    • RPMCommand
    • Status
  • uavcan.equipment.gnss
    • Fix
    • Auxiliary
    • RTCMStream
    • Fix2
    • ECEFPositionVelocity
  • uavcan.equipment.hardpoint
    • Command
    • Status
  • uavcan.equipment.ice
    • FuelTankStatus
  • uavcan.equipment.ice.reciprocating
    • Status
    • CylinderStatus
  • uavcan.equipment.indication
    • BeepCommand
    • LightsCommand
    • RGB565
    • SingleLightCommand
  • uavcan.equipment.power
    • PrimaryPowerSupplyStatus
    • CircuitStatus
    • BatteryInfo
  • uavcan.equipment.range_sensor
    • Measurement
  • uavcan.equipment.safety
    • ArmingStatus
  • uavcan.navigation
    • GlobalNavigationSolution
  • uavcan.protocol
    • GetNodeInfo
    • GetDataTypeInfo
    • NodeStatus
    • GetTransportStats
    • GlobalTimeSync
    • Panic
    • RestartNode
    • AccessCommandShell
    • CANIfaceStats
    • DataTypeKind
    • HardwareVersion
    • SoftwareVersion
  • uavcan.protocol.debug
    • KeyValue
    • LogMessage
    • LogLevel
  • uavcan.protocol.dynamic_node_id
    • Allocation
  • uavcan.protocol.dynamic_node_id.server
    • AppendEntries
    • RequestVote
    • Discovery
    • Entry
  • uavcan.protocol.enumeration
    • Begin
    • Indication
  • uavcan.protocol.file
    • BeginFirmwareUpdate
    • GetInfo
    • GetDirectoryEntryInfo
    • Delete
    • Read
    • Write
    • EntryType
    • Error
    • Path
  • uavcan.protocol.param
    • ExecuteOpcode
    • GetSet
    • Empty
    • NumericValue
    • Value

List of standard data types (标准数据类型列表)

This section lists all standard data types. Link to the repository that contains the sources of all DSDL definitions can be found on the contacts page.
本节列出了所有标准数据类型。可以在 DSDL 仓库里找到源码。

Autogenerated Thu, 09 Jan 2020 15:10:17 +0000.

uavcan

CoarseOrientation
Full name: uavcan.CoarseOrientation

  1. #
  2. # Nested type.
  3. # Coarse, low-resolution 3D orientation represented as fixed axes in 16 bit.
  4. #
  5. # Roll, pitch, yaw angles in radians should be multiplied by
  6. # ANGLE_MULTIPLIER in order to convert them to the coarse representation.
  7. #
  8. # ANGLE_MULTIPLIER = NORM / PI
  9. #
  10. # Where NORM is 12, because it:
  11. # - Fits the maximum range of a signed 5 bit integer
  12. # - Allows to exactly represent the following angles:
  13. # 0, 15, 30, 45, 60, 75, 90, 105, 120, 135, 150, 165, 180, and negatives
  14. #
  15. float32 ANGLE_MULTIPLIER = 4.7746482927568605
  16. int5[3] fixed_axis_roll_pitch_yaw
  17. bool orientation_defined # False if the orientation is actually not defined

Timestamp
Full name: uavcan.Timestamp

  1. #
  2. # Global timestamp in microseconds, 7 bytes.
  3. #
  4. # Use this data type for timestamp fields in messages, like follows:
  5. # uavcan.Timestamp timestamp
  6. #
  7. uint56 UNKNOWN = 0
  8. truncated uint56 usec # Microseconds

uavcan.equipment.actuator

ArrayCommand
Full name: uavcan.equipment.actuator.ArrayCommand
Default data type ID: 1010

  1. #
  2. # Actuator commands.
  3. # The system supports up to 256 actuators; up to 15 of them can be commanded with one message.
  4. #
  5. Command[<=15] commands

Status
Full name: uavcan.equipment.actuator.Status
Default data type ID: 1011

  1. #
  2. # Generic actuator feedback, if available.
  3. # Unknown fields should be set to NAN.
  4. #
  5. uint8 actuator_id
  6. #
  7. # Whether the units are linear or angular depends on the actuator type (refer to the Command data type).
  8. #
  9. float16 position # meter or radian
  10. float16 force # Newton or Newton metre
  11. float16 speed # meter per second or radian per second
  12. void1
  13. uint7 POWER_RATING_PCT_UNKNOWN = 127
  14. uint7 power_rating_pct # 0 - unloaded, 100 - full load

Command
Full name: uavcan.equipment.actuator.Command

  1. #
  2. # Nested type.
  3. # Single actuator command.
  4. #
  5. uint8 actuator_id
  6. #
  7. # Whether the units are linear or angular depends on the actuator type.
  8. #
  9. uint8 COMMAND_TYPE_UNITLESS = 0 # [-1, 1]
  10. uint8 COMMAND_TYPE_POSITION = 1 # meter or radian
  11. uint8 COMMAND_TYPE_FORCE = 2 # Newton or Newton metre
  12. uint8 COMMAND_TYPE_SPEED = 3 # meter per second or radian per second
  13. uint8 command_type
  14. #
  15. # Value of the above type
  16. #
  17. float16 command_value

uavcan.equipment.ahrs

Solution
Full name: uavcan.equipment.ahrs.Solution
Default data type ID: 1000

  1. #
  2. # Inertial data and orientation in body frame.
  3. #
  4. uavcan.Timestamp timestamp
  5. #
  6. # Normalized quaternion
  7. #
  8. float16[4] orientation_xyzw
  9. void4
  10. float16[<=9] orientation_covariance
  11. #
  12. # rad/sec
  13. #
  14. float16[3] angular_velocity
  15. void4
  16. float16[<=9] angular_velocity_covariance
  17. #
  18. # m/s^2
  19. #
  20. float16[3] linear_acceleration
  21. float16[<=9] linear_acceleration_covariance

MagneticFieldStrength
Full name: uavcan.equipment.ahrs.MagneticFieldStrength
Default data type ID: 1001

  1. #
  2. # Magnetic field readings, in Gauss, in body frame.
  3. # SI units are avoided because of float16 range limitations.
  4. # This message is deprecated. Use the newer 1002.MagneticFieldStrength2.uavcan message.
  5. #
  6. float16[3] magnetic_field_ga
  7. float16[<=9] magnetic_field_covariance

MagneticFieldStrength2
Full name: uavcan.equipment.ahrs.MagneticFieldStrength2
Default data type ID: 1002

  1. #
  2. # Magnetic field readings, in Gauss, in body frame.
  3. # SI units are avoided because of float16 range limitations.
  4. #
  5. uint8 sensor_id
  6. float16[3] magnetic_field_ga
  7. float16[<=9] magnetic_field_covariance

RawIMU
Full name: uavcan.equipment.ahrs.RawIMU
Default data type ID: 1003

  1. #
  2. # Raw IMU data with timestamps.
  3. #
  4. # THIS DEFINITION MAY BE CHANGED IN A NON-BACKWARD-COMPATIBLE WAY IN THE FUTURE.
  5. #
  6. #
  7. # Data acquisition timestamp in the bus shared time base.
  8. #
  9. uavcan.Timestamp timestamp
  10. #
  11. # Integration interval, seconds.
  12. # Set to a non-positive value if the integrated samples are not available
  13. # (in this case, only the latest point samples will be valid).
  14. #
  15. float32 integration_interval
  16. #
  17. # Angular velocity samples in radian/second.
  18. # The samples are represented in the body frame, the axes are ordered as follows:
  19. # 1. angular velocity around X (roll rate)
  20. # 2. angular velocity around Y (pitch rate)
  21. # 3. angular velocity around Z (yaw rate)
  22. #
  23. float16[3] rate_gyro_latest # Latest sample, radian/second
  24. float32[3] rate_gyro_integral # Integrated samples, radian/second
  25. #
  26. # Linear acceleration samples in meter/(second^2).
  27. # The samples are represented in the body frame, the axes are ordered as follows:
  28. # 1. linear acceleration along X (forward positive)
  29. # 2. linear acceleration along Y (right positive)
  30. # 3. linear acceleration along Z (down positive)
  31. #
  32. float16[3] accelerometer_latest # Latest sample, meter/(second^2)
  33. float32[3] accelerometer_integral # Integrated samples, meter/(second^2)
  34. #
  35. # Covariance matrix. The diagonal entries are ordered as follows:
  36. # 1. roll rate (radian^2)/(second^2)
  37. # 2. pitch rate (radian^2)/(second^2)
  38. # 3. yaw rate (radian^2)/(second^2)
  39. # 4. forward acceleration (meter^2)/(second^4)
  40. # 5. rightward acceleration (meter^2)/(second^4)
  41. # 6. downward acceleration (meter^2)/(second^4)
  42. #
  43. float16[<=36] covariance

uavcan.equipment.air_data

TrueAirspeed
Full name: uavcan.equipment.air_data.TrueAirspeed
Default data type ID: 1020

  1. #
  2. # TAS.
  3. #
  4. float16 true_airspeed # m/s
  5. float16 true_airspeed_variance # (m/s)^2

IndicatedAirspeed
Full name: uavcan.equipment.air_data.IndicatedAirspeed
Default data type ID: 1021

  1. #
  2. # IAS.
  3. #
  4. float16 indicated_airspeed # m/s
  5. float16 indicated_airspeed_variance # (m/s)^2

AngleOfAttack
Full name: uavcan.equipment.air_data.AngleOfAttack
Default data type ID: 1025

  1. #
  2. # Angle of attack.
  3. #
  4. uint8 SENSOR_ID_LEFT = 254
  5. uint8 SENSOR_ID_RIGHT = 255
  6. uint8 sensor_id
  7. float16 aoa # Radians
  8. float16 aoa_variance # Radians^2

Sideslip
Full name: uavcan.equipment.air_data.Sideslip
Default data type ID: 1026

  1. #
  2. # Body sideslip in radians.
  3. #
  4. float16 sideslip_angle # Radians
  5. float16 sideslip_angle_variance # Radians^2

RawAirData
Full name: uavcan.equipment.air_data.RawAirData
Default data type ID: 1027

  1. #
  2. # Raw Air Data.
  3. #
  4. # Note: unused vars should be assigned NaN
  5. #
  6. # Heater State
  7. #
  8. uint8 FLAG_HEATER_AVAILABLE = 1
  9. uint8 FLAG_HEATER_WORKING = 2
  10. uint8 FLAG_HEATER_OVERCURRENT = 4
  11. uint8 FLAG_HEATER_OPENCIRCUIT = 8
  12. uint8 flags
  13. #
  14. # Pressure Data
  15. #
  16. float32 static_pressure # Pascal
  17. float32 differential_pressure # Pascal
  18. #
  19. # Temperature Data
  20. #
  21. float16 static_pressure_sensor_temperature # Kelvin
  22. float16 differential_pressure_sensor_temperature # Kelvin
  23. float16 static_air_temperature # Kelvin
  24. # This field contains the raw temperature reading
  25. # from the externally mounted temperature sensor or,
  26. # in absence of one, the raw temperature of the pressure sensor.
  27. float16 pitot_temperature # Kelvin
  28. float16[<=16] covariance # order of diagonal elements :
  29. # static_pressure, differential_pressure,
  30. # static_air_temperature, pitot_temperature
  31. # Pascal^2 for pressure variance and covariance
  32. # Kevin^2 for Temperature variance and covariance
  33. # Pascal*Kelvin for pressure/temperature covariance

StaticPressure
Full name: uavcan.equipment.air_data.StaticPressure
Default data type ID: 1028

  1. #
  2. # Static pressure.
  3. #
  4. float32 static_pressure # Pascal
  5. float16 static_pressure_variance # Pascal^2

StaticTemperature
Full name: uavcan.equipment.air_data.StaticTemperature
Default data type ID: 1029

  1. #
  2. # Static temperature.
  3. #
  4. float16 static_temperature # Kelvin
  5. float16 static_temperature_variance # Kelvin^2

uavcan.equipment.camera_gimbal

AngularCommand Full name: uavcan.equipment.camera_gimbal.AngularCommand
Default data type ID: 1040

  1. #
  2. # Generic camera gimbal control.
  3. #
  4. # This message can only be used in the following modes:
  5. # - COMMAND_MODE_ANGULAR_VELOCITY
  6. # - COMMAND_MODE_ORIENTATION_FIXED_FRAME
  7. # - COMMAND_MODE_ORIENTATION_BODY_FRAME
  8. #
  9. uint8 gimbal_id
  10. #
  11. # Target operation mode - how to handle this message.
  12. # See the list of acceptable modes above.
  13. #
  14. Mode mode
  15. #
  16. # In the angular velocity mode, this field contains a rate quaternion.
  17. # In the orientation mode, this field contains orientation either in fixed frame or in body frame.
  18. #
  19. float16[4] quaternion_xyzw

GEOPOICommand
Full name: uavcan.equipment.camera_gimbal.GEOPOICommand
Default data type ID: 1041

  1. #
  2. # Generic camera gimbal control.
  3. #
  4. # This message can only be used in the following modes:
  5. # - COMMAND_MODE_GEO_POI
  6. #
  7. uint8 gimbal_id
  8. #
  9. # Target operation mode - how to handle this message.
  10. # See the list of acceptable modes above.
  11. #
  12. Mode mode
  13. #
  14. # Coordinates of the POI (point of interest).
  15. #
  16. int32 longitude_deg_1e7 # 1 LSB = 1e-7 deg
  17. int32 latitude_deg_1e7
  18. int22 height_cm # 1 LSB = 10 mm
  19. uint2 HEIGHT_REFERENCE_ELLIPSOID = 0
  20. uint2 HEIGHT_REFERENCE_MEAN_SEA_LEVEL = 1
  21. uint2 height_reference

Status
Full name: uavcan.equipment.camera_gimbal.Status
Default data type ID: 1044

  1. #
  2. # Generic gimbal status.
  3. #
  4. uint8 gimbal_id
  5. Mode mode
  6. #
  7. # Camera axis orientation in body frame (not in fixed frame).
  8. # Please refer to the UAVCAN coordinate frame conventions.
  9. #
  10. float16[4] camera_orientation_in_body_frame_xyzw
  11. float16[<=9] camera_orientation_in_body_frame_covariance # +inf for non-existent axes

Mode
Full name: uavcan.equipment.camera_gimbal.Mode

  1. #
  2. # Gimbal operating mode
  3. #
  4. uint8 COMMAND_MODE_ANGULAR_VELOCITY = 0
  5. uint8 COMMAND_MODE_ORIENTATION_FIXED_FRAME = 1
  6. uint8 COMMAND_MODE_ORIENTATION_BODY_FRAME = 2
  7. uint8 COMMAND_MODE_GEO_POI = 3
  8. uint8 command_mode

uavcan.equipment.device

Temperature
Full name: uavcan.equipment.device.Temperature
Default data type ID: 1110

  1. #
  2. # Generic device temperature
  3. #
  4. uint16 device_id
  5. float16 temperature # in kelvin
  6. uint8 ERROR_FLAG_OVERHEATING = 1
  7. uint8 ERROR_FLAG_OVERCOOLING = 2
  8. uint8 error_flags

uavcan.equipment.esc

RawCommand
Full name: uavcan.equipment.esc.RawCommand
Default data type ID: 1030

  1. #
  2. # Raw ESC command normalized into [-8192, 8191]; negative values indicate reverse rotation.
  3. # The ESC should normalize the setpoint into its effective input range.
  4. # Non-zero setpoint value below minimum should be interpreted as min valid setpoint for the given motor.
  5. #
  6. int14[<=20] cmd

RPMCommand
Full name: uavcan.equipment.esc.RPMCommand
Default data type ID: 1031

  1. #
  2. # Simple RPM setpoint.
  3. # The ESC should automatically clamp the setpoint according to the minimum and maximum supported RPM;
  4. # for example, given a ESC that operates in the range 100 to 10000 RPM, a setpoint of 1 RPM will be clamped to 100 RPM.
  5. # Negative values indicate reverse rotation.
  6. #
  7. int18[<=20] rpm

Status
Full name: uavcan.equipment.esc.Status
Default data type ID: 1034

  1. #
  2. # Generic ESC status.
  3. # Unknown fields should be set to NAN.
  4. #
  5. uint32 error_count # Resets when the motor restarts
  6. float16 voltage # Volt
  7. float16 current # Ampere. Can be negative in case of a regenerative braking.
  8. float16 temperature # Kelvin
  9. int18 rpm # Negative value indicates reverse rotation
  10. uint7 power_rating_pct # Instant demand factor in percent (percent of maximum power); range 0% to 127%.
  11. uint5 esc_index

uavcan.equipment.gnss

Fix
Full name: uavcan.equipment.gnss.Fix
Default data type ID: 1060

  1. #
  2. # GNSS navigation solution with uncertainty.
  3. # This message is deprecated. Use the newer 1063.Fix2.uavcan message.
  4. #
  5. uavcan.Timestamp timestamp # Global network-synchronized time, if available, otherwise zero
  6. #
  7. # Time solution.
  8. # Time standard (GPS, UTC, TAI, etc) is defined in the field below.
  9. #
  10. uavcan.Timestamp gnss_timestamp
  11. #
  12. # Time standard used in the GNSS timestamp field.
  13. #
  14. uint3 GNSS_TIME_STANDARD_NONE = 0 # Time is unknown
  15. uint3 GNSS_TIME_STANDARD_TAI = 1
  16. uint3 GNSS_TIME_STANDARD_UTC = 2
  17. uint3 GNSS_TIME_STANDARD_GPS = 3
  18. uint3 gnss_time_standard
  19. void5 # Reserved space
  20. #
  21. # If known, the number of leap seconds allows to perform conversions between some time standards.
  22. #
  23. uint8 NUM_LEAP_SECONDS_UNKNOWN = 0
  24. uint8 num_leap_seconds
  25. #
  26. # Position and velocity solution
  27. #
  28. int37 longitude_deg_1e8 # Longitude degrees multiplied by 1e8 (approx. 1 mm per LSB)
  29. int37 latitude_deg_1e8 # Latitude degrees multiplied by 1e8 (approx. 1 mm per LSB on equator)
  30. int27 height_ellipsoid_mm # Height above ellipsoid in millimeters
  31. int27 height_msl_mm # Height above mean sea level in millimeters
  32. float16[3] ned_velocity # NED frame (north-east-down) in meters per second
  33. #
  34. # Fix status
  35. #
  36. uint6 sats_used
  37. uint2 STATUS_NO_FIX = 0
  38. uint2 STATUS_TIME_ONLY = 1
  39. uint2 STATUS_2D_FIX = 2
  40. uint2 STATUS_3D_FIX = 3
  41. uint2 status
  42. #
  43. # Precision
  44. #
  45. float16 pdop
  46. void4
  47. float16[<=9] position_covariance # m^2
  48. float16[<=9] velocity_covariance # (m/s)^2

Auxiliary
Full name: uavcan.equipment.gnss.Auxiliary
Default data type ID: 1061

  1. #
  2. # GNSS low priority auxiliary info.
  3. # Unknown DOP parameters should be set to NAN.
  4. #
  5. float16 gdop
  6. float16 pdop
  7. float16 hdop
  8. float16 vdop
  9. float16 tdop
  10. float16 ndop
  11. float16 edop
  12. uint7 sats_visible # All visible sats of all available GNSS (e.g. GPS, GLONASS, etc)
  13. uint6 sats_used # All used sats of all available GNSS

RTCMStream
Full name: uavcan.equipment.gnss.RTCMStream
Default data type ID: 1062

  1. #
  2. # GNSS RTCM SC-104 protocol raw stream container.
  3. # RTCM messages that are longer than max data size can be split over multiple consecutive messages.
  4. #
  5. uint8 PROTOCOL_ID_UNKNOWN = 0
  6. uint8 PROTOCOL_ID_RTCM2 = 2
  7. uint8 PROTOCOL_ID_RTCM3 = 3
  8. uint8 protocol_id
  9. uint8[<=128] data

Fix2
Full name: uavcan.equipment.gnss.Fix2
Default data type ID: 1063

  1. #
  2. # GNSS ECEF and LLA navigation solution with uncertainty.
  3. #
  4. #
  5. # Global network-synchronized time, if available, otherwise zero.
  6. #
  7. uavcan.Timestamp timestamp
  8. #
  9. # Time solution.
  10. # The method and number of leap seconds which were in use for deriving the timestamp are
  11. # defined in the fields below.
  12. #
  13. uavcan.Timestamp gnss_timestamp
  14. #
  15. # Method used for deriving the GNSS timestamp field.
  16. # This data type relies on the following definitions:
  17. #
  18. # Leap seconds - Accumulated one-second adjustments applied to UTC since 1972.
  19. # For reference, on May 2017, the number of leap seconds was equal 27.
  20. # The number of leap seconds is taken from the field num_leap_seconds.
  21. # Refer to https://en.wikipedia.org/wiki/Leap_second for a general overview.
  22. #
  23. # TAI timestamp - The number of microseconds between the current TAI time and
  24. # the TAI time at UTC 1970-01-01T00:00:00.
  25. #
  26. # UTC timestamp - The number of microseconds between the current UTC time and
  27. # UTC 1970-01-01T00:00:00.
  28. # UTC can be expressed via TAI as follows (in seconds):
  29. # UTC = TAI - num_leap_seconds - 10
  30. # And via GPS (in seconds):
  31. # UTC = GPS - num_leap_seconds + 9
  32. #
  33. # GPS timestamp - The number of microseconds between the current GPS time and
  34. # the GPS time at UTC 1970-01-01T00:00:00.
  35. # GPS time can be expressed via TAI as follows (in seconds):
  36. # GPS = TAI - 19
  37. #
  38. uint3 GNSS_TIME_STANDARD_NONE = 0 # Time is unknown
  39. uint3 GNSS_TIME_STANDARD_TAI = 1
  40. uint3 GNSS_TIME_STANDARD_UTC = 2
  41. uint3 GNSS_TIME_STANDARD_GPS = 3
  42. uint3 gnss_time_standard
  43. void13 # Reserved space
  44. #
  45. # Accumulated one-second adjustments applied to UTC since 1972.
  46. # The number must agree with the currently correct number of UTC leap seconds. If this cannot
  47. # be garanteed, the field must be set to NUM_LEAP_SECONDS_UNKNOWN.
  48. #
  49. uint8 NUM_LEAP_SECONDS_UNKNOWN = 0
  50. uint8 num_leap_seconds
  51. #
  52. # Position and velocity solution
  53. #
  54. int37 longitude_deg_1e8 # Longitude degrees multiplied by 1e8 (approx. 1 mm per LSB)
  55. int37 latitude_deg_1e8 # Latitude degrees multiplied by 1e8 (approx. 1 mm per LSB on equator)
  56. int27 height_ellipsoid_mm # Height above ellipsoid in millimeters
  57. int27 height_msl_mm # Height above mean sea level in millimeters
  58. float32[3] ned_velocity # NED frame (north-east-down) in meters per second
  59. #
  60. # Fix status
  61. #
  62. uint6 sats_used
  63. uint2 STATUS_NO_FIX = 0
  64. uint2 STATUS_TIME_ONLY = 1
  65. uint2 STATUS_2D_FIX = 2
  66. uint2 STATUS_3D_FIX = 3
  67. uint2 status
  68. #
  69. # GNSS Mode
  70. #
  71. uint4 MODE_SINGLE = 0
  72. uint4 MODE_DGPS = 1
  73. uint4 MODE_RTK = 2
  74. uint4 MODE_PPP = 3
  75. uint4 mode
  76. #
  77. # GNSS Sub mode
  78. #
  79. uint6 SUB_MODE_DGPS_OTHER = 0
  80. uint6 SUB_MODE_DGPS_SBAS = 1
  81. uint6 SUB_MODE_RTK_FLOAT = 0
  82. uint6 SUB_MODE_RTK_FIXED = 1
  83. uint6 sub_mode
  84. #
  85. # Precision
  86. #
  87. float16[<=36] covariance # Position and velocity covariance. Units are
  88. # m^2 for position, (m/s)^2 for velocity and
  89. # m^2/s for position/velocity.
  90. float16 pdop
  91. #
  92. # Position and velocity solution in ECEF, if available
  93. #
  94. ECEFPositionVelocity[<=1] ecef_position_velocity

ECEFPositionVelocity
Full name: uavcan.equipment.gnss.ECEFPositionVelocity

  1. #
  2. # Nested type.
  3. # GNSS ECEF high resolution position and velocity.
  4. #
  5. # ECEF is an acronym for Earth-Centered-Earth-Fixed, which is a cartesian
  6. # coordinate system which rotates with the earth. The origin (0,0,0) is
  7. # located at the center of the earth. The x-axis is a vector pointing from
  8. # the origin with positive direction towards 0 degrees latitude and
  9. # longitude (equator, at the prime meridian). The z-axis is a vector
  10. # pointing from the origin towards the north-pole. The y-axis completes a
  11. # right-handed coordinate system.
  12. #
  13. float32[3] velocity_xyz # XYZ velocity in m/s
  14. int36[3] position_xyz_mm # XYZ-axis coordinates in mm
  15. void6 # Aligns the following array at byte boundary
  16. float16[<=36] covariance # Position and velocity covariance in the ECEF frame. Units are m^2 for position,
  17. # (m/s)^2 for velocity, and m^2/s for position/velocity.

uavcan.equipment.hardpoint

Command
Full name: uavcan.equipment.hardpoint.Command
Default data type ID: 1070

  1. #
  2. # Generic cargo holder/hardpoint command.
  3. #
  4. uint8 hardpoint_id
  5. #
  6. # Either a binary command (0 - release, 1+ - hold) or bitmask
  7. #
  8. uint16 command

Status
Full name: uavcan.equipment.hardpoint.Status
Default data type ID: 1071

  1. #
  2. # Generic cargo holder/hardpoint status.
  3. #
  4. uint8 hardpoint_id
  5. float16 payload_weight # Newton
  6. float16 payload_weight_variance
  7. #
  8. # Meaning is the same as for the command field in the Command message
  9. #
  10. uint16 status

uavcan.equipment.ice

FuelTankStatus
Full name: uavcan.equipment.ice.FuelTankStatus
Default data type ID: 1129

  1. #
  2. # Generic fuel tank status message.
  3. # All fields are required unless stated otherwise. Unpopulated optional fields should be set to NaN.
  4. #
  5. #
  6. # Reserved for future use.
  7. #
  8. void9
  9. #
  10. # The estimated amount of fuel.
  11. # The reported values can be either measured directly using appropriate sensors,
  12. # or they can be estimated by fusing the data provided by various sensors.
  13. # For example, a Kalman filter can be used to fuse the data from fuel level sensors and flow sensors.
  14. # All fields are required.
  15. #
  16. uint7 available_fuel_volume_percent # Unit: percent, from 0% to 100%
  17. float32 available_fuel_volume_cm3 # Unit: centimeter^3
  18. #
  19. # Estimate of the current fuel consumption rate.
  20. # The flow can be negative if the fuel is being transferred between the tanks or during refueling.
  21. # This field is required.
  22. # Unit: (centimeter^3)/minute
  23. #
  24. float32 fuel_consumption_rate_cm3pm
  25. #
  26. # Fuel temperature.
  27. # This field is optional, set to NaN if not provided.
  28. # Unit: kelvin
  29. #
  30. float16 fuel_temperature
  31. #
  32. # The ID of the current fuel tank.
  33. #
  34. uint8 fuel_tank_id

uavcan.equipment.ice.reciprocating

Status
Full name: uavcan.equipment.ice.reciprocating.Status
Default data type ID: 1120

  1. #
  2. # Generic status message of a piston engine control system.
  3. #
  4. # All integer fields are required unless stated otherwise.
  5. # All floating point fields are optional unless stated otherwise; unknown/unapplicable fields should be set to NaN.
  6. #
  7. #
  8. # Abstract engine state. The flags defined below can provide further elaboration.
  9. # This is a required field.
  10. #
  11. uint2 state
  12. #
  13. # The engine is not running. This is the default state.
  14. # Next states: STARTING, FAULT
  15. #
  16. uint2 STATE_STOPPED = 0
  17. #
  18. # The engine is starting. This is a transient state.
  19. # Next states: STOPPED, RUNNING, FAULT
  20. #
  21. uint2 STATE_STARTING = 1
  22. #
  23. # The engine is running normally.
  24. # Some error flags may be set to indicate non-fatal issues, e.g. overheating.
  25. # Next states: STOPPED, FAULT
  26. #
  27. uint2 STATE_RUNNING = 2
  28. #
  29. # The engine can no longer function.
  30. # The error flags may contain additional information about the nature of the fault.
  31. # Next states: STOPPED.
  32. #
  33. uint2 STATE_FAULT = 3
  34. #
  35. # General status flags.
  36. # Note that not all flags are required. Those that aren't are prepended with a validity flag, which is, obviously,
  37. # always required; when the validity flag is set, it is assumed that the relevant flags are set correctly.
  38. # If the validity flag is cleared, then the state of the relevant flags should be ignored.
  39. # All unused bits must be cleared.
  40. #
  41. uint30 flags
  42. #
  43. # General error. This flag is required, and it can be used to indicate an error condition
  44. # that does not fit any of the other flags.
  45. # Note that the vendor may also report additional status information via the vendor specific status code
  46. # field of the NodeStatus message.
  47. #
  48. uint30 FLAG_GENERAL_ERROR = 1
  49. #
  50. # Error of the crankshaft sensor. This flag is optional.
  51. #
  52. uint30 FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED = 2
  53. uint30 FLAG_CRANKSHAFT_SENSOR_ERROR = 4
  54. #
  55. # Temperature levels. These flags are optional; either none of them or all of them are supported.
  56. #
  57. uint30 FLAG_TEMPERATURE_SUPPORTED = 8
  58. uint30 FLAG_TEMPERATURE_BELOW_NOMINAL = 16 # Under-temperature warning
  59. uint30 FLAG_TEMPERATURE_ABOVE_NOMINAL = 32 # Over-temperature warning
  60. uint30 FLAG_TEMPERATURE_OVERHEATING = 64 # Critical overheating
  61. uint30 FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL = 128 # Exhaust gas over-temperature warning
  62. #
  63. # Fuel pressure. These flags are optional; either none of them or all of them are supported.
  64. #
  65. uint30 FLAG_FUEL_PRESSURE_SUPPORTED = 256
  66. uint30 FLAG_FUEL_PRESSURE_BELOW_NOMINAL = 512 # Under-pressure warning
  67. uint30 FLAG_FUEL_PRESSURE_ABOVE_NOMINAL = 1024 # Over-pressure warning
  68. #
  69. # Detonation warning. This flag is optional.
  70. # This warning is cleared immediately after broadcasting is done if detonation is no longer happening.
  71. #
  72. uint30 FLAG_DETONATION_SUPPORTED = 2048
  73. uint30 FLAG_DETONATION_OBSERVED = 4096 # Detonation condition observed warning
  74. #
  75. # Misfire warning. This flag is optional.
  76. # This warning is cleared immediately after broadcasting is done if misfire is no longer happening.
  77. #
  78. uint30 FLAG_MISFIRE_SUPPORTED = 8192
  79. uint30 FLAG_MISFIRE_OBSERVED = 16384 # Misfire condition observed warning
  80. #
  81. # Oil pressure. These flags are optional; either none of them or all of them are supported.
  82. #
  83. uint30 FLAG_OIL_PRESSURE_SUPPORTED = 32768
  84. uint30 FLAG_OIL_PRESSURE_BELOW_NOMINAL = 65536 # Under-pressure warning
  85. uint30 FLAG_OIL_PRESSURE_ABOVE_NOMINAL = 131072 # Over-pressure warning
  86. #
  87. # Debris warning. This flag is optional.
  88. #
  89. uint30 FLAG_DEBRIS_SUPPORTED = 262144
  90. uint30 FLAG_DEBRIS_DETECTED = 524288 # Detection of debris warning
  91. #
  92. # Reserved space
  93. #
  94. void16
  95. #
  96. # Engine load estimate.
  97. # Unit: percent.
  98. # Range: [0, 127].
  99. #
  100. uint7 engine_load_percent
  101. #
  102. # Engine speed.
  103. # Unit: revolutions per minute.
  104. #
  105. uint17 engine_speed_rpm
  106. #
  107. # Spark dwell time.
  108. # Unit: millisecond.
  109. #
  110. float16 spark_dwell_time_ms
  111. #
  112. # Atmospheric (barometric) pressure.
  113. # Unit: kilopascal.
  114. #
  115. float16 atmospheric_pressure_kpa
  116. #
  117. # Engine intake manifold pressure.
  118. # Unit: kilopascal.
  119. #
  120. float16 intake_manifold_pressure_kpa
  121. #
  122. # Engine intake manifold temperature.
  123. # Unit: kelvin.
  124. #
  125. float16 intake_manifold_temperature
  126. #
  127. # Engine coolant temperature.
  128. # Unit: kelvin.
  129. #
  130. float16 coolant_temperature
  131. #
  132. # Oil pressure.
  133. # Unit: kilopascal.
  134. #
  135. float16 oil_pressure
  136. #
  137. # Oil temperature.
  138. # Unit: kelvin.
  139. #
  140. float16 oil_temperature
  141. #
  142. # Fuel pressure.
  143. # Unit: kilopascal.
  144. #
  145. float16 fuel_pressure
  146. #
  147. # Instant fuel consumption estimate.
  148. # The estimated value should be low-pass filtered in order to prevent aliasing effects.
  149. # Unit: (centimeter^3)/minute.
  150. #
  151. float32 fuel_consumption_rate_cm3pm
  152. #
  153. # Estimate of the consumed fuel since the start of the engine.
  154. # This variable MUST be reset when the engine is stopped.
  155. # Unit: centimeter^3.
  156. #
  157. float32 estimated_consumed_fuel_volume_cm3
  158. #
  159. # Throttle position.
  160. # Unit: percent.
  161. #
  162. uint7 throttle_position_percent
  163. #
  164. # The index of the publishing ECU.
  165. #
  166. uint6 ecu_index
  167. #
  168. # Spark plug activity report.
  169. # Can be used during pre-flight tests of the spark subsystem.
  170. #
  171. uint3 spark_plug_usage
  172. #
  173. uint3 SPARK_PLUG_SINGLE = 0
  174. uint3 SPARK_PLUG_FIRST_ACTIVE = 1
  175. uint3 SPARK_PLUG_SECOND_ACTIVE = 2
  176. uint3 SPARK_PLUG_BOTH_ACTIVE = 3
  177. #
  178. # Per-cylinder status information.
  179. #
  180. CylinderStatus[<=16] cylinder_status

CylinderStatus
Full name: uavcan.equipment.ice.reciprocating.CylinderStatus

  1. #
  2. # Cylinder state information.
  3. # This is a nested data type.
  4. #
  5. # All unknown parameters should be set to NaN.
  6. #
  7. #
  8. # Cylinder ignition timing.
  9. # Units: angular degrees of the crankshaft.
  10. #
  11. float16 ignition_timing_deg
  12. #
  13. # Fuel injection time.
  14. # Units: millisecond.
  15. #
  16. float16 injection_time_ms
  17. #
  18. # Cylinder head temperature (CHT).
  19. # Units: kelvin.
  20. #
  21. float16 cylinder_head_temperature
  22. #
  23. # Exhaust gas temperature (EGT).
  24. # Set to NaN if this cylinder is not equipped with an EGT sensor.
  25. # Set this field to the same value for all cylinders if there is a single shared EGT sensor.
  26. # Units: kelvin.
  27. #
  28. float16 exhaust_gas_temperature
  29. #
  30. # Estimated lambda coefficient.
  31. # This parameter is mostly useful for monitoring and tuning purposes.
  32. # Unit: dimensionless ratio
  33. #
  34. float16 lambda_coefficient

uavcan.equipment.indication

BeepCommand
Full name: uavcan.equipment.indication.BeepCommand
Default data type ID: 1080

  1. #
  2. # Nodes that are capable of producing sounds should obey.
  3. #
  4. float16 frequency # Hz
  5. float16 duration # Sec

LightsCommand
Full name: uavcan.equipment.indication.LightsCommand
Default data type ID: 1081

  1. #
  2. # Lights control command.
  3. #
  4. SingleLightCommand[<=20] commands

RGB565
Full name: uavcan.equipment.indication.RGB565

  1. #
  2. # Nested type.
  3. # RGB color in the standard 5-6-5 16-bit palette.
  4. # Monocolor lights should interpret this as brightness setpoint: from zero (0, 0, 0) to full brightness (31, 63, 31).
  5. #
  6. uint5 red
  7. uint6 green
  8. uint5 blue

SingleLightCommand
Full name: uavcan.equipment.indication.SingleLightCommand

  1. #
  2. # Nested type.
  3. # Controls single light source, color or monochrome.
  4. #
  5. #
  6. # Common aircraft lights IDs
  7. #
  8. # inform the crew working on the apron around noisy airplanes, wearing hearing protection,
  9. # that the engines are turned on. Also called beacon light
  10. uint8 LIGHT_ID_ANTI_COLLISION = 246
  11. # a red light is mounted on the left, or port, side of the craft and a green on the right,
  12. # or starboard, side both 110 degree, and tail white light of 140 degree. Also called navigation lights
  13. uint8 LIGHT_ID_RIGHT_OF_WAY = 247
  14. # high-intensity burst of white light, to help other pilots recognize the
  15. # aircraft's position in low-visibility conditions
  16. uint8 LIGHT_ID_STROBE = 248
  17. # positioned on the outer side just in front of the engine cowlings on the fuselage
  18. uint8 LIGHT_ID_WING = 249
  19. # lights that highlite on the logo painted on the tail or other visible surface.
  20. # Also called vertical tail flood lights
  21. uint8 LIGHT_ID_LOGO = 250
  22. # help the pilots see the area in front of them and also shows other traffic that they're on the move
  23. uint8 LIGHT_ID_TAXI = 251
  24. # light up the area in front of the airplane a bit more towards the side, easier for turns
  25. uint8 LIGHT_ID_TURN_OFF = 252
  26. # very bright, lights up the area in front but a lot more than the taxi light
  27. uint8 LIGHT_ID_TAKE_OFF = 253
  28. # very bright lights on the wings to help the pilots during landing by
  29. # lighting up the area where they're going to touch down
  30. uint8 LIGHT_ID_LANDING = 254
  31. # usually yellow electroluminescent lightstrips designed to use
  32. # during formation flying at night or under low visibility conditions
  33. uint8 LIGHT_ID_FORMATION = 255
  34. uint8 light_id
  35. RGB565 color # Monocolor lights should interpret this as brightness

uavcan.equipment.power

PrimaryPowerSupplyStatus
Full name: uavcan.equipment.power.PrimaryPowerSupplyStatus
Default data type ID: 1090

  1. #
  2. # Primary power supply status.
  3. # Typical publishing rate should be around 1~2 Hz.
  4. #
  5. #
  6. # How many hours left to full discharge at average load over the last 10 seconds.
  7. #
  8. float16 hours_to_empty_at_10sec_avg_power # [Hours]
  9. float16 hours_to_empty_at_10sec_avg_power_variance # [Hours^2]
  10. #
  11. # True if the publishing node senses that an external power source can be used, e.g. to charge batteries.
  12. #
  13. bool external_power_available
  14. #
  15. # Remaining energy estimate in percent.
  16. #
  17. uint7 remaining_energy_pct # [Percent] Required
  18. uint7 remaining_energy_pct_stdev # [Percent] Error standard deviation. Use best guess if unknown.

CircuitStatus
Full name: uavcan.equipment.power.CircuitStatus
Default data type ID: 1091

  1. #
  2. # Generic electrical circuit info.
  3. #
  4. uint16 circuit_id
  5. float16 voltage
  6. float16 current
  7. uint8 ERROR_FLAG_OVERVOLTAGE = 1
  8. uint8 ERROR_FLAG_UNDERVOLTAGE = 2
  9. uint8 ERROR_FLAG_OVERCURRENT = 4
  10. uint8 ERROR_FLAG_UNDERCURRENT = 8
  11. uint8 error_flags

BatteryInfo
Full name: uavcan.equipment.power.BatteryInfo
Default data type ID: 1092

  1. #
  2. # Single battery info.
  3. #
  4. # Typical publishing rate should be around 0.2~1 Hz.
  5. #
  6. # Please refer to the Smart Battery data specification for some elaboration.
  7. #
  8. #
  9. # Primary parameters.
  10. # Some fields can be set to NAN if their values are unknown.
  11. # Full charge capacity is expected to slowly reduce as the battery is aging. Normally its estimate is updated after
  12. # every charging cycle.
  13. #
  14. float16 temperature # [Kelvin]
  15. float16 voltage # [Volt]
  16. float16 current # [Ampere]
  17. float16 average_power_10sec # [Watt] Average power consumption over the last 10 seconds
  18. float16 remaining_capacity_wh # [Watt hours] Will be increasing during charging
  19. float16 full_charge_capacity_wh # [Watt hours] Predicted battery capacity when it is fully charged. Falls with aging
  20. float16 hours_to_full_charge # [Hours] Charging is expected to complete in this time; zero if not charging
  21. #
  22. # Status flags.
  23. # Notes:
  24. # - CHARGING must be always set as long as the battery is connected to a charger, even if the charging is complete.
  25. # - CHARGED must be cleared immediately when the charger is disconnected.
  26. #
  27. uint11 STATUS_FLAG_IN_USE = 1 # The battery is currently used as a power supply
  28. uint11 STATUS_FLAG_CHARGING = 2 # Charger is active
  29. uint11 STATUS_FLAG_CHARGED = 4 # Charging complete, but the charger is still active
  30. uint11 STATUS_FLAG_TEMP_HOT = 8 # Battery temperature is above normal
  31. uint11 STATUS_FLAG_TEMP_COLD = 16 # Battery temperature is below normal
  32. uint11 STATUS_FLAG_OVERLOAD = 32 # Safe operating area violation
  33. uint11 STATUS_FLAG_BAD_BATTERY = 64 # This battery should not be used anymore (e.g. low SOH)
  34. uint11 STATUS_FLAG_NEED_SERVICE = 128 # This battery requires maintenance (e.g. balancing, full recharge)
  35. uint11 STATUS_FLAG_BMS_ERROR = 256 # Battery management system/controller error, smart battery interface error
  36. uint11 STATUS_FLAG_RESERVED_A = 512 # Keep zero
  37. uint11 STATUS_FLAG_RESERVED_B = 1024 # Keep zero
  38. uint11 status_flags
  39. #
  40. # State of Health (SOH) estimate, in percent.
  41. # http://en.wikipedia.org/wiki/State_of_health
  42. #
  43. uint7 STATE_OF_HEALTH_UNKNOWN = 127 # Use this constant if SOH cannot be estimated
  44. uint7 state_of_health_pct # Health of the battery, in percent, optional
  45. #
  46. # Relative State of Charge (SOC) estimate, in percent.
  47. # http://en.wikipedia.org/wiki/State_of_charge
  48. #
  49. uint7 state_of_charge_pct # Percent of the full charge [0, 100]. This field is required
  50. uint7 state_of_charge_pct_stdev # SOC error standard deviation; use best guess if unknown
  51. #
  52. # Battery identification.
  53. # Model instance ID must be unique within the same battery model name.
  54. # Model name is a human-readable string that normally should include the vendor name, model name, and chemistry
  55. # type of this battery. This field should be assumed case-insensitive. Example: "Zubax Smart Battery v1.1 LiPo".
  56. #
  57. uint8 battery_id # Identifies the battery within this vehicle, e.g. 0 - primary battery
  58. uint32 model_instance_id # Set to zero if not applicable
  59. uint8[<32] model_name # Battery model name

uavcan.equipment.range_sensor

Measurement
Full name: uavcan.equipment.range_sensor.Measurement
Default data type ID: 1050

  1. #
  2. # Generic narrow-beam range sensor data.
  3. #
  4. uavcan.Timestamp timestamp
  5. uint8 sensor_id
  6. uavcan.CoarseOrientation beam_orientation_in_body_frame
  7. float16 field_of_view # Radians
  8. uint5 SENSOR_TYPE_UNDEFINED = 0
  9. uint5 SENSOR_TYPE_SONAR = 1
  10. uint5 SENSOR_TYPE_LIDAR = 2
  11. uint5 SENSOR_TYPE_RADAR = 3
  12. uint5 sensor_type
  13. uint3 READING_TYPE_UNDEFINED = 0 # Range is unknown
  14. uint3 READING_TYPE_VALID_RANGE = 1 # Range field contains valid distance
  15. uint3 READING_TYPE_TOO_CLOSE = 2 # Range field contains min range for the sensor
  16. uint3 READING_TYPE_TOO_FAR = 3 # Range field contains max range for the sensor
  17. uint3 reading_type
  18. float16 range # Meters

uavcan.equipment.safety

ArmingStatus
Full name: uavcan.equipment.safety.ArmingStatus
Default data type ID: 1100

  1. #
  2. # This message represents the system arming status.
  3. # Some nodes may refuse to operate unless the system is fully armed.
  4. #
  5. uint8 STATUS_DISARMED = 0
  6. uint8 STATUS_FULLY_ARMED = 255
  7. uint8 status

uavcan.navigation

GlobalNavigationSolution
Full name: uavcan.navigation.GlobalNavigationSolution
Default data type ID: 2000

  1. #
  2. # Inertial data and orientation in body frame with fused location.
  3. #
  4. # Fields marked as optional should be set to NaN if the corresponding value is unknown.
  5. #
  6. #
  7. # Global network synchronized timestamp, if known.
  8. # Set to zero if the timestamp is not known.
  9. #
  10. uavcan.Timestamp timestamp
  11. #
  12. # Geo location [angular degree].
  13. #
  14. float64 longitude # required
  15. float64 latitude # required
  16. #
  17. # Height estimates [meter].
  18. #
  19. float32 height_ellipsoid # Above ellipsoid (required)
  20. float32 height_msl # Above the mean sea level (required)
  21. float32 height_agl # Above ground level (provided by radar altimeter or LIDAR) (optional)
  22. float32 height_baro # Barometric height (optional)
  23. #
  24. # Atmospheric pressure adjusted to sea level [hectopascal].
  25. #
  26. float16 qnh_hpa # optional
  27. #
  28. # Rotation quaternion between the NED frame and the body frame.
  29. # Zero rotation corresponds to the following orientation:
  30. # X facing north
  31. # Y facing east
  32. # Z facing down
  33. #
  34. float32[4] orientation_xyzw
  35. #
  36. # Column order:
  37. # longitude [meter^2]
  38. # latitude [meter^2]
  39. # height (MSL or ellipsoid, whichever worse) [meter^2]
  40. # roll angle [radian^2]
  41. # pitch angle [radian^2]
  42. # yaw angle [radian^2]
  43. #
  44. float16[<=36] pose_covariance
  45. #
  46. # Linear velocity in the body frame, X-Y-Z [meter/second].
  47. #
  48. float32[3] linear_velocity_body
  49. #
  50. # Angular velocity in the body frame, roll-pitch-yaw [radian/second].
  51. #
  52. float32[3] angular_velocity_body
  53. #
  54. # Low resolution estimate of the linear acceleration in the body frame [(meter/second)^2].
  55. # This estimate should be properly downsampled in order to avoid aliasing effects.
  56. #
  57. float16[3] linear_acceleration_body
  58. #
  59. # Column order:
  60. # X velocity [(meter/second)^2]
  61. # Y velocity [(meter/second)^2]
  62. # Z velocity [(meter/second)^2]
  63. # roll velocity [(radian/second)^2]
  64. # pitch velocity [(radian/second)^2]
  65. # yaw velocity [(radian/second)^2]
  66. #
  67. float16[<=36] velocity_covariance

uavcan.protocol

GetNodeInfo
Full name: uavcan.protocol.GetNodeInfo
Default data type ID: 1

  1. #
  2. # Full node info request.
  3. # Note that all fields of the response section are byte-aligned.
  4. #
  5. ---
  6. #
  7. # Current node status
  8. #
  9. NodeStatus status
  10. #
  11. # Version information shall not be changed while the node is running.
  12. #
  13. SoftwareVersion software_version
  14. HardwareVersion hardware_version
  15. #
  16. # Human readable non-empty ASCII node name.
  17. # Node name shall not be changed while the node is running.
  18. # Empty string is not a valid node name.
  19. # Allowed characters are: a-z (lowercase ASCII letters) 0-9 (decimal digits) . (dot) - (dash) _ (underscore).
  20. # Node name is a reversed internet domain name (like Java packages), e.g. "com.manufacturer.project.product".
  21. #
  22. uint8[<=80] name

GetDataTypeInfo
Full name: uavcan.protocol.GetDataTypeInfo
Default data type ID: 2

  1. #
  2. # Get the implementation details of a given data type.
  3. #
  4. # Request is interpreted as follows:
  5. # - If the field 'name' is empty, the fields 'kind' and 'id' will be used to identify the data type.
  6. # - If the field 'name' is non-empty, it will be used to identify the data type; the
  7. # fields 'kind' and 'id' will be ignored.
  8. #
  9. uint16 id # Ignored if 'name' is non-empty
  10. DataTypeKind kind # Ignored if 'name' is non-empty
  11. uint8[<=80] name # Full data type name, e.g. "uavcan.protocol.GetDataTypeInfo"
  12. ---
  13. uint64 signature # Data type signature; valid only if the data type is known (see FLAG_KNOWN)
  14. uint16 id # Valid only if the data type is known (see FLAG_KNOWN)
  15. DataTypeKind kind # Ditto
  16. uint8 FLAG_KNOWN = 1 # This data type is defined
  17. uint8 FLAG_SUBSCRIBED = 2 # Subscribed to messages of this type
  18. uint8 FLAG_PUBLISHING = 4 # Publishing messages of this type
  19. uint8 FLAG_SERVING = 8 # Providing service of this type
  20. uint8 flags
  21. uint8[<=80] name # Full data type name

NodeStatus
Full name: uavcan.protocol.NodeStatus
Default data type ID: 341

  1. #
  2. # Abstract node status information.
  3. #
  4. # Any UAVCAN node is required to publish this message periodically.
  5. #
  6. #
  7. # Publication period may vary within these limits.
  8. # It is NOT recommended to change it at run time.
  9. #
  10. uint16 MAX_BROADCASTING_PERIOD_MS = 1000
  11. uint16 MIN_BROADCASTING_PERIOD_MS = 2
  12. #
  13. # If a node fails to publish this message in this amount of time, it should be considered offline.
  14. #
  15. uint16 OFFLINE_TIMEOUT_MS = 3000
  16. #
  17. # Uptime counter should never overflow.
  18. # Other nodes may detect that a remote node has restarted when this value goes backwards.
  19. #
  20. uint32 uptime_sec
  21. #
  22. # Abstract node health.
  23. #
  24. uint2 HEALTH_OK = 0 # The node is functioning properly.
  25. uint2 HEALTH_WARNING = 1 # A critical parameter went out of range or the node encountered a minor failure.
  26. uint2 HEALTH_ERROR = 2 # The node encountered a major failure.
  27. uint2 HEALTH_CRITICAL = 3 # The node suffered a fatal malfunction.
  28. uint2 health
  29. #
  30. # Current mode.
  31. #
  32. # Mode OFFLINE can be actually reported by the node to explicitly inform other network
  33. # participants that the sending node is about to shutdown. In this case other nodes will not
  34. # have to wait OFFLINE_TIMEOUT_MS before they detect that the node is no longer available.
  35. #
  36. # Reserved values can be used in future revisions of the specification.
  37. #
  38. uint3 MODE_OPERATIONAL = 0 # Node is performing its main functions.
  39. uint3 MODE_INITIALIZATION = 1 # Node is initializing; this mode is entered immediately after startup.
  40. uint3 MODE_MAINTENANCE = 2 # Node is under maintenance.
  41. uint3 MODE_SOFTWARE_UPDATE = 3 # Node is in the process of updating its software.
  42. uint3 MODE_OFFLINE = 7 # Node is no longer available.
  43. uint3 mode
  44. #
  45. # Not used currently, keep zero when publishing, ignore when receiving.
  46. #
  47. uint3 sub_mode
  48. #
  49. # Optional, vendor-specific node status code, e.g. a fault code or a status bitmask.
  50. #
  51. uint16 vendor_specific_status_code

GetTransportStats
Full name: uavcan.protocol.GetTransportStats
Default data type ID: 4

  1. #
  2. # Get transport statistics.
  3. #
  4. ---
  5. #
  6. # UAVCAN transport layer statistics.
  7. #
  8. uint48 transfers_tx # Number of transmitted transfers.
  9. uint48 transfers_rx # Number of received transfers.
  10. uint48 transfer_errors # Number of errors detected in the UAVCAN transport layer.
  11. #
  12. # CAN bus statistics, for each interface independently.
  13. #
  14. CANIfaceStats[<=3] can_iface_stats

GlobalTimeSync
Full name: uavcan.protocol.GlobalTimeSync
Default data type ID: 4

  1. #
  2. # Global time synchronization.
  3. # Any node that publishes timestamped data must use this time reference.
  4. #
  5. # Please refer to the specification to learn about the synchronization algorithm.
  6. #
  7. #
  8. # Broadcasting period must be within this range.
  9. #
  10. uint16 MAX_BROADCASTING_PERIOD_MS = 1100 # Milliseconds
  11. uint16 MIN_BROADCASTING_PERIOD_MS = 40 # Milliseconds
  12. #
  13. # Synchronization slaves may switch to a new source if the current master was silent for this amount of time.
  14. #
  15. uint16 RECOMMENDED_BROADCASTER_TIMEOUT_MS = 2200 # Milliseconds
  16. #
  17. # Time in microseconds when the PREVIOUS GlobalTimeSync message was transmitted.
  18. # If this message is the first one, this field must be zero.
  19. #
  20. truncated uint56 previous_transmission_timestamp_usec # Microseconds

Panic
Full name: uavcan.protocol.Panic
Default data type ID: 5

  1. #
  2. # This message may be published periodically to inform network participants that the system has encountered
  3. # an unrecoverable fault and is not capable of further operation.
  4. #
  5. # Nodes that are expected to react to this message should wait for at least MIN_MESSAGES subsequent messages
  6. # with any reason text from any sender published with the interval no higher than MAX_INTERVAL_MS before
  7. # undertaking any emergency actions.
  8. #
  9. uint8 MIN_MESSAGES = 3
  10. uint16 MAX_INTERVAL_MS = 500
  11. #
  12. # Short description that would fit a single CAN frame.
  13. #
  14. uint8[<=7] reason_text

RestartNode
Full name: uavcan.protocol.RestartNode
Default data type ID: 5

  1. #
  2. # Restart the node.
  3. #
  4. # Some nodes may require restart before the new configuration will be applied.
  5. #
  6. # The request should be rejected if magic_number does not equal MAGIC_NUMBER.
  7. #
  8. uint40 MAGIC_NUMBER = 0xACCE551B1E
  9. uint40 magic_number
  10. ---
  11. bool ok

AccessCommandShell
Full name: uavcan.protocol.AccessCommandShell
Default data type ID: 6

  1. #
  2. # THIS DEFINITION IS SUBJECT TO CHANGE.
  3. #
  4. # This service allows to execute arbitrary commands on the remote node's internal system shell.
  5. #
  6. # Essentially, this service mimics a typical terminal emulator, with one text input (stdin) and two text
  7. # outputs (stdout and stderr). When there's no process running, the input is directed into the terminal
  8. # handler itself, which interpretes it. If there's a process running, the input will be directed into
  9. # stdin of the running process. It is possible to forcefully return the terminal into a known state by
  10. # means of setting the reset flag (see below), in which case the terminal will kill all of the child
  11. # processes, if any, and return into the initial idle state.
  12. #
  13. # The server is assumed to allocate one independent terminal instance per client, so that different clients
  14. # can execute commands without interfering with each other.
  15. #
  16. #
  17. # Input and output should use this newline character.
  18. #
  19. uint8 NEWLINE = '\n'
  20. #
  21. # The server is required to keep the result of the last executed command for at least this time.
  22. # When this time expires, the server may remove the results in order to reclaim the memory, but it
  23. # is not guaranteed. Hence, the clients must retrieve the results in this amount of time.
  24. #
  25. uint8 MIN_OUTPUT_LIFETIME_SEC = 10
  26. #
  27. # These flags control the shell and command execution.
  28. #
  29. uint8 FLAG_RESET_SHELL = 1 # Restarts the shell instance anew; may or may not imply CLEAR_OUTPUT_BUFFERS
  30. uint8 FLAG_CLEAR_OUTPUT_BUFFERS = 2 # Makes stdout and stderr buffers empty
  31. uint8 FLAG_READ_STDOUT = 64 # Output will contain stdout
  32. uint8 FLAG_READ_STDERR = 128 # Output will be extended with stderr
  33. uint8 flags
  34. #
  35. # If the shell is idle, it will interpret this string.
  36. # If there's a process running, this string will be piped into its stdin.
  37. #
  38. # If RESET_SHELL is set, new input will be interpreted by the shell immediately.
  39. #
  40. uint8[<=128] input
  41. ---
  42. #
  43. # Exit status of the last executed process, or error code of the shell itself.
  44. # Default value is zero.
  45. #
  46. int32 last_exit_status
  47. #
  48. # These flags indicate the status of the shell.
  49. #
  50. uint8 FLAG_RUNNING = 1 # The shell is currently running a process; stdin/out/err are piped to it
  51. uint8 FLAG_SHELL_ERROR = 2 # Exit status contains error code, output contains text (e.g. no such command)
  52. uint8 FLAG_HAS_PENDING_STDOUT = 64 # There is more stdout to read
  53. uint8 FLAG_HAS_PENDING_STDERR = 128 # There is more stderr to read
  54. uint8 flags
  55. #
  56. # In case of a shell error, this string may contain ASCII string explaining the nature of the error.
  57. # Otherwise, if stdout read is requested, this string will contain stdout data. If stderr read is requested,
  58. # this string will contain stderr data. If both stdout and stderr read is requested, this string will start
  59. # with stdout and end with stderr, with no separator in between.
  60. #
  61. uint8[<=256] output

CANIfaceStats
Full name: uavcan.protocol.CANIfaceStats

  1. #
  2. # Single CAN iface statistics.
  3. #
  4. uint48 frames_tx # Number of transmitted CAN frames.
  5. uint48 frames_rx # Number of received CAN frames.
  6. uint48 errors # Number of errors in the CAN layer.

DataTypeKind
Full name: uavcan.protocol.DataTypeKind

  1. #
  2. # Data type kind (message or service).
  3. #
  4. uint8 SERVICE = 0
  5. uint8 MESSAGE = 1
  6. uint8 value

HardwareVersion
Full name: uavcan.protocol.HardwareVersion

  1. #
  2. # Nested type.
  3. # Generic hardware version information.
  4. # These values should remain unchanged for the device's lifetime.
  5. #
  6. #
  7. # Hardware version code.
  8. #
  9. uint8 major
  10. uint8 minor
  11. #
  12. # Unique ID is a 128 bit long sequence that is globally unique for each node.
  13. # All zeros is not a valid UID.
  14. # If filled with zeros, assume that the value is undefined.
  15. #
  16. uint8[16] unique_id
  17. #
  18. # Certificate of authenticity (COA) of the hardware, 255 bytes max.
  19. #
  20. uint8[<=255] certificate_of_authenticity

SoftwareVersion
Full name: uavcan.protocol.SoftwareVersion

  1. #
  2. # Nested type.
  3. # Generic software version information.
  4. #
  5. #
  6. # Primary version numbers.
  7. # If both fields are set to zero, the version is considered unknown.
  8. #
  9. uint8 major
  10. uint8 minor
  11. #
  12. # This mask indicates which optional fields (see below) are set.
  13. #
  14. uint8 OPTIONAL_FIELD_FLAG_VCS_COMMIT = 1
  15. uint8 OPTIONAL_FIELD_FLAG_IMAGE_CRC = 2
  16. uint8 optional_field_flags
  17. #
  18. # VCS commit hash or revision number, e.g. git short commit hash. Optional.
  19. #
  20. uint32 vcs_commit
  21. #
  22. # The value of an arbitrary hash function applied to the firmware image.
  23. # This field is used to detect whether the firmware running on the node is EXACTLY THE SAME
  24. # as a certain specific revision. This field provides the absolute identity guarantee, unlike
  25. # the version fields above, which can be the same for different builds of the firmware.
  26. #
  27. # The exact hash function and the methods of its application are implementation defined.
  28. # However, implementations are recommended to adhere to the following guidelines,
  29. # fully or partially:
  30. #
  31. # - The hash function should be CRC-64-WE, the same that is used for computing DSDL signatures.
  32. #
  33. # - The hash function should be applied to the entire application image padded to 8 bytes.
  34. #
  35. # - If the computed image CRC is stored within the firmware image itself, the value of
  36. # the hash function becomes ill-defined, because it becomes recursively dependent on itself.
  37. # In order to circumvent this issue, while computing or checking the CRC, its value stored
  38. # within the image should be zeroed out.
  39. #
  40. uint64 image_crc

uavcan.protocol.debug

KeyValue
Full name: uavcan.protocol.debug.KeyValue
Default data type ID: 16370

  1. #
  2. # Generic named parameter (key/value pair).
  3. #
  4. #
  5. # Integers are exactly representable in the range (-2^24, 2^24) which is (-16'777'216, 16'777'216).
  6. #
  7. float32 value
  8. #
  9. # Tail array optimization is enabled, so if key length does not exceed 3 characters, the whole
  10. # message can fit into one CAN frame. The message always fits into one CAN FD frame.
  11. #
  12. uint8[<=58] key

LogMessage
Full name: uavcan.protocol.debug.LogMessage
Default data type ID: 16383

  1. #
  2. # Generic log message.
  3. # All items are byte aligned.
  4. #
  5. LogLevel level
  6. uint8[<=31] source
  7. uint8[<=90] text

LogLevel
Full name: uavcan.protocol.debug.LogLevel

  1. #
  2. # Log message severity
  3. #
  4. uint3 DEBUG = 0
  5. uint3 INFO = 1
  6. uint3 WARNING = 2
  7. uint3 ERROR = 3
  8. uint3 value

uavcan.protocol.dynamic_node_id

Allocation
Full name: uavcan.protocol.dynamic_node_id.Allocation
Default data type ID: 1

  1. #
  2. # This message is used for dynamic Node ID allocation.
  3. #
  4. # When a node needs to request a node ID dynamically, it will transmit an anonymous message transfer of this type.
  5. # In order to reduce probability of CAN ID collisions when multiple nodes are publishing this request, the CAN ID
  6. # field of anonymous message transfer includes a Discriminator, which is a special field that has to be filled with
  7. # random data by the transmitting node. Since Discriminator collisions are likely to happen (probability approx.
  8. # 0.006%), nodes that are requesting dynamic allocations need to be able to handle them correctly. Hence, a collision
  9. # resolution protocol is defined (alike CSMA/CD). The collision resolution protocol is based on two randomized
  10. # transmission intervals:
  11. #
  12. # - Request period - Trequest.
  13. # - Followup delay - Tfollowup.
  14. #
  15. # Recommended randomization ranges for these intervals are documented in the costants of this message type (see below).
  16. # Random intervals must be chosen anew per transmission, whereas the Discriminator value is allowed to stay constant
  17. # per node.
  18. #
  19. # In the below description the following terms are used:
  20. # - Allocator - the node that serves allocation requests.
  21. # - Allocatee - the node that requests an allocation from the Allocator.
  22. #
  23. # The response timeout is not explicitly defined for this protocol, as the Allocatee will request the allocation
  24. # Trequest units of time later again, unless the allocation has been granted. Despite this, the implementation can
  25. # consider the value of FOLLOWUP_TIMEOUT_MS as an allocation timeout, if necessary.
  26. #
  27. # On the allocatee's side the protocol is defined through the following set of rules:
  28. #
  29. # Rule A. On initialization:
  30. # 1. The allocatee subscribes to this message.
  31. # 2. The allocatee starts the Request Timer with a random interval of Trequest.
  32. #
  33. # Rule B. On expiration of Request Timer:
  34. # 1. Request Timer restarts with a random interval of Trequest.
  35. # 2. The allocatee broadcasts a first-stage Allocation request message, where the fields are assigned following values:
  36. # node_id - preferred node ID, or zero if the allocatee doesn't have any preference
  37. # first_part_of_unique_id - true
  38. # unique_id - first MAX_LENGTH_OF_UNIQUE_ID_IN_REQUEST bytes of unique ID
  39. #
  40. # Rule C. On any Allocation message, even if other rules also match:
  41. # 1. Request Timer restarts with a random interval of Trequest.
  42. #
  43. # Rule D. On an Allocation message WHERE (source node ID is non-anonymous) AND (allocatee's unique ID starts with the
  44. # bytes available in the field unique_id) AND (unique_id is less than 16 bytes long):
  45. # 1. The allocatee waits for Tfollowup units of time, while listening for other Allocation messages. If an Allocation
  46. # message is received during this time, the execution of this rule will be terminated. Also see rule C.
  47. # 2. The allocatee broadcasts a second-stage Allocation request message, where the fields are assigned following values:
  48. # node_id - same value as in the first-stage
  49. # first_part_of_unique_id - false
  50. # unique_id - at most MAX_LENGTH_OF_UNIQUE_ID_IN_REQUEST bytes of local unique ID with an offset
  51. # equal to number of bytes in the received unique ID
  52. #
  53. # Rule E. On an Allocation message WHERE (source node ID is non-anonymous) AND (unique_id fully matches allocatee's
  54. # unique ID) AND (node_id in the received message is not zero):
  55. # 1. Request Timer stops.
  56. # 2. The allocatee initializes its node_id with the received value.
  57. # 3. The allocatee terminates subscription to Allocation messages.
  58. # 4. Exit.
  59. #
  60. #
  61. # Recommended randomization range for request period.
  62. #
  63. # These definitions have an advisory status; it is OK to pick higher values for both bounds, as it won't affect
  64. # protocol compatibility. In fact, it is advised to pick higher values if the target application is not concerned
  65. # about the time it will spend on completing the dynamic node ID allocation procedure, as it will reduce
  66. # interference with other nodes, possibly of higher importance.
  67. #
  68. # The lower bound shall not be lower than FOLLOWUP_TIMEOUT_MS, otherwise the request may conflict with a followup.
  69. #
  70. uint16 MAX_REQUEST_PERIOD_MS = 1000 # It is OK to exceed this value
  71. uint16 MIN_REQUEST_PERIOD_MS = 600 # It is OK to exceed this value
  72. #
  73. # Recommended randomization range for followup delay.
  74. # The upper bound shall not exceed FOLLOWUP_TIMEOUT_MS, because the allocator will reset the state on its end.
  75. #
  76. uint16 MAX_FOLLOWUP_DELAY_MS = 400
  77. uint16 MIN_FOLLOWUP_DELAY_MS = 0 # Defined only for regularity; will always be zero.
  78. #
  79. # Allocator will reset its state if there was no follow-up request in this amount of time.
  80. #
  81. uint16 FOLLOWUP_TIMEOUT_MS = 500
  82. #
  83. # Any request message can accommodate no more than this number of bytes of unique ID.
  84. # This limitation is needed to ensure that all request transfers are single-frame.
  85. # This limitation does not apply to CAN FD transport.
  86. #
  87. uint8 MAX_LENGTH_OF_UNIQUE_ID_IN_REQUEST = 6
  88. #
  89. # When requesting an allocation, set the field 'node_id' to this value if there's no preference.
  90. #
  91. uint7 ANY_NODE_ID = 0
  92. #
  93. # If transfer is anonymous, this is the preferred ID.
  94. # If transfer is non-anonymous, this is allocated ID.
  95. #
  96. # If the allocatee does not have any preference, this value must be set to zero. In this case, the allocator
  97. # must choose the highest unused node ID value for this allocation (except 126 and 127, that are reserved for
  98. # network maintenance tools). E.g., if the allocation table is empty and the node has requested an allocation
  99. # without any preference, the allocator will grant the node ID 125.
  100. #
  101. # If the preferred node ID is not zero, the allocator will traverse the allocation table starting from the
  102. # prefferred node ID upward, untill a free node ID is found. If a free node ID could not be found, the
  103. # allocator will restart the search from the preferred node ID downward, until a free node ID is found.
  104. #
  105. # In pseudocode:
  106. # int findFreeNodeID(const int preferred)
  107. # {
  108. # // Search up
  109. # int candidate = (preferred > 0) ? preferred : 125;
  110. # while (candidate <= 125)
  111. # {
  112. # if (!isOccupied(candidate))
  113. # return candidate;
  114. # candidate++;
  115. # }
  116. # // Search down
  117. # candidate = (preferred > 0) ? preferred : 125;
  118. # while (candidate > 0)
  119. # {
  120. # if (!isOccupied(candidate))
  121. # return candidate;
  122. # candidate--;
  123. # }
  124. # // Not found
  125. # return -1;
  126. # }
  127. #
  128. uint7 node_id
  129. #
  130. # If transfer is anonymous, this field indicates first-stage request.
  131. # If transfer is non-anonymous, this field should be assigned zero and ignored.
  132. #
  133. bool first_part_of_unique_id
  134. #
  135. # If transfer is anonymous, this array must not contain more than MAX_LENGTH_OF_UNIQUE_ID_IN_REQUEST items.
  136. # Note that array is tail-optimized, i.e. it will not be prepended with length field.
  137. #
  138. uint8[<=16] unique_id

uavcan.protocol.dynamic_node_id.server

AppendEntries
Full name: uavcan.protocol.dynamic_node_id.server.AppendEntries
Default data type ID: 30

  1. #
  2. # THIS DEFINITION IS SUBJECT TO CHANGE.
  3. #
  4. # This type is a part of the Raft consensus algorithm.
  5. # Please refer to the specification for details.
  6. #
  7. #
  8. # Given min election timeout and cluster size, the maximum recommended request interval can be derived as follows:
  9. #
  10. # max recommended request interval = (min election timeout) / 2 requests / (cluster size - 1)
  11. #
  12. # The equation assumes that the Leader requests one Follower at a time, so that there's at most one pending call
  13. # at any moment. Such behavior is optimal as it creates uniform bus load, but it is actually implementation-specific.
  14. # Obviously, request interval can be lower than that if needed, but higher values are not recommended as they may
  15. # cause Followers to initiate premature elections in case of intensive frame losses or delays.
  16. #
  17. # Real timeout is randomized in the range (MIN, MAX], according to the Raft paper.
  18. #
  19. uint16 DEFAULT_MIN_ELECTION_TIMEOUT_MS = 2000
  20. uint16 DEFAULT_MAX_ELECTION_TIMEOUT_MS = 4000
  21. #
  22. # Refer to the Raft paper for explanation.
  23. #
  24. uint32 term
  25. uint32 prev_log_term
  26. uint8 prev_log_index
  27. uint8 leader_commit
  28. #
  29. # Worst-case replication time per Follower can be computed as:
  30. #
  31. # worst replication time = (127 log entries) * (2 trips of next_index) * (request interval per Follower)
  32. #
  33. Entry[<=1] entries
  34. ---
  35. #
  36. # Refer to the Raft paper for explanation.
  37. #
  38. uint32 term
  39. bool success

RequestVote
Full name: uavcan.protocol.dynamic_node_id.server.RequestVote
Default data type ID: 31

  1. #
  2. # THIS DEFINITION IS SUBJECT TO CHANGE.
  3. #
  4. # This type is a part of the Raft consensus algorithm.
  5. # Please refer to the specification for details.
  6. #
  7. #
  8. # Refer to the Raft paper for explanation.
  9. #
  10. uint32 term
  11. uint32 last_log_term
  12. uint8 last_log_index
  13. ---
  14. #
  15. # Refer to the Raft paper for explanation.
  16. #
  17. uint32 term
  18. bool vote_granted

Discovery
Full name: uavcan.protocol.dynamic_node_id.server.Discovery
Default data type ID: 390

  1. #
  2. # THIS DEFINITION IS SUBJECT TO CHANGE.
  3. #
  4. # This message is used by allocation servers to find each other's node ID.
  5. # Please refer to the specification for details.
  6. #
  7. # A server should stop publishing this message as soon as it has discovered all other nodes in the cluster.
  8. #
  9. # An exception applies: when a server receives a Discovery message from another server where the list
  10. # of known nodes is incomplete (i.e. len(known_nodes) < configured_cluster_size), the server must
  11. # publish a discovery message once. This condition allows other servers to quickly re-discover the cluster
  12. # after restart.
  13. #
  14. #
  15. # This message should be broadcasted by the server at this interval until all other servers are discovered.
  16. #
  17. uint16 BROADCASTING_PERIOD_MS = 1000
  18. #
  19. # Number of servers in the cluster as configured on the sender.
  20. #
  21. uint8 configured_cluster_size
  22. #
  23. # Node ID of servers that are known to the publishing server, including the publishing server itself.
  24. # Capacity of this array defines maximum size of the server cluster.
  25. #
  26. uint8[<=5] known_nodes

Entry
Full name: uavcan.protocol.dynamic_node_id.server.Entry

  1. #
  2. # THIS DEFINITION IS SUBJECT TO CHANGE.
  3. #
  4. # One dynamic node ID allocation entry.
  5. # This type is a part of the Raft consensus algorithm.
  6. # Please refer to the specification for details.
  7. #
  8. uint32 term # Refer to the Raft paper for explanation.
  9. uint8[16] unique_id # Unique ID of this allocation.
  10. void1
  11. uint7 node_id # Node ID of this allocation.

uavcan.protocol.enumeration

Begin
Full name: uavcan.protocol.enumeration.Begin
Default data type ID: 15

  1. #
  2. # This service instructs the node to begin the process of automated enumeration.
  3. #
  4. #
  5. # The node will automatically leave enumeration mode upon expiration of this timeout.
  6. #
  7. uint16 TIMEOUT_CANCEL = 0 # Stop enumeration immediately
  8. uint16 TIMEOUT_INFINITE = 65535 # Do not stop until explicitly requested
  9. uint16 timeout_sec # [Seconds]
  10. #
  11. # Name of the parameter to enumerate, e.g. ESC index.
  12. # If the name is left empty, the node will infer the parameter name automatically (autodetect).
  13. # It is highly recommended to always use autodetection in order to avoid dependency on hard-coded parameter names,
  14. # and also allow the enumeratee to possibly enumerate multiple different parameters at once.
  15. # The rule of thumb is to always leave this parameter empty unless you really know what you're doing.
  16. #
  17. uint8[<=92] parameter_name
  18. ---
  19. uint8 ERROR_OK = 0 # Success
  20. uint8 ERROR_INVALID_MODE = 1 # The node cannot perform enumeration in its current operating mode
  21. uint8 ERROR_INVALID_PARAMETER = 2 # The node cannot enumerate on the requested parameter, or it doesn't exist
  22. uint8 ERROR_UNSUPPORTED = 3 # The node cannot perform enumeration in its current configuration
  23. uint8 ERROR_UNKNOWN = 255 # Generic error
  24. uint8 error

Indication
Full name: uavcan.protocol.enumeration.Indication
Default data type ID: 380

  1. #
  2. # This message will be broadcasted when the node receives user input in the process of enumeration.
  3. #
  4. void6
  5. #
  6. # This field is unused; keep it empty
  7. #
  8. uavcan.protocol.param.NumericValue value
  9. #
  10. # Name of the enumerated parameter.
  11. # This field must always be populated by the enumeratee.
  12. # If multiple parameters were enumerated at once (e.g. ESC index and the direction of rotation),
  13. # the field should contain the name of the most important parameter.
  14. #
  15. uint8[<=92] parameter_name

uavcan.protocol.file

BeginFirmwareUpdate
Full name: uavcan.protocol.file.BeginFirmwareUpdate
Default data type ID: 40

  1. #
  2. # This service initiates firmware update on a remote node.
  3. #
  4. # The node that is being updated (slave) will retrieve the firmware image file 'image_file_remote_path' from the node
  5. # 'source_node_id' using the file read service, then it will update the firmware and reboot.
  6. #
  7. # The slave can explicitly reject this request if it is not possible to update the firmware at the moment
  8. # (e.g. if the node is busy).
  9. #
  10. # If the slave node accepts this request, the initiator will get a response immediately, before the update process
  11. # actually begins.
  12. #
  13. # While the firmware is being updated, the slave should set its mode (uavcan.protocol.NodeStatus.mode) to
  14. # MODE_SOFTWARE_UPDATE.
  15. #
  16. uint8 source_node_id # If this field is zero, the caller's Node ID will be used instead.
  17. Path image_file_remote_path
  18. ---
  19. #
  20. # Other error codes may be added in the future.
  21. #
  22. uint8 ERROR_OK = 0
  23. uint8 ERROR_INVALID_MODE = 1 # Cannot perform the update in the current operating mode or state.
  24. uint8 ERROR_IN_PROGRESS = 2 # Firmware update is already in progess, and the slave doesn't want to restart.
  25. uint8 ERROR_UNKNOWN = 255
  26. uint8 error
  27. uint8[<128] optional_error_message # Detailed description of the error.

GetInfo
Full name: uavcan.protocol.file.GetInfo
Default data type ID: 45

  1. #
  2. # Request info about a remote file system entry (file, directory, etc).
  3. #
  4. Path path
  5. ---
  6. #
  7. # File size in bytes.
  8. # Should be set to zero for directories.
  9. #
  10. uint40 size
  11. Error error
  12. EntryType entry_type

GetDirectoryEntryInfo
Full name: uavcan.protocol.file.GetDirectoryEntryInfo
Default data type ID: 46

  1. #
  2. # This service can be used to retrieve remote directory listing, one entry per request.
  3. #
  4. # The client should query each entry independently, iterating 'entry_index' from 0 until the last entry is passed,
  5. # in which case the server will report that there is no such entry (via the fields 'entry_type' and 'error').
  6. #
  7. # The entry_index shall be applied to the ordered list of directory entries (e.g. alphabetically ordered). The exact
  8. # sorting criteria does not matter as long as it provides the same ordering for subsequent service calls.
  9. #
  10. uint32 entry_index
  11. Path directory_path
  12. ---
  13. Error error
  14. EntryType entry_type
  15. Path entry_full_path # Ignored/Empty if such entry does not exist.

Delete
Full name: uavcan.protocol.file.Delete
Default data type ID: 47

  1. #
  2. # Delete remote file system entry.
  3. # If the remote entry is a directory, all nested entries will be removed too.
  4. #
  5. Path path
  6. ---
  7. Error error

Read
Full name: uavcan.protocol.file.Read
Default data type ID: 48

  1. #
  2. # Read file from a remote node.
  3. #
  4. # There are two possible outcomes of a successful service call:
  5. # 1. Data array size equals its capacity. This means that the end of the file is not reached yet.
  6. # 2. Data array size is less than its capacity, possibly zero. This means that the end of file is reached.
  7. #
  8. # Thus, if the client needs to fetch the entire file, it should repeatedly call this service while increasing the
  9. # offset, until incomplete data is returned.
  10. #
  11. # If the object pointed by 'path' cannot be read (e.g. it is a directory or it does not exist), appropriate error code
  12. # will be returned, and data array will be empty.
  13. #
  14. uint40 offset
  15. Path path
  16. ---
  17. Error error
  18. uint8[<=256] data

Write
Full name: uavcan.protocol.file.Write
Default data type ID: 49

  1. #
  2. # Write into a remote file.
  3. # The server shall place the contents of the field 'data' into the file pointed by 'path' at the offset specified by
  4. # the field 'offset'.
  5. #
  6. # When writing a file, the client should repeatedly call this service with data while advancing offset until the file
  7. # is written completely. When write is complete, the client shall call the service one last time, with the offset
  8. # set to the size of the file and with the data field empty, which will signal the server that the write operation is
  9. # complete.
  10. #
  11. # When the write operation is complete, the server shall truncate the resulting file past the specified offset.
  12. #
  13. # Server implementation advice:
  14. # It is recommended to implement proper handling of concurrent writes to the same file from different clients, for
  15. # example by means of creating a staging area for uncompleted writes (like FTP servers do).
  16. #
  17. uint40 offset
  18. Path path
  19. uint8[<=192] data
  20. ---
  21. Error error

EntryType
Full name: uavcan.protocol.file.EntryType

  1. #
  2. # Nested type.
  3. # Represents the type of the file system entry (e.g. file or directory).
  4. # If such entry does not exist, 'flags' must be set to zero.
  5. #
  6. uint8 FLAG_FILE = 1 # Excludes FLAG_DIRECTORY
  7. uint8 FLAG_DIRECTORY = 2 # Excludes FLAG_FILE
  8. uint8 FLAG_SYMLINK = 4 # Link target is either FLAG_FILE or FLAG_DIRECTORY
  9. uint8 FLAG_READABLE = 8
  10. uint8 FLAG_WRITEABLE = 16
  11. uint8 flags

Error
Full name: uavcan.protocol.file.Error

  1. #
  2. # Nested type.
  3. # File operation result code.
  4. #
  5. int16 OK = 0
  6. int16 UNKNOWN_ERROR = 32767
  7. int16 NOT_FOUND = 2
  8. int16 IO_ERROR = 5
  9. int16 ACCESS_DENIED = 13
  10. int16 IS_DIRECTORY = 21 # I.e. attempt to read/write on a path that points to a directory
  11. int16 INVALID_VALUE = 22 # E.g. file name is not valid for the target file system
  12. int16 FILE_TOO_LARGE = 27
  13. int16 OUT_OF_SPACE = 28
  14. int16 NOT_IMPLEMENTED = 38
  15. int16 value

Path
Full name: uavcan.protocol.file.Path

  1. #
  2. # Nested type.
  3. #
  4. # File system path in UTF8.
  5. #
  6. # The only valid separator is forward slash.
  7. #
  8. uint8 SEPARATOR = '/'
  9. uint8[<=200] path

uavcan.protocol.param

ExecuteOpcode
Full name: uavcan.protocol.param.ExecuteOpcode
Default data type ID: 10

  1. #
  2. # Service to control the node configuration.
  3. #
  4. #
  5. # SAVE operation instructs the remote node to save the current configuration parameters into a non-volatile
  6. # storage. The node may require a restart in order for some changes to take effect.
  7. #
  8. # ERASE operation instructs the remote node to clear its configuration storage and reinitialize the parameters
  9. # with their default values. The node may require a restart in order for some changes to take effect.
  10. #
  11. # Other opcodes may be added in the future (for example, an opcode for switching between multiple configurations).
  12. #
  13. uint8 OPCODE_SAVE = 0 # Save all parameters to non-volatile storage.
  14. uint8 OPCODE_ERASE = 1 # Clear the non-volatile storage; some changes may take effect only after reboot.
  15. uint8 opcode
  16. #
  17. # Reserved, keep zero.
  18. #
  19. int48 argument
  20. ---
  21. #
  22. # If 'ok' (the field below) is true, this value is not used and must be kept zero.
  23. # If 'ok' is false, this value may contain error code. Error code constants may be defined in the future.
  24. #
  25. int48 argument
  26. #
  27. # True if the operation has been performed successfully, false otherwise.
  28. #
  29. bool ok

GetSet
Full name: uavcan.protocol.param.GetSet
Default data type ID: 11

  1. #
  2. # Get or set a parameter by name or by index.
  3. # Note that access by index should only be used to retreive the list of parameters; it is higly
  4. # discouraged to use it for anything else, because persistent ordering is not guaranteed.
  5. #
  6. #
  7. # Index of the parameter starting from 0; ignored if name is nonempty.
  8. # Use index only to retrieve the list of parameters.
  9. # Parameter ordering must be well defined (e.g. alphabetical, or any other stable ordering),
  10. # in order for the index access to work.
  11. #
  12. uint13 index
  13. #
  14. # If set - parameter will be assigned this value, then the new value will be returned.
  15. # If not set - current parameter value will be returned.
  16. # Refer to the definition of Value for details.
  17. #
  18. Value value
  19. #
  20. # Name of the parameter; always preferred over index if nonempty.
  21. #
  22. uint8[<=92] name
  23. ---
  24. void5
  25. #
  26. # Actual parameter value.
  27. #
  28. # For set requests, it should contain the actual parameter value after the set request was
  29. # executed. The objective is to let the client know if the value could not be updated, e.g.
  30. # due to its range violation, etc.
  31. #
  32. # Empty value (and/or empty name) indicates that there is no such parameter.
  33. #
  34. Value value
  35. void5
  36. Value default_value # Optional
  37. void6
  38. NumericValue max_value # Optional, not applicable for bool/string
  39. void6
  40. NumericValue min_value # Optional, not applicable for bool/string
  41. #
  42. # Empty name (and/or empty value) in response indicates that there is no such parameter.
  43. #
  44. uint8[<=92] name

Empty
Full name: uavcan.protocol.param.Empty

  1. #
  2. # Ex nihilo nihil fit.
  3. #

NumericValue
Full name: uavcan.protocol.param.NumericValue

  1. #
  2. # Numeric-only value.
  3. #
  4. # This is a union, which means that this structure can contain either one of the fields below.
  5. # The structure is prefixed with tag - a selector value that indicates which particular field is encoded.
  6. #
  7. @union # Tag is 2 bits long.
  8. Empty empty # Empty field, used to represent an undefined value.
  9. int64 integer_value
  10. float32 real_value

Value
Full name: uavcan.protocol.param.Value

  1. #
  2. # Single parameter value.
  3. #
  4. # This is a union, which means that this structure can contain either one of the fields below.
  5. # The structure is prefixed with tag - a selector value that indicates which particular field is encoded.
  6. #
  7. @union # Tag is 3 bit long, so outer structure has 5-bit prefix to ensure proper alignment
  8. Empty empty # Empty field, used to represent an undefined value.
  9. int64 integer_value
  10. float32 real_value # 32-bit type is used to simplify implementation on low-end systems
  11. uint8 boolean_value # 8-bit value is used for alignment reasons
  12. uint8[<=128] string_value # Length prefix is exactly one byte long, which ensures proper alignment of payload