mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_IOMCU: added set_default_rate method
This commit is contained in:
parent
738d70ef02
commit
ff3b0ec1bd
@ -72,6 +72,7 @@ enum ioevents {
|
||||
IOEVENT_GET_RCIN,
|
||||
IOEVENT_ENABLE_SBUS,
|
||||
IOEVENT_SET_HEATER_TARGET,
|
||||
IOEVENT_SET_DEFAULT_RATE,
|
||||
};
|
||||
|
||||
// setup page registers
|
||||
@ -209,6 +210,13 @@ void AP_IOMCU::thread_main(void)
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
if (mask & EVENT_MASK(IOEVENT_SET_DEFAULT_RATE)) {
|
||||
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_DEFAULTRATE, rate.default_freq)) {
|
||||
event_failed(IOEVENT_SET_DEFAULT_RATE);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
// check for regular timed events
|
||||
uint32_t now = AP_HAL::millis();
|
||||
@ -533,4 +541,11 @@ void AP_IOMCU::set_heater_duty_cycle(uint8_t duty_cycle)
|
||||
trigger_event(IOEVENT_SET_HEATER_TARGET);
|
||||
}
|
||||
|
||||
// set default output rate
|
||||
void AP_IOMCU::set_default_rate(uint16_t rate_hz)
|
||||
{
|
||||
rate.default_freq = rate_hz;
|
||||
trigger_event(IOEVENT_SET_DEFAULT_RATE);
|
||||
}
|
||||
|
||||
#endif // HAL_WITH_IO_MCU
|
||||
|
@ -67,6 +67,9 @@ public:
|
||||
// set target for IMU heater
|
||||
void set_heater_duty_cycle(uint8_t duty_cycle);
|
||||
|
||||
// set default output rate
|
||||
void set_default_rate(uint16_t rate_hz);
|
||||
|
||||
private:
|
||||
AP_HAL::UARTDriver &uart;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user