mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
HAL_Empty: allow return of last value in RCOutput
this is needed for linux boards with no native RCOutput that use SBUS out on a serial port to ensure they can display the servo values in the GCS
This commit is contained in:
parent
1ce77111e5
commit
dff6a5bff9
@ -1,5 +1,6 @@
|
|||||||
|
|
||||||
#include "RCOutput.h"
|
#include "RCOutput.h"
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
using namespace Empty;
|
using namespace Empty;
|
||||||
|
|
||||||
@ -18,12 +19,23 @@ void RCOutput::disable_ch(uint8_t chan)
|
|||||||
{}
|
{}
|
||||||
|
|
||||||
void RCOutput::write(uint8_t chan, uint16_t period_us)
|
void RCOutput::write(uint8_t chan, uint16_t period_us)
|
||||||
{}
|
{
|
||||||
|
if (chan < ARRAY_SIZE(value)) {
|
||||||
|
value[chan] = period_us;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
uint16_t RCOutput::read(uint8_t chan) {
|
uint16_t RCOutput::read(uint8_t chan)
|
||||||
|
{
|
||||||
|
if (chan < ARRAY_SIZE(value)) {
|
||||||
|
return value[chan];
|
||||||
|
}
|
||||||
return 900;
|
return 900;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput::read(uint16_t* period_us, uint8_t len)
|
void RCOutput::read(uint16_t* period_us, uint8_t len)
|
||||||
{}
|
{
|
||||||
|
len = MIN(len, ARRAY_SIZE(value));
|
||||||
|
memcpy(period_us, value, len*sizeof(value[0]));
|
||||||
|
}
|
||||||
|
|
||||||
|
@ -13,4 +13,6 @@ class Empty::RCOutput : public AP_HAL::RCOutput {
|
|||||||
void read(uint16_t* period_us, uint8_t len) override;
|
void read(uint16_t* period_us, uint8_t len) override;
|
||||||
void cork(void) override {}
|
void cork(void) override {}
|
||||||
void push(void) override {}
|
void push(void) override {}
|
||||||
|
private:
|
||||||
|
uint16_t value[16];
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user