AP_IOMCU: added periodic reading of RC input

This commit is contained in:
Andrew Tridgell 2017-12-28 09:26:11 +11:00
parent 06322da4e2
commit ceeade5822
2 changed files with 15 additions and 0 deletions

View File

@ -66,6 +66,7 @@ enum ioevents {
IOEVENT_SET_ONESHOT_ON,
IOEVENT_SET_ONESHOT_OFF,
IOEVENT_SET_RATES,
IOEVENT_GET_RCIN,
};
// setup page registers
@ -186,6 +187,9 @@ void AP_IOMCU::send_servo_out()
*/
void AP_IOMCU::read_rc_input()
{
// read a min of 9 channels and max of max_channels
uint8_t n = MIN(MAX(9, rc_input.count), max_channels);
read_registers(PAGE_RAW_RCIN, 0, 6+n, (uint16_t *)&rc_input);
}
/*

View File

@ -113,6 +113,17 @@ private:
uint16_t prssi;
} reg_status;
// PAGE_RAW_RCIN values
struct PACKED {
uint16_t count;
uint16_t flags;
uint16_t nrssi;
uint16_t data;
uint16_t frame_count;
uint16_t lost_frame_count;
uint16_t pwm[max_channels];
} rc_input;
// output pwm values
struct {
uint8_t num_channels;