Copter: Added Toy Mode logger documentation

This commit is contained in:
Rishabh 2020-04-04 14:32:27 +05:30 committed by Randy Mackay
parent b8878380d6
commit 4995a9b274

View File

@ -990,6 +990,17 @@ void ToyMode::thrust_limiting(float *thrust, uint8_t num_motors)
}
uint16_t pwm[4];
hal.rcout->read(pwm, 4);
// @LoggerMessage: THST
// @Description: Maximum thrust limitation based on battery voltage in Toy Mode
// @Field: TimeUS: Time since system startup
// @Field: Vol: Filtered battery voltage
// @Field: Mul: Thrust multiplier between 0 and 1 to limit the output thrust based on battery voltage
// @Field: M1: Motor 1 pwm output
// @Field: M2: Motor 2 pwm output
// @Field: M3: Motor 3 pwm output
// @Field: M4: Motor 4 pwm output
if (motor_log_counter++ % 10 == 0) {
AP::logger().Write("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH",
AP_HAL::micros64(),