mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: remove unused circle_desired_rotations
desired num rotations is already held in command so we save 1byte of RAM
This commit is contained in:
parent
e6d2692eab
commit
d2dad1b2c1
@ -546,9 +546,8 @@ static int16_t desired_climb_rate; // pilot desired climb rate - for lo
|
||||
static float acro_level_mix; // scales back roll, pitch and yaw inversely proportional to input from pilot
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Circle Mode / Loiter control
|
||||
// Loiter control
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
static uint8_t circle_desired_rotations; // how many times to circle as specified by mission command
|
||||
static uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds)
|
||||
static uint32_t loiter_time; // How long have we been loitering - The start time in millis
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user