mirror of https://github.com/ArduPilot/ardupilot
Sub: cleanup unused variable
This commit is contained in:
parent
29d3369c51
commit
9448e110b9
|
@ -54,8 +54,6 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|||
|
||||
int16_t channels[11];
|
||||
|
||||
uint32_t tnow_ms = millis();
|
||||
|
||||
float rpyScale = 0.4*gain; // Scale -1000-1000 to -400-400 with gain
|
||||
float throttleScale = 0.8*gain*g.throttle_gain; // Scale 0-1000 to 0-800 times gain
|
||||
int16_t rpyCenter = 1500;
|
||||
|
|
Loading…
Reference in New Issue