mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_BoardConfig: use hal.rcout->enable_sbus_out()
This commit is contained in:
parent
6f284d673a
commit
2304c41f44
@ -161,10 +161,6 @@ void AP_BoardConfig::init()
|
||||
}
|
||||
|
||||
if (_sbus_out_rate.get() >= 1) {
|
||||
int fd = open("/dev/px4io", 0);
|
||||
if (fd == -1) {
|
||||
hal.console->printf("SBUS: Unable to open px4io for sbus\n");
|
||||
} else {
|
||||
static const struct {
|
||||
uint8_t value;
|
||||
uint16_t rate;
|
||||
@ -183,16 +179,8 @@ void AP_BoardConfig::init()
|
||||
rate = rates[i].rate;
|
||||
}
|
||||
}
|
||||
for (uint8_t tries=0; tries<10; tries++) {
|
||||
if (ioctl(fd, SBUS_SET_PROTO_VERSION, 1) != 0) {
|
||||
continue;
|
||||
}
|
||||
if (ioctl(fd, PWM_SERVO_SET_SBUS_RATE, rate) != 0) {
|
||||
continue;
|
||||
}
|
||||
break;
|
||||
}
|
||||
close(fd);
|
||||
if (!hal.rcout->enable_sbus_out(rate)) {
|
||||
hal.console->printf("Failed to enable SBUS out\n");
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user