AP_BoardConfig: use hal.rcout->enable_sbus_out()

This commit is contained in:
Andrew Tridgell 2016-04-15 16:39:38 +10:00
parent 6f284d673a
commit 2304c41f44

View File

@ -161,10 +161,6 @@ void AP_BoardConfig::init()
} }
if (_sbus_out_rate.get() >= 1) { 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 { static const struct {
uint8_t value; uint8_t value;
uint16_t rate; uint16_t rate;
@ -183,16 +179,8 @@ void AP_BoardConfig::init()
rate = rates[i].rate; rate = rates[i].rate;
} }
} }
for (uint8_t tries=0; tries<10; tries++) { if (!hal.rcout->enable_sbus_out(rate)) {
if (ioctl(fd, SBUS_SET_PROTO_VERSION, 1) != 0) { hal.console->printf("Failed to enable SBUS out\n");
continue;
}
if (ioctl(fd, PWM_SERVO_SET_SBUS_RATE, rate) != 0) {
continue;
}
break;
}
close(fd);
} }
} }