AP_HAL_ChibiOS: set pwm output values in simstate object
This commit is contained in:
parent
8b2f85756a
commit
f7608c22da
@ -32,6 +32,10 @@
|
|||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_SIM_ENABLED
|
||||||
|
#include <AP_HAL/SIMState.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_USE_PWM == TRUE
|
#if HAL_USE_PWM == TRUE
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
|
|
||||||
@ -512,11 +516,17 @@ 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 >= max_channels) {
|
if (chan >= max_channels) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
last_sent[chan] = period_us;
|
last_sent[chan] = period_us;
|
||||||
|
|
||||||
|
#if AP_SIM_ENABLED
|
||||||
|
hal.simstate->pwm_output[chan] = period_us;
|
||||||
|
return;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_WITH_IO_MCU
|
#if HAL_WITH_IO_MCU
|
||||||
// handle IO MCU channels
|
// handle IO MCU channels
|
||||||
if (AP_BoardConfig::io_enabled()) {
|
if (AP_BoardConfig::io_enabled()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user