mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-08 22:53:57 -04:00
Copter: Remove trim_radio() function.
This commit is contained in:
parent
ecaf3280e5
commit
2186dec271
ArduCopter
@ -1144,8 +1144,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
init_barometer(false);
|
init_barometer(false);
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
} else if (packet.param4 == 1) {
|
} else if (packet.param4 == 1) {
|
||||||
trim_radio();
|
result = MAV_RESULT_UNSUPPORTED;
|
||||||
result = MAV_RESULT_ACCEPTED;
|
|
||||||
} else if (packet.param5 == 1) {
|
} else if (packet.param5 == 1) {
|
||||||
// 3d accel calibration
|
// 3d accel calibration
|
||||||
float trim_roll, trim_pitch;
|
float trim_roll, trim_pitch;
|
||||||
|
@ -186,19 +186,3 @@ static void set_throttle_zero_flag(int16_t throttle_control)
|
|||||||
ap.throttle_zero = true;
|
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();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user