ardupilot/libraries/AP_HAL_SITL/RCInput.h
Peter Barker 2e46dcf582 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;
      |          ^
2025-02-11 11:54:52 +11:00

24 lines
493 B
C++

#pragma once
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define SITL_RC_INPUT_CHANNELS 16
#include "AP_HAL_SITL.h"
class HALSITL::RCInput : public AP_HAL::RCInput {
public:
explicit RCInput() {}
void init() override;
bool new_input() override;
uint8_t num_channels() override;
uint16_t read(uint8_t ch) override;
uint8_t read(uint16_t* periods, uint8_t len) override;
const char *protocol() const override { return "SITL"; }
};
#endif