Clarification of coordinate systems for sensors_* and vehicle_* messages (#16339)

Changed all 'NED' references to 'FRD'. Also cleaned up mixing of m/s/s and m/s^2 to use the latter. Corrected m/s/s to Pascals. Plus minor typos. Also made some minor cosmetic clean ups.

Co-authored-by: Robin <robin@Robins-MacBook-Pro-Work.local>
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
This commit is contained in:
Robin Lilja 2020-12-15 09:18:05 +01:00 committed by GitHub
parent fdd1d6d244
commit aa244a098c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
17 changed files with 46 additions and 46 deletions

View File

@ -3,11 +3,11 @@ uint64 timestamp_sample
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32 x # acceleration in the NED X board axis in m/s^2
float32 y # acceleration in the NED Y board axis in m/s^2
float32 z # acceleration in the NED Z board axis in m/s^2
float32 x # acceleration in the FRD board frame X-axis in m/s^2
float32 y # acceleration in the FRD board frame Y-axis in m/s^2
float32 z # acceleration in the FRD board frame Z-axis in m/s^2
float32 temperature # temperature in degrees celsius
float32 temperature # temperature in degrees Celsius
uint32 error_count

View File

@ -8,8 +8,8 @@ float32 scale
uint8 samples # number of valid samples
int16[32] x # acceleration in the NED X board axis in m/s/s
int16[32] y # acceleration in the NED Y board axis in m/s/s
int16[32] z # acceleration in the NED Z board axis in m/s/s
int16[32] x # acceleration in the FRD board frame X-axis in m/s^2
int16[32] y # acceleration in the FRD board frame Y-axis in m/s^2
int16[32] z # acceleration in the FRD board frame Z-axis in m/s^2
uint8 rotation # Direction the sensor faces (see Rotation enum)

View File

@ -7,4 +7,4 @@ uint32 error_count
float32 pressure # static pressure measurement in millibar
float32 temperature # static temperature measurement in deg C
float32 temperature # static temperature measurement in deg Celsius

View File

@ -7,12 +7,12 @@ uint64 timestamp # time since system start (microseconds)
int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid
# gyro timstamp is equal to the timestamp of the message
float32[3] gyro_rad # average angular rate measured in the XYZ body frame in rad/s over the last gyro sampling period
uint32 gyro_integral_dt # gyro measurement sampling period in us
float32[3] gyro_rad # average angular rate measured in the FRD body frame XYZ-axis in rad/s over the last gyro sampling period
uint32 gyro_integral_dt # gyro measurement sampling period in microseconds
int32 accelerometer_timestamp_relative # timestamp + accelerometer_timestamp_relative = Accelerometer timestamp
float32[3] accelerometer_m_s2 # average value acceleration measured in the XYZ body frame in m/s/s over the last accelerometer sampling period
uint32 accelerometer_integral_dt # accelerometer measurement sampling period in us
float32[3] accelerometer_m_s2 # average value acceleration measured in the FRD body frame XYZ-axis in m/s^2 over the last accelerometer sampling period
uint32 accelerometer_integral_dt # accelerometer measurement sampling period in microseconds
uint8 CLIPPING_X = 1
uint8 CLIPPING_Y = 2

View File

@ -15,15 +15,15 @@ float32[3] gyro_offset_3 # gyro 3 XYZ offsets in the sensor frame in rad/s
# Corrections for acceleromter acceleration outputs where corrected_accel = raw_accel * accel_scale + accel_offset
# Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame
uint32[4] accel_device_ids
float32[3] accel_offset_0 # accelerometer 0 XYZ offsets in the sensor frame in m/s/s
float32[3] accel_offset_1 # accelerometer 1 XYZ offsets in the sensor frame in m/s/s
float32[3] accel_offset_2 # accelerometer 2 XYZ offsets in the sensor frame in m/s/s
float32[3] accel_offset_3 # accelerometer 3 XYZ offsets in the sensor frame in m/s/s
float32[3] accel_offset_0 # accelerometer 0 offsets in the FRD board frame XYZ-axis in m/s^s
float32[3] accel_offset_1 # accelerometer 1 offsets in the FRD board frame XYZ-axis in m/s^s
float32[3] accel_offset_2 # accelerometer 2 offsets in the FRD board frame XYZ-axis in m/s^s
float32[3] accel_offset_3 # accelerometer 3 offsets in the FRD board frame XYZ-axis in m/s^s
# Corrections for barometric pressure outputs where corrected_pressure = raw_pressure * pressure_scale + pressure_offset
# Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame
uint32[4] baro_device_ids
float32 baro_offset_0 # barometric pressure 0 offsets in the sensor frame in m/s/s
float32 baro_offset_1 # barometric pressure 1 offsets in the sensor frame in m/s/s
float32 baro_offset_2 # barometric pressure 2 offsets in the sensor frame in m/s/s
float32 baro_offset_3 # barometric pressure 3 offsets in the sensor frame in m/s/s
float32 baro_offset_0 # barometric pressure 0 offsets in the sensor frame in Pascals
float32 baro_offset_1 # barometric pressure 1 offsets in the sensor frame in Pascals
float32 baro_offset_2 # barometric pressure 2 offsets in the sensor frame in Pascals
float32 baro_offset_3 # barometric pressure 3 offsets in the sensor frame in Pascals

View File

@ -3,11 +3,11 @@ uint64 timestamp_sample
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32 x # angular velocity in the NED X board axis in rad/s
float32 y # angular velocity in the NED Y board axis in rad/s
float32 z # angular velocity in the NED Z board axis in rad/s
float32 x # angular velocity in the FRD board frame X-axis in rad/s
float32 y # angular velocity in the FRD board frame Y-axis in rad/s
float32 z # angular velocity in the FRD board frame Z-axis in rad/s
float32 temperature # temperature in degrees celsius
float32 temperature # temperature in degrees Celsius
uint32 error_count

View File

@ -8,8 +8,8 @@ float32 scale
uint8 samples # number of valid samples
int16[32] x # angular velocity in the NED X board axis in rad/s
int16[32] y # angular velocity in the NED Y board axis in rad/s
int16[32] z # angular velocity in the NED Z board axis in rad/s
int16[32] x # angular velocity in the FRD board frame X-axis in rad/s
int16[32] y # angular velocity in the FRD board frame Y-axis in rad/s
int16[32] z # angular velocity in the FRD board frame Z-axis in rad/s
uint8 rotation # Direction the sensor faces (see Rotation enum)

View File

@ -3,11 +3,11 @@ uint64 timestamp_sample
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32 x # magnetic field in the NED X board axis in Gauss
float32 y # magnetic field in the NED Y board axis in Gauss
float32 z # magnetic field in the NED Z board axis in Gauss
float32 x # magnetic field in the FRD board frame X-axis in Gauss
float32 y # magnetic field in the FRD board frame Y-axis in Gauss
float32 z # magnetic field in the FRD board frame Z-axis in Gauss
float32 temperature # temperature in degrees celsius
float32 temperature # temperature in degrees Celsius
uint32 error_count

View File

@ -6,7 +6,7 @@ uint64 timestamp # time since system start (microseconds)
uint32 accel_device_id_primary # current primary accel device id for reference
uint32[4] accel_device_ids
float32[4] accel_inconsistency_m_s_s # magnitude of acceleration difference between IMU instance and mean in (m/s/s).
float32[4] accel_inconsistency_m_s_s # magnitude of acceleration difference between IMU instance and mean in m/s^2.
bool[4] accel_healthy

View File

@ -7,7 +7,7 @@ uint8 brick_valid # brick bits power is good when bit 1
uint8 usb_valid # USB is valid when 1
uint8 servo_valid # servo power is good when 1
uint8 periph_5v_oc # peripheral overcurrent when 1
uint8 hipower_5v_oc # hi power peripheral overcurrent when 1
uint8 hipower_5v_oc # high power peripheral overcurrent when 1
uint8 BRICK1_VALID_SHIFTS=0
uint8 BRICK1_VALID_MASK=1

View File

@ -3,4 +3,4 @@ uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
float32[3] xyz # Bias corrected acceleration (including gravity) in body axis (in m/s^2)
float32[3] xyz # Bias corrected acceleration (including gravity) in the FRD body frame XYZ-axis in m/s^2

View File

@ -6,7 +6,7 @@ uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint32 baro_device_id # unique device ID for the selected barometer
float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH.
float32 baro_temp_celcius # Temperature in degrees celsius
float32 baro_pressure_pa # Absolute pressure in pascals
float32 baro_temp_celcius # Temperature in degrees Celsius
float32 baro_pressure_pa # Absolute pressure in Pascals
float32 rho # air density

View File

@ -2,4 +2,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds)
float32[3] xyz # angular acceleration about X, Y, Z body axis in rad/s^2,
float32[3] xyz # angular acceleration about the FRD body frame XYZ-axis in rad/s^2

