Browse Source

Copter: bug fix to Tricopter motor logging

Fourth motor taken from yaw channel's radio_out instead of random
location in memory
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
5cc8772947
  1. 2
      ArduCopter/Log.pde

2
ArduCopter/Log.pde

@ -276,7 +276,7 @@ static void Log_Write_Motors() @@ -276,7 +276,7 @@ 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_4],
motors.motor_out[g.rc_4.radio_out]}
g.rc_4.radio_out}
#else // QUAD frame
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
motors.motor_out[AP_MOTORS_MOT_2],

Loading…
Cancel
Save