AP_HAL_SITL: RCInput minor fix

fix style
make constructor explicit
remove unused _valid
correct read to return real length instead of fixed 8
correct implicit cast
This commit is contained in:
Pierre Kancir 2017-01-09 13:28:35 +01:00 committed by Francisco Ferreira
parent 7f5b32f59f
commit ff46964d22
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
2 changed files with 8 additions and 9 deletions

View File

@ -37,10 +37,10 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
if (len > SITL_RC_INPUT_CHANNELS) {
len = SITL_RC_INPUT_CHANNELS;
}
for (uint8_t i=0; i<len; i++) {
for (uint8_t i=0; i < len; i++) {
periods[i] = read(i);
}
return 8;
return len;
}
bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
@ -57,9 +57,11 @@ bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
bool RCInput::set_override(uint8_t channel, int16_t override)
{
if (override < 0) return false; /* -1: no change. */
if (override < 0) {
return false; /* -1: no change. */
}
if (channel < SITL_RC_INPUT_CHANNELS) {
_override[channel] = override;
_override[channel] = static_cast<uint16_t>(override);
if (override != 0) {
return true;
}

View File

@ -9,9 +9,7 @@
class HALSITL::RCInput : public AP_HAL::RCInput {
public:
RCInput(SITL_State *sitlState) {
_sitlState = sitlState;
}
explicit RCInput(SITL_State *sitlState): _sitlState(sitlState) {}
void init() override;
bool new_input() override;
uint8_t num_channels() override {
@ -26,7 +24,6 @@ public:
private:
SITL_State *_sitlState;
bool _valid;
/* override state */
uint16_t _override[SITL_RC_INPUT_CHANNELS];