From 49db8d39006ff86f88dbb90496ad965bebada4bc Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Thu, 24 Oct 2024 11:21:15 +0200 Subject: [PATCH 1/4] msg: add versioning and split into core/aux messages --- msg/CMakeLists.txt | 94 ++++++++++--------- msg/{ => versioned}/ActuatorMotors.msg | 3 + msg/{ => versioned}/ActuatorServos.msg | 3 + msg/{ => versioned}/ArmingCheckReply.msg | 2 + msg/{ => versioned}/ArmingCheckRequest.msg | 2 + msg/{ => versioned}/BatteryStatus.msg | 2 + msg/{ => versioned}/ConfigOverrides.msg | 3 + msg/{ => versioned}/GotoSetpoint.msg | 2 + msg/{ => versioned}/HomePosition.msg | 2 + msg/{ => versioned}/ManualControlSetpoint.msg | 2 + msg/{ => versioned}/ModeCompleted.msg | 3 + .../RegisterExtComponentReply.msg | 2 + .../RegisterExtComponentRequest.msg | 3 + msg/{ => versioned}/TrajectorySetpoint.msg | 2 + .../UnregisterExtComponent.msg | 2 + .../VehicleAngularVelocity.msg | 1 + msg/{ => versioned}/VehicleAttitude.msg | 2 + .../VehicleAttitudeSetpoint.msg | 2 + msg/{ => versioned}/VehicleCommand.msg | 2 + msg/{ => versioned}/VehicleCommandAck.msg | 2 + msg/{ => versioned}/VehicleControlMode.msg | 2 + msg/{ => versioned}/VehicleGlobalPosition.msg | 2 + msg/{ => versioned}/VehicleLandDetected.msg | 2 + msg/{ => versioned}/VehicleLocalPosition.msg | 2 + msg/{ => versioned}/VehicleOdometry.msg | 3 + msg/{ => versioned}/VehicleRatesSetpoint.msg | 2 + msg/{ => versioned}/VehicleStatus.msg | 2 + msg/{ => versioned}/VtolVehicleStatus.msg | 3 + 28 files changed, 110 insertions(+), 44 deletions(-) rename msg/{ => versioned}/ActuatorMotors.msg (95%) rename msg/{ => versioned}/ActuatorServos.msg (92%) rename msg/{ => versioned}/ArmingCheckReply.msg (96%) rename msg/{ => versioned}/ArmingCheckRequest.msg (84%) rename msg/{ => versioned}/BatteryStatus.msg (99%) rename msg/{ => versioned}/ConfigOverrides.msg (95%) rename msg/{ => versioned}/GotoSetpoint.msg (97%) rename msg/{ => versioned}/HomePosition.msg (96%) rename msg/{ => versioned}/ManualControlSetpoint.msg (98%) rename msg/{ => versioned}/ModeCompleted.msg (94%) rename msg/{ => versioned}/RegisterExtComponentReply.msg (93%) rename msg/{ => versioned}/RegisterExtComponentRequest.msg (97%) rename msg/{ => versioned}/TrajectorySetpoint.msg (95%) rename msg/{ => versioned}/UnregisterExtComponent.msg (92%) rename msg/{ => versioned}/VehicleAngularVelocity.msg (94%) rename msg/{ => versioned}/VehicleAttitude.msg (96%) rename msg/{ => versioned}/VehicleAttitudeSetpoint.msg (96%) rename msg/{ => versioned}/VehicleCommand.msg (99%) rename msg/{ => versioned}/VehicleCommandAck.msg (98%) rename msg/{ => versioned}/VehicleControlMode.msg (97%) rename msg/{ => versioned}/VehicleGlobalPosition.msg (98%) rename msg/{ => versioned}/VehicleLandDetected.msg (96%) rename msg/{ => versioned}/VehicleLocalPosition.msg (99%) rename msg/{ => versioned}/VehicleOdometry.msg (97%) rename msg/{ => versioned}/VehicleRatesSetpoint.msg (95%) rename msg/{ => versioned}/VehicleStatus.msg (99%) rename msg/{ => versioned}/VtolVehicleStatus.msg (94%) diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 24f70e12a6ca..4c352876d8ec 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -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 @@ -62,7 +57,6 @@ set(msg_files CellularStatus.msg CollisionConstraints.msg CollisionReport.msg - ConfigOverrides.msg ControlAllocatorStatus.msg Cpuload.msg DatamanRequest.msg @@ -72,31 +66,31 @@ set(msg_files DebugValue.msg DebugVect.msg DifferentialPressure.msg - DistanceSensor.msg DistanceSensorModeChangeRequest.msg + DistanceSensor.msg Ekf2Timestamps.msg EscReport.msg EscStatus.msg EstimatorAidSource1d.msg EstimatorAidSource2d.msg EstimatorAidSource3d.msg - EstimatorBias.msg EstimatorBias3d.msg + EstimatorBias.msg EstimatorEventFlags.msg EstimatorGpsStatus.msg EstimatorInnovations.msg EstimatorSelectorStatus.msg EstimatorSensorBias.msg EstimatorStates.msg - EstimatorStatus.msg EstimatorStatusFlags.msg + EstimatorStatus.msg Event.msg - FigureEightStatus.msg FailsafeFlags.msg FailureDetectorStatus.msg + FigureEightStatus.msg FlightPhaseEstimation.msg - FollowTarget.msg FollowTargetEstimator.msg + FollowTarget.msg FollowTargetStatus.msg FuelTankStatus.msg GeneratorStatus.msg @@ -110,7 +104,6 @@ set(msg_files GimbalManagerSetAttitude.msg GimbalManagerSetManualControl.msg GimbalManagerStatus.msg - GotoSetpoint.msg GpioConfig.msg GpioIn.msg GpioOut.msg @@ -120,7 +113,6 @@ set(msg_files Gripper.msg HealthReport.msg HeaterStatus.msg - HomePosition.msg HoverThrustEstimate.msg InputRc.msg InternalCombustionEngineStatus.msg @@ -136,7 +128,6 @@ set(msg_files LogMessage.msg MagnetometerBiasEstimate.msg MagWorkerData.msg - ManualControlSetpoint.msg ManualControlSwitches.msg MavlinkLog.msg MavlinkTunnel.msg @@ -145,7 +136,6 @@ set(msg_files Mission.msg MissionResult.msg MountOrientation.msg - ModeCompleted.msg NavigatorMissionItem.msg NavigatorStatus.msg NormalizedUnsignedSetpoint.msg @@ -158,9 +148,9 @@ set(msg_files OpenDroneIdSelfId.msg OpenDroneIdSystem.msg OrbitStatus.msg - OrbTest.msg OrbTestLarge.msg OrbTestMedium.msg + OrbTest.msg ParameterResetRequest.msg ParameterSetUsedRequest.msg ParameterSetValueRequest.msg @@ -182,8 +172,6 @@ set(msg_files RateCtrlStatus.msg RcChannels.msg RcParameterMap.msg - RegisterExtComponentReply.msg - RegisterExtComponentRequest.msg RoverAckermannGuidanceStatus.msg RoverAckermannStatus.msg RoverDifferentialGuidanceStatus.msg @@ -196,25 +184,25 @@ set(msg_files RtlStatus.msg RtlTimeEstimate.msg SatelliteInfo.msg - SensorAccel.msg SensorAccelFifo.msg + SensorAccel.msg + SensorAirflow.msg SensorBaro.msg SensorCombined.msg SensorCorrection.msg SensorGnssRelative.msg SensorGps.msg - SensorGyro.msg SensorGyroFft.msg SensorGyroFifo.msg + SensorGyro.msg SensorHygrometer.msg SensorMag.msg SensorOpticalFlow.msg SensorPreflightMag.msg SensorSelection.msg - SensorsStatus.msg SensorsStatusImu.msg + SensorsStatus.msg SensorUwb.msg - SensorAirflow.msg SystemPower.msg TakeoffStatus.msg TaskStackInfo.msg @@ -223,47 +211,59 @@ set(msg_files TiltrotorExtraControls.msg TimesyncStatus.msg TrajectoryBezier.msg - TrajectorySetpoint.msg TrajectoryWaypoint.msg TransponderReport.msg TuneControl.msg UavcanParameterRequest.msg UavcanParameterValue.msg - UlogStream.msg UlogStreamAck.msg - UnregisterExtComponent.msg + UlogStream.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 +315,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 +336,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 +374,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 +396,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 +447,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 +498,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 diff --git a/msg/ActuatorMotors.msg b/msg/versioned/ActuatorMotors.msg similarity index 95% rename from msg/ActuatorMotors.msg rename to msg/versioned/ActuatorMotors.msg index e74566f1f75e..da63a388bb04 100644 --- a/msg/ActuatorMotors.msg +++ b/msg/versioned/ActuatorMotors.msg @@ -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 diff --git a/msg/ActuatorServos.msg b/msg/versioned/ActuatorServos.msg similarity index 92% rename from msg/ActuatorServos.msg rename to msg/versioned/ActuatorServos.msg index 2c7900e8116a..e740f39c8c7d 100644 --- a/msg/ActuatorServos.msg +++ b/msg/versioned/ActuatorServos.msg @@ -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 diff --git a/msg/ArmingCheckReply.msg b/msg/versioned/ArmingCheckReply.msg similarity index 96% rename from msg/ArmingCheckReply.msg rename to msg/versioned/ArmingCheckReply.msg index 589ad1b1cd7d..1a1aaa518379 100644 --- a/msg/ArmingCheckReply.msg +++ b/msg/versioned/ArmingCheckReply.msg @@ -1,3 +1,5 @@ +uint32 MESSAGE_VERSION = 0 + uint64 timestamp # time since system start (microseconds) uint8 request_id diff --git a/msg/ArmingCheckRequest.msg b/msg/versioned/ArmingCheckRequest.msg similarity index 84% rename from msg/ArmingCheckRequest.msg rename to msg/versioned/ArmingCheckRequest.msg index 69e7e85f351b..17c6e4bacd98 100644 --- a/msg/ArmingCheckRequest.msg +++ b/msg/versioned/ArmingCheckRequest.msg @@ -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 diff --git a/msg/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg similarity index 99% rename from msg/BatteryStatus.msg rename to msg/versioned/BatteryStatus.msg index e8651616152f..9838786f3fce 100644 --- a/msg/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -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 diff --git a/msg/ConfigOverrides.msg b/msg/versioned/ConfigOverrides.msg similarity index 95% rename from msg/ConfigOverrides.msg rename to msg/versioned/ConfigOverrides.msg index 09b87253a8f3..b274adfbecd7 100644 --- a/msg/ConfigOverrides.msg +++ b/msg/versioned/ConfigOverrides.msg @@ -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) diff --git a/msg/GotoSetpoint.msg b/msg/versioned/GotoSetpoint.msg similarity index 97% rename from msg/GotoSetpoint.msg rename to msg/versioned/GotoSetpoint.msg index 5fe3ab8a7916..4871a3cb7d56 100644 --- a/msg/GotoSetpoint.msg +++ b/msg/versioned/GotoSetpoint.msg @@ -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 diff --git a/msg/HomePosition.msg b/msg/versioned/HomePosition.msg similarity index 96% rename from msg/HomePosition.msg rename to msg/versioned/HomePosition.msg index e6a517285fe4..a25bf241636e 100644 --- a/msg/HomePosition.msg +++ b/msg/versioned/HomePosition.msg @@ -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 diff --git a/msg/ManualControlSetpoint.msg b/msg/versioned/ManualControlSetpoint.msg similarity index 98% rename from msg/ManualControlSetpoint.msg rename to msg/versioned/ManualControlSetpoint.msg index 95fa62228344..ddf902f00f7d 100644 --- a/msg/ManualControlSetpoint.msg +++ b/msg/versioned/ManualControlSetpoint.msg @@ -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) diff --git a/msg/ModeCompleted.msg b/msg/versioned/ModeCompleted.msg similarity index 94% rename from msg/ModeCompleted.msg rename to msg/versioned/ModeCompleted.msg index 0a20b0294e53..1022df36d364 100644 --- a/msg/ModeCompleted.msg +++ b/msg/versioned/ModeCompleted.msg @@ -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) diff --git a/msg/RegisterExtComponentReply.msg b/msg/versioned/RegisterExtComponentReply.msg similarity index 93% rename from msg/RegisterExtComponentReply.msg rename to msg/versioned/RegisterExtComponentReply.msg index 7cd7eef07b2b..4495bcdb90b5 100644 --- a/msg/RegisterExtComponentReply.msg +++ b/msg/versioned/RegisterExtComponentReply.msg @@ -1,3 +1,5 @@ +uint32 MESSAGE_VERSION = 0 + uint64 timestamp # time since system start (microseconds) uint64 request_id # ID from the request diff --git a/msg/RegisterExtComponentRequest.msg b/msg/versioned/RegisterExtComponentRequest.msg similarity index 97% rename from msg/RegisterExtComponentRequest.msg rename to msg/versioned/RegisterExtComponentRequest.msg index 46ab0cb0a15d..b0798705ca30 100644 --- a/msg/RegisterExtComponentRequest.msg +++ b/msg/versioned/RegisterExtComponentRequest.msg @@ -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 diff --git a/msg/TrajectorySetpoint.msg b/msg/versioned/TrajectorySetpoint.msg similarity index 95% rename from msg/TrajectorySetpoint.msg rename to msg/versioned/TrajectorySetpoint.msg index 4a88c86769a6..150be404b94f 100644 --- a/msg/TrajectorySetpoint.msg +++ b/msg/versioned/TrajectorySetpoint.msg @@ -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 diff --git a/msg/UnregisterExtComponent.msg b/msg/versioned/UnregisterExtComponent.msg similarity index 92% rename from msg/UnregisterExtComponent.msg rename to msg/versioned/UnregisterExtComponent.msg index 2ad78d4b6836..8f85aaebfe4c 100644 --- a/msg/UnregisterExtComponent.msg +++ b/msg/versioned/UnregisterExtComponent.msg @@ -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 diff --git a/msg/VehicleAngularVelocity.msg b/msg/versioned/VehicleAngularVelocity.msg similarity index 94% rename from msg/VehicleAngularVelocity.msg rename to msg/versioned/VehicleAngularVelocity.msg index db3767c0aa80..6c91f3c0703e 100644 --- a/msg/VehicleAngularVelocity.msg +++ b/msg/versioned/VehicleAngularVelocity.msg @@ -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) diff --git a/msg/VehicleAttitude.msg b/msg/versioned/VehicleAttitude.msg similarity index 96% rename from msg/VehicleAttitude.msg rename to msg/versioned/VehicleAttitude.msg index 99e6f25c2e42..fde3a85546c7 100644 --- a/msg/VehicleAttitude.msg +++ b/msg/versioned/VehicleAttitude.msg @@ -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) diff --git a/msg/VehicleAttitudeSetpoint.msg b/msg/versioned/VehicleAttitudeSetpoint.msg similarity index 96% rename from msg/VehicleAttitudeSetpoint.msg rename to msg/versioned/VehicleAttitudeSetpoint.msg index 74a753023df5..28aa780699dc 100644 --- a/msg/VehicleAttitudeSetpoint.msg +++ b/msg/versioned/VehicleAttitudeSetpoint.msg @@ -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) diff --git a/msg/VehicleCommand.msg b/msg/versioned/VehicleCommand.msg similarity index 99% rename from msg/VehicleCommand.msg rename to msg/versioned/VehicleCommand.msg index 2970410a886e..96162e9f89f9 100644 --- a/msg/VehicleCommand.msg +++ b/msg/versioned/VehicleCommand.msg @@ -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 diff --git a/msg/VehicleCommandAck.msg b/msg/versioned/VehicleCommandAck.msg similarity index 98% rename from msg/VehicleCommandAck.msg rename to msg/versioned/VehicleCommandAck.msg index 6f54fa46315b..c11a5f8c5dfd 100644 --- a/msg/VehicleCommandAck.msg +++ b/msg/versioned/VehicleCommandAck.msg @@ -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 diff --git a/msg/VehicleControlMode.msg b/msg/versioned/VehicleControlMode.msg similarity index 97% rename from msg/VehicleControlMode.msg rename to msg/versioned/VehicleControlMode.msg index 9b33f9b8cad3..0a1fdedfbf14 100644 --- a/msg/VehicleControlMode.msg +++ b/msg/versioned/VehicleControlMode.msg @@ -1,3 +1,5 @@ +uint32 MESSAGE_VERSION = 0 + uint64 timestamp # time since system start (microseconds) bool flag_armed # synonym for actuator_armed.armed diff --git a/msg/VehicleGlobalPosition.msg b/msg/versioned/VehicleGlobalPosition.msg similarity index 98% rename from msg/VehicleGlobalPosition.msg rename to msg/versioned/VehicleGlobalPosition.msg index 30aaf5652a96..387576d8c792 100644 --- a/msg/VehicleGlobalPosition.msg +++ b/msg/versioned/VehicleGlobalPosition.msg @@ -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) diff --git a/msg/VehicleLandDetected.msg b/msg/versioned/VehicleLandDetected.msg similarity index 96% rename from msg/VehicleLandDetected.msg rename to msg/versioned/VehicleLandDetected.msg index fc0ca4a6d81c..1cbf54571360 100644 --- a/msg/VehicleLandDetected.msg +++ b/msg/versioned/VehicleLandDetected.msg @@ -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 diff --git a/msg/VehicleLocalPosition.msg b/msg/versioned/VehicleLocalPosition.msg similarity index 99% rename from msg/VehicleLocalPosition.msg rename to msg/versioned/VehicleLocalPosition.msg index 0e74ac0f4bfc..aec6311ab383 100644 --- a/msg/VehicleLocalPosition.msg +++ b/msg/versioned/VehicleLocalPosition.msg @@ -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) diff --git a/msg/VehicleOdometry.msg b/msg/versioned/VehicleOdometry.msg similarity index 97% rename from msg/VehicleOdometry.msg rename to msg/versioned/VehicleOdometry.msg index fbdd1920e1b4..f4d600d2b81e 100644 --- a/msg/VehicleOdometry.msg +++ b/msg/versioned/VehicleOdometry.msg @@ -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 diff --git a/msg/VehicleRatesSetpoint.msg b/msg/versioned/VehicleRatesSetpoint.msg similarity index 95% rename from msg/VehicleRatesSetpoint.msg rename to msg/versioned/VehicleRatesSetpoint.msg index 35a06c35aa5f..a4c169e4123c 100644 --- a/msg/VehicleRatesSetpoint.msg +++ b/msg/versioned/VehicleRatesSetpoint.msg @@ -1,3 +1,5 @@ +uint32 MESSAGE_VERSION = 0 + uint64 timestamp # time since system start (microseconds) # body angular rates in FRD frame diff --git a/msg/VehicleStatus.msg b/msg/versioned/VehicleStatus.msg similarity index 99% rename from msg/VehicleStatus.msg rename to msg/versioned/VehicleStatus.msg index 6756da812977..a347dfce3d9d 100644 --- a/msg/VehicleStatus.msg +++ b/msg/versioned/VehicleStatus.msg @@ -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) diff --git a/msg/VtolVehicleStatus.msg b/msg/versioned/VtolVehicleStatus.msg similarity index 94% rename from msg/VtolVehicleStatus.msg rename to msg/versioned/VtolVehicleStatus.msg index 61a8246796f1..51beb30fa307 100644 --- a/msg/VtolVehicleStatus.msg +++ b/msg/versioned/VtolVehicleStatus.msg @@ -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 From 2031ba07c3ae5657e094bfdbfa224c5ad6374b78 Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Thu, 31 Oct 2024 13:15:42 +0100 Subject: [PATCH 2/4] tools: update scripts after msg/ restructure --- Tools/msg/generate_msg_docs.py | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/Tools/msg/generate_msg_docs.py b/Tools/msg/generate_msg_docs.py index a44a317b5279..e097e79672e0 100755 --- a/Tools/msg/generate_msg_docs.py +++ b/Tools/msg/generate_msg_docs.py @@ -11,9 +11,22 @@ def get_msgs_list(msgdir): """ - Makes list of msg files in the given directory + Makes a list of relative paths of .msg files in the given directory + and its subdirectories. + + Parameters: + msgdir (str): The directory to search for .msg files. + + Returns: + list: A list of relative paths to .msg files. """ - return [fn for fn in os.listdir(msgdir) if fn.endswith(".msg")] + msgs = [] + for root, _, files in os.walk(msgdir): + for fn in files: + if fn.endswith(".msg"): + relative_path = os.path.relpath(os.path.join(root, fn), msgdir) + msgs.append(relative_path) + return msgs if __name__ == "__main__": @@ -32,7 +45,7 @@ def get_msgs_list(msgdir): filelist_in_markdown='' for msg_file in msg_files: - msg_name = os.path.splitext(msg_file)[0] + msg_name = os.path.splitext(os.path.basename(msg_file))[0] output_file = os.path.join(output_dir, msg_name+'.md') msg_filename = os.path.join(msg_path, msg_file) print("{:} -> {:}".format(msg_filename, output_file)) From 202c357a7d7c969bb0c07cfe608b320ac1377f72 Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Thu, 31 Oct 2024 13:29:46 +0100 Subject: [PATCH 3/4] jenkins: update after msg/ restructure --- Jenkinsfile | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Jenkinsfile b/Jenkinsfile index d7f166b5fe4d..e69d5b65a650 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -231,8 +231,10 @@ pipeline { sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_msgs.git") // 'main' branch sh('rm -f px4_msgs/msg/*.msg') + sh('rm -f px4_msgs/msg/versioned/*.msg') sh('rm -f px4_msgs/srv/*.srv') sh('cp msg/*.msg px4_msgs/msg/') + sh('cp msg/versioned/*.msg px4_msgs/versioned/msg/') sh('cp srv/*.srv px4_msgs/srv/') sh('cd px4_msgs; git status; git add .; git commit -a -m "Update message definitions `date`" || true') sh('cd px4_msgs; git push origin main || true') From b8636fde6b8b0925ef96ad1ef45c2102030f043e Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Thu, 31 Oct 2024 14:05:47 +0100 Subject: [PATCH 4/4] suffle msgs to original position --- msg/CMakeLists.txt | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 4c352876d8ec..73d2695f1706 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -66,31 +66,31 @@ set(msg_files DebugValue.msg DebugVect.msg DifferentialPressure.msg - DistanceSensorModeChangeRequest.msg DistanceSensor.msg + DistanceSensorModeChangeRequest.msg Ekf2Timestamps.msg EscReport.msg EscStatus.msg EstimatorAidSource1d.msg EstimatorAidSource2d.msg EstimatorAidSource3d.msg - EstimatorBias3d.msg EstimatorBias.msg + EstimatorBias3d.msg EstimatorEventFlags.msg EstimatorGpsStatus.msg EstimatorInnovations.msg EstimatorSelectorStatus.msg EstimatorSensorBias.msg EstimatorStates.msg - EstimatorStatusFlags.msg EstimatorStatus.msg + EstimatorStatusFlags.msg Event.msg + FigureEightStatus.msg FailsafeFlags.msg FailureDetectorStatus.msg - FigureEightStatus.msg FlightPhaseEstimation.msg - FollowTargetEstimator.msg FollowTarget.msg + FollowTargetEstimator.msg FollowTargetStatus.msg FuelTankStatus.msg GeneratorStatus.msg @@ -148,9 +148,9 @@ set(msg_files OpenDroneIdSelfId.msg OpenDroneIdSystem.msg OrbitStatus.msg + OrbTest.msg OrbTestLarge.msg OrbTestMedium.msg - OrbTest.msg ParameterResetRequest.msg ParameterSetUsedRequest.msg ParameterSetValueRequest.msg @@ -184,25 +184,25 @@ set(msg_files RtlStatus.msg RtlTimeEstimate.msg SatelliteInfo.msg - SensorAccelFifo.msg SensorAccel.msg - SensorAirflow.msg + SensorAccelFifo.msg SensorBaro.msg SensorCombined.msg SensorCorrection.msg SensorGnssRelative.msg SensorGps.msg + SensorGyro.msg SensorGyroFft.msg SensorGyroFifo.msg - SensorGyro.msg SensorHygrometer.msg SensorMag.msg SensorOpticalFlow.msg SensorPreflightMag.msg SensorSelection.msg - SensorsStatusImu.msg SensorsStatus.msg + SensorsStatusImu.msg SensorUwb.msg + SensorAirflow.msg SystemPower.msg TakeoffStatus.msg TaskStackInfo.msg @@ -216,8 +216,8 @@ set(msg_files TuneControl.msg UavcanParameterRequest.msg UavcanParameterValue.msg - UlogStreamAck.msg UlogStream.msg + UlogStreamAck.msg VehicleAcceleration.msg VehicleAirData.msg VehicleAngularAccelerationSetpoint.msg