AP_HAL_SITL: update ESC telemetry in rcout

This commit is contained in:
Andy Piper 2021-03-06 20:58:15 +00:00 committed by Andrew Tridgell
parent 6447bd1cdd
commit 5b992de959
2 changed files with 4 additions and 0 deletions

View File

@ -85,6 +85,7 @@ void RCOutput::push(void)
memcpy(_sitlState->pwm_output, _pending, SITL_NUM_CHANNELS * sizeof(uint16_t));
_corked = false;
}
esc_telem.update();
}
/*

View File

@ -3,6 +3,7 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
#include "AP_HAL_SITL.h"
#include <AP_ESC_Telem/AP_ESC_Telem_SITL.h>
class HALSITL::RCOutput : public AP_HAL::RCOutput {
public:
@ -36,6 +37,8 @@ public:
private:
SITL_State *_sitlState;
AP_ESC_Telem_SITL esc_telem;
uint16_t _freq_hz;
uint16_t _enable_mask;
bool _corked;