RC_Channels: Collapse has_new_input() with set_pwm_all()

This commit is contained in:
Michael du Breuil 2018-04-23 21:20:02 -07:00 committed by Andrew Tridgell
parent 0d6043e0c6
commit 30554d0de0
3 changed files with 11 additions and 12 deletions

View File

@ -152,14 +152,12 @@ public:
static uint8_t get_valid_channel_count(void); // returns the number of valid channels in the last read static uint8_t get_valid_channel_count(void); // returns the number of valid channels in the last read
static int16_t get_receiver_rssi(void); // returns [0, 255] for receiver RSSI (0 is no link) if present, otherwise -1 static int16_t get_receiver_rssi(void); // returns [0, 255] for receiver RSSI (0 is no link) if present, otherwise -1
static bool has_new_input(void); // returns true if there has been new input since last checked static bool read_input(void); // returns true if new input has been read in
static void clear_overrides(void); // clears any active overrides static void clear_overrides(void); // clears any active overrides
static bool receiver_bind(const int dsmMode); // puts the reciever in bind mode if present, returns true if success static bool receiver_bind(const int dsmMode); // puts the reciever in bind mode if present, returns true if success
static bool set_override(const uint8_t chan, const int16_t value); // set a channels override value static bool set_override(const uint8_t chan, const int16_t value); // set a channels override value
static bool set_overrides(int16_t *overrides, const uint8_t len); // set multiple overrides at once static bool set_overrides(int16_t *overrides, const uint8_t len); // set multiple overrides at once
static void set_pwm_all(void);
private: private:
// this static arrangement is to avoid static pointers in AP_Param tables // this static arrangement is to avoid static pointers in AP_Param tables
static RC_Channel *channels; static RC_Channel *channels;

View File

@ -139,14 +139,20 @@ uint8_t RC_Channels::get_radio_in(uint16_t *chans, const uint8_t num_channels)
} }
/* /*
call read() and set_pwm() on all channels call read() and set_pwm() on all channels if there is new data
*/ */
void bool
RC_Channels::set_pwm_all(void) RC_Channels::read_input(void)
{ {
if (!hal.rcin->new_input()) {
return false;
}
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) { for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
channels[i].set_pwm(channels[i].read()); channels[i].set_pwm(channels[i].read());
} }
return true;
} }
uint8_t RC_Channels::get_valid_channel_count(void) uint8_t RC_Channels::get_valid_channel_count(void)
@ -159,11 +165,6 @@ int16_t RC_Channels::get_receiver_rssi(void)
return hal.rcin->get_rssi(); return hal.rcin->get_rssi();
} }
bool RC_Channels::has_new_input(void)
{
return hal.rcin->new_input();
}
void RC_Channels::clear_overrides(void) void RC_Channels::clear_overrides(void)
{ {
hal.rcin->clear_overrides(); hal.rcin->clear_overrides();

View File

@ -51,7 +51,7 @@ void setup()
void loop() void loop()
{ {
RC_Channels::set_pwm_all(); RC_Channels::read_input();
print_pwm(); print_pwm();
hal.scheduler->delay(20); hal.scheduler->delay(20);