mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AP_Logger: add video stab log structure
This commit is contained in:
parent
cc5a867397
commit
cee0503812
@ -139,6 +139,35 @@ struct PACKED log_Rate {
|
|||||||
float accel_out;
|
float accel_out;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// @LoggerMessage: VSTB
|
||||||
|
// @Description: Log message for video stabilisation software such as Gyroflow
|
||||||
|
// @Field: TimeUS: Time since system startup
|
||||||
|
// @Field: GyrX: measured rotation rate about X axis
|
||||||
|
// @Field: GyrY: measured rotation rate about Y axis
|
||||||
|
// @Field: GyrZ: measured rotation rate about Z axis
|
||||||
|
// @Field: AccX: acceleration along X axis
|
||||||
|
// @Field: AccY: acceleration along Y axis
|
||||||
|
// @Field: AccZ: acceleration along Z axis
|
||||||
|
// @Field: Q1: Estimated attitude quaternion component 1
|
||||||
|
// @Field: Q2: Estimated attitude quaternion component 2
|
||||||
|
// @Field: Q3: Estimated attitude quaternion component 3
|
||||||
|
// @Field: Q4: Estimated attitude quaternion component 4
|
||||||
|
|
||||||
|
struct PACKED log_Gyroflow {
|
||||||
|
LOG_PACKET_HEADER;
|
||||||
|
uint64_t time_us;
|
||||||
|
float gyro_x;
|
||||||
|
float gyro_y;
|
||||||
|
float gyro_z;
|
||||||
|
float accel_x;
|
||||||
|
float accel_y;
|
||||||
|
float accel_z;
|
||||||
|
float Q1;
|
||||||
|
float Q2;
|
||||||
|
float Q3;
|
||||||
|
float Q4;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
#define LOG_STRUCTURE_FROM_AHRS \
|
#define LOG_STRUCTURE_FROM_AHRS \
|
||||||
{ LOG_AHR2_MSG, sizeof(log_AHRS), \
|
{ LOG_AHR2_MSG, sizeof(log_AHRS), \
|
||||||
@ -152,4 +181,7 @@ struct PACKED log_Rate {
|
|||||||
{ LOG_POS_MSG, sizeof(log_POS), \
|
{ LOG_POS_MSG, sizeof(log_POS), \
|
||||||
"POS","QLLfff","TimeUS,Lat,Lng,Alt,RelHomeAlt,RelOriginAlt", "sDUmmm", "FGG000" , true }, \
|
"POS","QLLfff","TimeUS,Lat,Lng,Alt,RelHomeAlt,RelOriginAlt", "sDUmmm", "FGG000" , true }, \
|
||||||
{ LOG_RATE_MSG, sizeof(log_Rate), \
|
{ LOG_RATE_MSG, sizeof(log_Rate), \
|
||||||
"RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut", "skk-kk-kk-oo-", "F?????????BB-" , true },
|
"RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut", "skk-kk-kk-oo-", "F?????????BB-" , true }, \
|
||||||
|
{ LOG_GYROFLOW_MSG, sizeof(log_Gyroflow), \
|
||||||
|
"VSTB", "Qffffffffff", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,Q1,Q2,Q3,Q4", "sEEEooo????", "F000000????" },
|
||||||
|
|
||||||
|
@ -1427,6 +1427,7 @@ enum LogMessages : uint8_t {
|
|||||||
LOG_STAK_MSG,
|
LOG_STAK_MSG,
|
||||||
LOG_FILE_MSG,
|
LOG_FILE_MSG,
|
||||||
LOG_SCRIPTING_MSG,
|
LOG_SCRIPTING_MSG,
|
||||||
|
LOG_VIDEO_STABILISATION_MSG,
|
||||||
|
|
||||||
_LOG_LAST_MSG_
|
_LOG_LAST_MSG_
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user