Copter: throttle sent to GCS uses 0 to 1 range

This is probably not correct because we should be sending the throttle as a 0 to 1 number using the full possible output range.  This uses the reduced range passed in when the copter is being stabilized (i.e. between throttle-min and throttle-max)
This commit is contained in:
Leonard Hall 2016-01-02 12:18:00 +09:00 committed by Randy Mackay
parent f8d7b677d4
commit a44f7f650b

View File

@ -394,7 +394,7 @@ void NOINLINE Copter::send_vfr_hud(mavlink_channel_t chan)
gps.ground_speed(),
gps.ground_speed(),
(ahrs.yaw_sensor / 100) % 360,
(int16_t)(motors.get_throttle())/10,
(int16_t)(motors.get_throttle() * 100),
current_loc.alt / 100.0f,
climb_rate / 100.0f);
}