mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: remove unused throttle variable
This commit is contained in:
parent
1e8e3609c6
commit
66f1437e4f
@ -41,7 +41,6 @@ Rover::Rover(void) :
|
|||||||
camera_mount(ahrs, current_loc),
|
camera_mount(ahrs, current_loc),
|
||||||
#endif
|
#endif
|
||||||
control_mode(&mode_initializing),
|
control_mode(&mode_initializing),
|
||||||
throttle(500),
|
|
||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
frsky_telemetry(ahrs, battery, rangefinder),
|
frsky_telemetry(ahrs, battery, rangefinder),
|
||||||
#endif
|
#endif
|
||||||
|
@ -288,7 +288,6 @@ private:
|
|||||||
// Ground speed
|
// Ground speed
|
||||||
// The amount current ground speed is below min ground speed. meters per second
|
// The amount current ground speed is below min ground speed. meters per second
|
||||||
float ground_speed;
|
float ground_speed;
|
||||||
int16_t throttle;
|
|
||||||
|
|
||||||
// CH7 control
|
// CH7 control
|
||||||
// Used to track the CH7 toggle state.
|
// Used to track the CH7 toggle state.
|
||||||
|
Loading…
Reference in New Issue
Block a user