mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: remove unused init from sport mode
This commit is contained in:
parent
3d926a6943
commit
0e0d02cd6d
@ -440,10 +440,6 @@ static bool set_mode(uint8_t mode)
|
||||
|
||||
case SPORT:
|
||||
success = sport_init(ignore_checks);
|
||||
// reset acro angle targets to current attitude
|
||||
acro_roll = ahrs.roll_sensor;
|
||||
acro_pitch = ahrs.pitch_sensor;
|
||||
control_yaw = ahrs.yaw_sensor;
|
||||
break;
|
||||
|
||||
case FLIP:
|
||||
|
Loading…
Reference in New Issue
Block a user