|
|
|
@ -281,8 +281,9 @@ static_assert(sizeof(log_ISBD) < 256, "log_ISBD is over-size");
@@ -281,8 +281,9 @@ static_assert(sizeof(log_ISBD) < 256, "log_ISBD is over-size");
|
|
|
|
|
struct PACKED log_Vibe { |
|
|
|
|
LOG_PACKET_HEADER; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
uint8_t imu; |
|
|
|
|
float vibe_x, vibe_y, vibe_z; |
|
|
|
|
uint32_t clipping_0, clipping_1, clipping_2; |
|
|
|
|
uint32_t clipping; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct PACKED log_RCIN { |
|
|
|
@ -2238,12 +2239,11 @@ struct PACKED log_PSC {
@@ -2238,12 +2239,11 @@ struct PACKED log_PSC {
|
|
|
|
|
// @LoggerMessage: VIBE
|
|
|
|
|
// @Description: Processed (acceleration) vibration information
|
|
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
|
// @Field: IMU: Vibration instance number
|
|
|
|
|
// @Field: VibeX: Primary accelerometer filtered vibration, x-axis
|
|
|
|
|
// @Field: VibeY: Primary accelerometer filtered vibration, y-axis
|
|
|
|
|
// @Field: VibeZ: Primary accelerometer filtered vibration, z-axis
|
|
|
|
|
// @Field: Clip0: Number of clipping events on 1st accelerometer
|
|
|
|
|
// @Field: Clip1: Number of clipping events on 2nd accelerometer
|
|
|
|
|
// @Field: Clip2: Number of clipping events on 3rd accelerometer
|
|
|
|
|
// @Field: Clip: Number of clipping events on 1st accelerometer
|
|
|
|
|
|
|
|
|
|
// @LoggerMessage: VISO
|
|
|
|
|
// @Description: Visual Odometry
|
|
|
|
@ -2663,7 +2663,7 @@ struct PACKED log_PSC {
@@ -2663,7 +2663,7 @@ struct PACKED log_PSC {
|
|
|
|
|
{ LOG_BAR3_MSG, sizeof(log_BARO), \
|
|
|
|
|
"BAR3", BARO_FMT, BARO_LABELS, BARO_UNITS, BARO_MULTS }, \
|
|
|
|
|
{ LOG_VIBE_MSG, sizeof(log_Vibe), \
|
|
|
|
|
"VIBE", "QfffIII", "TimeUS,VibeX,VibeY,VibeZ,Clip0,Clip1,Clip2", "s------", "F------" }, \
|
|
|
|
|
"VIBE", "QBfffI", "TimeUS,IMU,VibeX,VibeY,VibeZ,Clip", "s#----", "F-----" }, \
|
|
|
|
|
{ LOG_IMUDT_MSG, sizeof(log_IMUDT), \
|
|
|
|
|
"IMT",IMT_FMT,IMT_LABELS, IMT_UNITS, IMT_MULTS }, \
|
|
|
|
|
{ LOG_IMUDT2_MSG, sizeof(log_IMUDT), \
|
|
|
|
|