msg: introduce message versioning

This commit is contained in:
GuillaumeLaine 2024-10-24 11:21:15 +02:00 committed by Beat Küng
parent f9140fcd50
commit 4fe7d713d3
28 changed files with 100 additions and 33 deletions

View File

@ -40,19 +40,14 @@ set(msg_files
ActionRequest.msg
ActuatorArmed.msg
ActuatorControlsStatus.msg
ActuatorMotors.msg
ActuatorOutputs.msg
ActuatorServos.msg
ActuatorServosTrim.msg
ActuatorTest.msg
AdcReport.msg
Airspeed.msg
AirspeedValidated.msg
AirspeedWind.msg
ArmingCheckReply.msg
ArmingCheckRequest.msg
AutotuneAttitudeControlStatus.msg
BatteryStatus.msg
Buffer128.msg
ButtonEvent.msg
CameraCapture.msg
@ -61,7 +56,7 @@ set(msg_files
CanInterfaceStatus.msg
CellularStatus.msg
CollisionConstraints.msg
ConfigOverrides.msg
CollisionReport.msg
ControlAllocatorStatus.msg
Cpuload.msg
DatamanRequest.msg
@ -109,7 +104,6 @@ set(msg_files
GimbalManagerSetAttitude.msg
GimbalManagerSetManualControl.msg
GimbalManagerStatus.msg
GotoSetpoint.msg
GpioConfig.msg
GpioIn.msg
GpioOut.msg
@ -119,7 +113,6 @@ set(msg_files
Gripper.msg
HealthReport.msg
HeaterStatus.msg
HomePosition.msg
HoverThrustEstimate.msg
InputRc.msg
InternalCombustionEngineStatus.msg
@ -135,7 +128,6 @@ set(msg_files
LogMessage.msg
MagnetometerBiasEstimate.msg
MagWorkerData.msg
ManualControlSetpoint.msg
ManualControlSwitches.msg
MavlinkLog.msg
MavlinkTunnel.msg
@ -144,7 +136,6 @@ set(msg_files
Mission.msg
MissionResult.msg
MountOrientation.msg
ModeCompleted.msg
NavigatorMissionItem.msg
NavigatorStatus.msg
NormalizedUnsignedSetpoint.msg
@ -181,8 +172,6 @@ set(msg_files
RateCtrlStatus.msg
RcChannels.msg
RcParameterMap.msg
RegisterExtComponentReply.msg
RegisterExtComponentRequest.msg
RoverAckermannGuidanceStatus.msg
RoverAckermannSetpoint.msg
RoverAckermannStatus.msg
@ -223,7 +212,6 @@ set(msg_files
TiltrotorExtraControls.msg
TimesyncStatus.msg
TrajectoryBezier.msg
TrajectorySetpoint.msg
TrajectoryWaypoint.msg
TransponderReport.msg
TuneControl.msg
@ -231,39 +219,52 @@ set(msg_files
UavcanParameterValue.msg
UlogStream.msg
UlogStreamAck.msg
UnregisterExtComponent.msg
VehicleAcceleration.msg
VehicleAirData.msg
VehicleAngularAccelerationSetpoint.msg
VehicleAngularVelocity.msg
VehicleAttitude.msg
VehicleAttitudeSetpoint.msg
VehicleCommand.msg
VehicleCommandAck.msg
VehicleConstraints.msg
VehicleControlMode.msg
VehicleGlobalPosition.msg
VehicleImu.msg
VehicleImuStatus.msg
VehicleLandDetected.msg
VehicleLocalPosition.msg
VehicleLocalPositionSetpoint.msg
VehicleMagnetometer.msg
VehicleOdometry.msg
VehicleOpticalFlow.msg
VehicleOpticalFlowVel.msg
VehicleRatesSetpoint.msg
VehicleRoi.msg
VehicleStatus.msg
VehicleThrustSetpoint.msg
VehicleTorqueSetpoint.msg
VehicleTrajectoryBezier.msg
VehicleTrajectoryWaypoint.msg
VelocityLimits.msg
VtolVehicleStatus.msg
WheelEncoders.msg
Wind.msg
YawEstimatorStatus.msg
versioned/ActuatorMotors.msg
versioned/ActuatorServos.msg
versioned/ArmingCheckReply.msg
versioned/ArmingCheckRequest.msg
versioned/BatteryStatus.msg
versioned/ConfigOverrides.msg
versioned/GotoSetpoint.msg
versioned/HomePosition.msg
versioned/ManualControlSetpoint.msg
versioned/ModeCompleted.msg
versioned/RegisterExtComponentReply.msg
versioned/RegisterExtComponentRequest.msg
versioned/TrajectorySetpoint.msg
versioned/UnregisterExtComponent.msg
versioned/VehicleAngularVelocity.msg
versioned/VehicleAttitude.msg
versioned/VehicleAttitudeSetpoint.msg
versioned/VehicleCommandAck.msg
versioned/VehicleCommand.msg
versioned/VehicleControlMode.msg
versioned/VehicleGlobalPosition.msg
versioned/VehicleLandDetected.msg
versioned/VehicleLocalPosition.msg
versioned/VehicleOdometry.msg
versioned/VehicleRatesSetpoint.msg
versioned/VehicleStatus.msg
versioned/VtolVehicleStatus.msg
)
list(SORT msg_files)
@ -315,7 +316,7 @@ add_custom_command(
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/msg/px_generate_uorb_topic_files.py
--headers
-f ${msg_files}
-i ${CMAKE_CURRENT_SOURCE_DIR}
-i ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/versioned
-o ${msg_out_path}
-e ${PX4_SOURCE_DIR}/Tools/msg/templates/uorb
DEPENDS
@ -336,7 +337,7 @@ add_custom_command(
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/msg/px_generate_uorb_topic_files.py
--json
-f ${msg_files}
-i ${CMAKE_CURRENT_SOURCE_DIR}
-i ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/versioned
-o ${msg_source_out_path}
-e ${PX4_SOURCE_DIR}/Tools/msg/templates/uorb
DEPENDS
@ -374,7 +375,7 @@ add_custom_command(
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/msg/px_generate_uorb_topic_files.py
--headers
-f ${msg_files}
-i ${CMAKE_CURRENT_SOURCE_DIR}
-i ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/versioned
-o ${ucdr_out_path}
-e ${PX4_SOURCE_DIR}/Tools/msg/templates/ucdr
DEPENDS
@ -396,7 +397,7 @@ add_custom_command(
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/msg/px_generate_uorb_topic_files.py
--sources
-f ${msg_files}
-i ${CMAKE_CURRENT_SOURCE_DIR}
-i ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/versioned
-o ${msg_source_out_path}
-e ${PX4_SOURCE_DIR}/Tools/msg/templates/uorb
DEPENDS
@ -447,7 +448,13 @@ if(CONFIG_LIB_CDRSTREAM)
# Copy .msg files
foreach(msg_file ${msg_files})
get_filename_component(msg ${msg_file} NAME_WE)
configure_file(${PX4_SOURCE_DIR}/msg/${msg}.msg ${idl_out_path}/${msg}.msg COPYONLY)
get_filename_component(msg_directory ${msg_file} DIRECTORY)
get_filename_component(msg_directory ${msg_directory} NAME)
if(msg_directory STREQUAL "versioned")
configure_file(${PX4_SOURCE_DIR}/msg/${msg_directory}/${msg}.msg ${idl_out_path}/${msg}.msg COPYONLY)
else()
configure_file(${PX4_SOURCE_DIR}/msg/${msg}.msg ${idl_out_path}/${msg}.msg COPYONLY)
endif()
list(APPEND uorb_cdr_idl ${idl_out_path}/${msg}.idl)
list(APPEND uorb_cdr_msg ${idl_out_path}/${msg}.msg)
list(APPEND uorb_cdr_idl_uorb ${idl_uorb_path}/${msg}.h)
@ -492,7 +499,7 @@ if(CONFIG_LIB_CDRSTREAM)
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/msg/px_generate_uorb_topic_files.py
--uorb-idl-header
-f ${msg_files}
-i ${CMAKE_CURRENT_SOURCE_DIR}
-i ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/versioned
-o ${idl_uorb_path}
-e ${PX4_SOURCE_DIR}/Tools/msg/templates/cdrstream
DEPENDS

View File

@ -1,4 +1,7 @@
# Motor control message
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled

View File

@ -1,4 +1,7 @@
# Servo control message
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint8 request_id

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
# broadcast message to request all registered arming checks to be reported

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
bool connected # Whether or not a battery is connected, based on a voltage threshold
float32 voltage_v # Battery voltage in volts, 0 if unknown

View File

@ -1,4 +1,7 @@
# Configurable overrides by (external) modes or mode executors
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
bool disable_auto_disarm # Prevent the drone from automatically disarming after landing (if configured)

View File

@ -5,6 +5,8 @@
# Unset optional setpoints are not controlled
# Unset optional constraints default to vehicle specifications
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
# setpoints

View File

@ -1,5 +1,7 @@
# GPS home position in WGS84 coordinates.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
float64 lat # Latitude in degrees

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)

View File

@ -2,6 +2,9 @@
# The possible values of nav_state are defined in the VehicleStatus msg.
# Note that this is not always published (e.g. when a user switches modes or on
# failsafe activation)
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 request_id # ID from the request

View File

@ -1,4 +1,7 @@
# Request to register an external component
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 request_id # ID, set this to a random value

View File

@ -3,6 +3,8 @@
# Needs to be kinematically consistent and feasible for smooth flight.
# setting a value to NaN means the state should not be controlled
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
# NED local world frame

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
char[25] name # either the mode name, or component name

View File

@ -1,3 +1,4 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds)

View File

@ -1,6 +1,8 @@
# This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use
# The quaternion uses the Hamilton convention, and the order is q(w, x, y, z)
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
float32 yaw_sp_move_rate # rad/s (commanded by user)

View File

@ -1,6 +1,8 @@
# Vehicle Command uORB message. Used for commanding a mission / action / etc.
# Follows the MAVLink COMMAND_INT / COMMAND_LONG definition
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command

View File

@ -2,6 +2,8 @@
# Used for acknowledging the vehicle command being received.
# Follows the MAVLink COMMAND_ACK message definition
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
# Result cases. This follows the MAVLink MAV_RESULT enum definition

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
bool flag_armed # synonym for actuator_armed.armed

View File

@ -5,6 +5,8 @@
# e.g. control inputs of the vehicle in a Kalman-filter implementation.
#
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
bool freefall # true if vehicle is currently in free-fall

View File

@ -1,6 +1,8 @@
# Fused local position in NED.
# The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)

View File

@ -1,4 +1,7 @@
# Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample

View File

@ -1,3 +1,5 @@
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
# body angular rates in FRD frame

View File

@ -1,5 +1,7 @@
# Encodes the system state of the vehicle published by commander
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 armed_time # Arming timestamp (microseconds)

View File

@ -1,4 +1,7 @@
# VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE
uint32 MESSAGE_VERSION = 0
uint8 VEHICLE_VTOL_STATE_UNDEFINED = 0
uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_FW = 1
uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2