mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Sub: Remove dead save_trim()
This commit is contained in:
parent
3b1827ca21
commit
3df1aa09e8
@ -694,8 +694,6 @@ private:
|
||||
void terrain_update();
|
||||
void terrain_logging();
|
||||
bool terrain_use();
|
||||
void save_trim();
|
||||
void auto_trim();
|
||||
void init_ardupilot();
|
||||
void startup_INS_ground();
|
||||
bool calibrate_gyros();
|
||||
|
@ -80,14 +80,3 @@ void Sub::enable_motor_output()
|
||||
motors.enable();
|
||||
motors.output_min();
|
||||
}
|
||||
|
||||
// save_trim - adds roll and pitch trims from the radio to ahrs
|
||||
void Sub::save_trim()
|
||||
{
|
||||
// save roll and pitch trim
|
||||
float roll_trim = ToRad((float)channel_roll->get_control_in()/100.0f);
|
||||
float pitch_trim = ToRad((float)channel_pitch->get_control_in()/100.0f);
|
||||
ahrs.add_trim(roll_trim, pitch_trim);
|
||||
Log_Write_Event(DATA_SAVE_TRIM);
|
||||
gcs_send_text(MAV_SEVERITY_INFO, "Trim saved");
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user