mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
HAL_SITL: use SIM_RC_CHANCOUNT
This commit is contained in:
parent
128ea42286
commit
b130036798
@ -2,6 +2,7 @@
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
||||
#include "RCInput.h"
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
using namespace HALSITL;
|
||||
|
||||
@ -22,7 +23,7 @@ bool RCInput::new_input()
|
||||
|
||||
uint16_t RCInput::read(uint8_t ch)
|
||||
{
|
||||
if (ch >= SITL_RC_INPUT_CHANNELS) {
|
||||
if (ch >= num_channels()) {
|
||||
return 0;
|
||||
}
|
||||
return _sitlState->pwm_input[ch];
|
||||
@ -30,8 +31,8 @@ uint16_t RCInput::read(uint8_t ch)
|
||||
|
||||
uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
||||
{
|
||||
if (len > SITL_RC_INPUT_CHANNELS) {
|
||||
len = SITL_RC_INPUT_CHANNELS;
|
||||
if (len > num_channels()) {
|
||||
len = num_channels();
|
||||
}
|
||||
for (uint8_t i=0; i < len; i++) {
|
||||
periods[i] = read(i);
|
||||
@ -39,4 +40,13 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
||||
return len;
|
||||
}
|
||||
|
||||
uint8_t RCInput::num_channels()
|
||||
{
|
||||
SITL::SITL *_sitl = AP::sitl();
|
||||
if (_sitl) {
|
||||
return MIN(_sitl->rc_chancount.get(), SITL_RC_INPUT_CHANNELS);
|
||||
}
|
||||
return SITL_RC_INPUT_CHANNELS;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -12,9 +12,7 @@ public:
|
||||
explicit RCInput(SITL_State *sitlState): _sitlState(sitlState) {}
|
||||
void init() override;
|
||||
bool new_input() override;
|
||||
uint8_t num_channels() override {
|
||||
return SITL_RC_INPUT_CHANNELS;
|
||||
}
|
||||
uint8_t num_channels() override;
|
||||
uint16_t read(uint8_t ch) override;
|
||||
uint8_t read(uint16_t* periods, uint8_t len) override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user