mirror of https://github.com/ArduPilot/ardupilot
Copter: added PID logging by default
this is essential for analysing tuning logs
This commit is contained in:
parent
564879594e
commit
68bf55a373
|
@ -306,7 +306,7 @@ const AP_Param::Info Copter::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 basiclog types by setting this to 65535.
|
||||
// @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 basiclog types by setting this to 65535. Note that if you want to reduce log sizes you should consider using LOG_FILE_RATEMAX instead of disabling logging items with this parameter.
|
||||
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging
|
||||
// @User: Standard
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
|
|
@ -527,7 +527,8 @@
|
|||
MASK_LOG_OPTFLOW | \
|
||||
MASK_LOG_COMPASS | \
|
||||
MASK_LOG_CAMERA | \
|
||||
MASK_LOG_MOTBATT
|
||||
MASK_LOG_MOTBATT | \
|
||||
MASK_LOG_PID
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
Loading…
Reference in New Issue