mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_HAL_SITL: remove unused variables from RCInput
In file included from ../../libraries/AP_HAL_SITL/RCInput.cpp:6: ../../libraries/AP_HAL_SITL/RCInput.h:22:17: warning: private field '_sitlState' is not used [-Wunused-private-field] 22 | SITL_State *_sitlState; | ^ ../../libraries/AP_HAL_SITL/RCInput.h:23:10: warning: private field 'using_rc_protocol' is not used [-Wunused-private-field] 23 | bool using_rc_protocol; | ^
This commit is contained in:
parent
4c2c20c018
commit
2e46dcf582
@ -42,7 +42,7 @@ static Storage sitlStorage;
|
||||
static SITL_State sitlState;
|
||||
static Scheduler sitlScheduler(&sitlState);
|
||||
#if AP_RCPROTOCOL_ENABLED
|
||||
static RCInput sitlRCInput(&sitlState);
|
||||
static RCInput sitlRCInput;
|
||||
#else
|
||||
static Empty::RCInput sitlRCInput;
|
||||
#endif
|
||||
|
@ -9,7 +9,7 @@
|
||||
|
||||
class HALSITL::RCInput : public AP_HAL::RCInput {
|
||||
public:
|
||||
explicit RCInput(SITL_State *sitlState): _sitlState(sitlState) {}
|
||||
explicit RCInput() {}
|
||||
void init() override;
|
||||
bool new_input() override;
|
||||
uint8_t num_channels() override;
|
||||
@ -17,10 +17,6 @@ public:
|
||||
uint8_t read(uint16_t* periods, uint8_t len) override;
|
||||
|
||||
const char *protocol() const override { return "SITL"; }
|
||||
|
||||
private:
|
||||
SITL_State *_sitlState;
|
||||
bool using_rc_protocol;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user