mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
HAL_Linux: use AP::RC()
This commit is contained in:
parent
672d09c965
commit
312018898f
@ -119,7 +119,7 @@ void RCInput_RCProtocol::init()
|
||||
} else {
|
||||
fd_115200 = -1;
|
||||
}
|
||||
rcp.init();
|
||||
AP::RC().init();
|
||||
printf("SBUS FD %d 115200 FD %d\n", fd_sbus, fd_115200);
|
||||
}
|
||||
|
||||
@ -131,7 +131,7 @@ void RCInput_RCProtocol::_timer_tick(void)
|
||||
ssize_t n = ::read(fd_sbus, &b[0], sizeof(b));
|
||||
if (n > 0) {
|
||||
for (uint8_t i=0; i<n; i++) {
|
||||
rcp.process_byte(b[i], 100000);
|
||||
AP::RC().process_byte(b[i], 100000);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -139,15 +139,15 @@ void RCInput_RCProtocol::_timer_tick(void)
|
||||
ssize_t n = ::read(fd_115200, &b[0], sizeof(b));
|
||||
if (n > 0) {
|
||||
for (uint8_t i=0; i<n; i++) {
|
||||
rcp.process_byte(b[i], 115200);
|
||||
AP::RC().process_byte(b[i], 115200);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (rcp.new_input()) {
|
||||
uint8_t n = rcp.num_channels();
|
||||
if (AP::RC().new_input()) {
|
||||
uint8_t n = AP::RC().num_channels();
|
||||
for (uint8_t i=0; i<n; i++) {
|
||||
_pwm_values[i] = rcp.read(i);
|
||||
_pwm_values[i] = AP::RC().read(i);
|
||||
}
|
||||
_num_channels = n;
|
||||
rc_input_count++;
|
||||
|
@ -43,7 +43,6 @@ private:
|
||||
|
||||
int fd_sbus;
|
||||
int fd_115200;
|
||||
AP_RCProtocol rcp;
|
||||
};
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user