mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Plane: add video stab log bit and log in ahrs_update
This commit is contained in:
parent
9c52752e16
commit
d473344177
@ -189,6 +189,10 @@ void Plane::ahrs_update()
|
||||
// update inertial_nav for quadplane
|
||||
quadplane.inertial_nav.update();
|
||||
#endif
|
||||
|
||||
if (should_log(MASK_LOG_VIDEO_STABILISATION)) {
|
||||
ahrs.write_video_stabilisation();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -618,7 +618,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Param: LOG_BITMASK
|
||||
// @DisplayName: Log bitmask
|
||||
// @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all log types by setting this to 65535. The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Sonar=16384, Arming=32768, FullLogs=65535
|
||||
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW,20:ATTITUDE_FULLRATE
|
||||
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW,20:ATTITUDE_FULLRATE,21:VideoStabilization
|
||||
// @User: Advanced
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
|
@ -118,6 +118,7 @@ enum log_messages {
|
||||
// #define MASK_LOG_ARM_DISARM (1<<15)
|
||||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||
#define MASK_LOG_ATTITUDE_FULLRATE (1U<<20)
|
||||
#define MASK_LOG_VIDEO_STABILISATION (1UL<<21)
|
||||
|
||||
// altitude control algorithms
|
||||
enum {
|
||||
|
Loading…
Reference in New Issue
Block a user