From 1f6bc7bd9c6d3b186ec2c53d227c8d8c3d4f6047 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 8 Nov 2013 15:20:38 +0900 Subject: [PATCH] Copter: log TradHeli ch7, ch8 in MOT message --- ArduCopter/Log.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 5a547d6dc2..9bef6393bb 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -238,8 +238,7 @@ struct PACKED log_Motors { #elif FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME int16_t motor_out[6]; #elif FRAME_CONFIG == HELI_FRAME - int16_t motor_out[4]; - int16_t ch7_pwm_setpoint; + int16_t motor_out[6]; #else // quads & TRI_FRAME int16_t motor_out[4]; #endif @@ -270,8 +269,9 @@ static void Log_Write_Motors() motor_out : {motors.motor_out[AP_MOTORS_MOT_1], motors.motor_out[AP_MOTORS_MOT_2], motors.motor_out[AP_MOTORS_MOT_3], - motors.motor_out[AP_MOTORS_MOT_4]}, - ch7_pwm_setpoint:motors.ch7_pwm_setpoint() + motors.motor_out[AP_MOTORS_MOT_4], + motors.motor_out[AP_MOTORS_MOT_7], + motors.motor_out[AP_MOTORS_MOT_8]} #elif FRAME_CONFIG == TRI_FRAME motor_out : {motors.motor_out[AP_MOTORS_MOT_1], motors.motor_out[AP_MOTORS_MOT_2],