mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_IOMCU: support oneshot mode
This commit is contained in:
parent
ba3cdf74b5
commit
30903f2acb
@ -67,7 +67,6 @@ enum ioevents {
|
||||
IOEVENT_FORCE_SAFETY_OFF,
|
||||
IOEVENT_FORCE_SAFETY_ON,
|
||||
IOEVENT_SET_ONESHOT_ON,
|
||||
IOEVENT_SET_ONESHOT_OFF,
|
||||
IOEVENT_SET_RATES,
|
||||
IOEVENT_GET_RCIN,
|
||||
IOEVENT_ENABLE_SBUS,
|
||||
@ -217,6 +216,13 @@ void AP_IOMCU::thread_main(void)
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
if (mask & EVENT_MASK(IOEVENT_SET_ONESHOT_ON)) {
|
||||
if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_ONESHOT)) {
|
||||
event_failed(IOEVENT_SET_ONESHOT_ON);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
// check for regular timed events
|
||||
uint32_t now = AP_HAL::millis();
|
||||
@ -548,4 +554,10 @@ void AP_IOMCU::set_default_rate(uint16_t rate_hz)
|
||||
trigger_event(IOEVENT_SET_DEFAULT_RATE);
|
||||
}
|
||||
|
||||
// setup for oneshot mode
|
||||
void AP_IOMCU::set_oneshot_mode(void)
|
||||
{
|
||||
trigger_event(IOEVENT_SET_ONESHOT_ON);
|
||||
}
|
||||
|
||||
#endif // HAL_WITH_IO_MCU
|
||||
|
@ -69,7 +69,10 @@ public:
|
||||
|
||||
// set default output rate
|
||||
void set_default_rate(uint16_t rate_hz);
|
||||
|
||||
|
||||
// set to oneshot mode
|
||||
void set_oneshot_mode(void);
|
||||
|
||||
private:
|
||||
AP_HAL::UARTDriver &uart;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user