View File

@ -2,6 +2,6 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds)
float32[3] xyz # Bias corrected angular velocity about X, Y, Z body axis in rad/s
float32[3] xyz # Bias corrected angular velocity about the FRD body frame XYZ-axis in rad/s
# TOPICS vehicle_angular_velocity vehicle_angular_velocity_groundtruth

View File

@ -1,10 +1,10 @@
# This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
float32[4] q # Quaternion rotation from XYZ body frame to NED earth frame.
float32[4] q # Quaternion rotation from the FRD body frame to the NED earth frame
float32[4] delta_q_reset # Amount by which quaternion has changed during last reset
uint8 quat_reset_counter # Quaternion reset counter

View File

@ -6,10 +6,10 @@ uint64 timestamp_sample
uint32 accel_device_id # Accelerometer unique device ID for the sensor that does not change between power cycles
uint32 gyro_device_id # Gyroscope unique device ID for the sensor that does not change between power cycles
float32[3] delta_angle # delta angle in the NED board axis in rad/s over the integration time frame (dt)
float32[3] delta_velocity # delta velocity in the NED board axis in m/s over the integration time frame (dt)
uint16 delta_angle_dt # integration period in us
uint16 delta_velocity_dt # integration period in us
float32[3] delta_angle # delta angle about the FRD body frame XYZ-axis in rad over the integration time frame (delta_angle_dt)
float32[3] delta_velocity # delta velocity in the FRD body frame XYZ-axis in m/s over the integration time frame (delta_velocity_dt)
uint16 delta_angle_dt # integration period in microseconds
uint16 delta_velocity_dt # integration period in microseconds
uint8 CLIPPING_X = 1
uint8 CLIPPING_Y = 2

View File

@ -5,6 +5,6 @@ uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint32 device_id # unique device ID for the selected magnetometer
float32[3] magnetometer_ga # Magnetic field in NED body frame, in Gauss
float32[3] magnetometer_ga # Magnetic field in the FRD body frame XYZ-axis in Gauss
uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes.