Copter: Remove trim_radio() function.

This commit is contained in:
Robert Lefebvre 2015-02-04 10:58:52 -05:00 committed by Randy Mackay
parent ecaf3280e5
commit 2186dec271
2 changed files with 2 additions and 19 deletions

View File

@ -1144,8 +1144,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
init_barometer(false);
result = MAV_RESULT_ACCEPTED;
} else if (packet.param4 == 1) {
trim_radio();
result = MAV_RESULT_ACCEPTED;
result = MAV_RESULT_UNSUPPORTED;
} else if (packet.param5 == 1) {
// 3d accel calibration
float trim_roll, trim_pitch;

View File

@ -185,20 +185,4 @@ static void set_throttle_zero_flag(int16_t throttle_control)
} else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {
ap.throttle_zero = true;
}
}
static void trim_radio()
{
for (uint8_t i = 0; i < 30; i++) {
read_radio();
}
g.rc_1.trim(); // roll
g.rc_2.trim(); // pitch
g.rc_4.trim(); // yaw
g.rc_1.save_eeprom();
g.rc_2.save_eeprom();
g.rc_4.save_eeprom();
}
}