mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_PX4: implement RCOutput::read_last_sent
This commit is contained in:
parent
6663d30728
commit
4bf3ec0e91
|
@ -285,6 +285,22 @@ void PX4RCOutput::read(uint16_t* period_us, uint8_t len)
|
|||
}
|
||||
}
|
||||
|
||||
uint16_t PX4RCOutput::read_last_sent(uint8_t ch)
|
||||
{
|
||||
if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return _period[ch];
|
||||
}
|
||||
|
||||
void PX4RCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
for (uint8_t i=0; i<len; i++) {
|
||||
period_us[i] = read_last_sent(i);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
update actuator armed state
|
||||
*/
|
||||
|
|
|
@ -20,6 +20,8 @@ public:
|
|||
void write(uint8_t ch, uint16_t period_us) override;
|
||||
uint16_t read(uint8_t ch) override;
|
||||
void read(uint16_t* period_us, uint8_t len) override;
|
||||
uint16_t read_last_sent(uint8_t ch) override;
|
||||
void read_last_sent(uint16_t* period_us, uint8_t len) override;
|
||||
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
|
||||
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override;
|
||||
bool force_safety_on(void) override;
|
||||
|
|
Loading…
Reference in New Issue