HAL_PX4: fixes for new PX4 device paths

This commit is contained in:
Andrew Tridgell 2015-02-13 20:21:03 +11:00
parent 38d63d51a5
commit 619196b6b3
3 changed files with 10 additions and 10 deletions

View File

@ -200,9 +200,9 @@ PX4AnalogIn::PX4AnalogIn() :
void PX4AnalogIn::init(void* machtnichts) void PX4AnalogIn::init(void* machtnichts)
{ {
_adc_fd = open(ADC_DEVICE_PATH, O_RDONLY | O_NONBLOCK); _adc_fd = open(ADC0_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
if (_adc_fd == -1) { if (_adc_fd == -1) {
hal.scheduler->panic("Unable to open " ADC_DEVICE_PATH); hal.scheduler->panic("Unable to open " ADC0_DEVICE_PATH);
} }
_battery_handle = orb_subscribe(ORB_ID(battery_status)); _battery_handle = orb_subscribe(ORB_ID(battery_status));
_servorail_handle = orb_subscribe(ORB_ID(servorail_status)); _servorail_handle = orb_subscribe(ORB_ID(servorail_status));

View File

@ -32,9 +32,9 @@ PX4GPIO::PX4GPIO()
void PX4GPIO::init() void PX4GPIO::init()
{ {
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
_led_fd = open(LED_DEVICE_PATH, O_RDWR); _led_fd = open(LED0_DEVICE_PATH, O_RDWR);
if (_led_fd == -1) { if (_led_fd == -1) {
hal.scheduler->panic("Unable to open " LED_DEVICE_PATH); hal.scheduler->panic("Unable to open " LED0_DEVICE_PATH);
} }
if (ioctl(_led_fd, LED_OFF, LED_BLUE) != 0) { if (ioctl(_led_fd, LED_OFF, LED_BLUE) != 0) {
hal.console->printf("GPIO: Unable to setup GPIO LED BLUE\n"); hal.console->printf("GPIO: Unable to setup GPIO LED BLUE\n");
@ -43,9 +43,9 @@ void PX4GPIO::init()
hal.console->printf("GPIO: Unable to setup GPIO LED RED\n"); hal.console->printf("GPIO: Unable to setup GPIO LED RED\n");
} }
#endif #endif
_tone_alarm_fd = open("/dev/tone_alarm", O_WRONLY); _tone_alarm_fd = open(TONEALARM0_DEVICE_PATH, O_WRONLY);
if (_tone_alarm_fd == -1) { if (_tone_alarm_fd == -1) {
hal.scheduler->panic("Unable to open /dev/tone_alarm"); hal.scheduler->panic("Unable to open " TONEALARM0_DEVICE_PATH);
} }
_gpio_fmu_fd = open(PX4FMU_DEVICE_PATH, 0); _gpio_fmu_fd = open(PX4FMU_DEVICE_PATH, 0);

View File

@ -21,9 +21,9 @@ using namespace PX4;
void PX4RCOutput::init(void* unused) void PX4RCOutput::init(void* unused)
{ {
_perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout"); _perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout");
_pwm_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR); _pwm_fd = open(PWM_OUTPUT0_DEVICE_PATH, O_RDWR);
if (_pwm_fd == -1) { if (_pwm_fd == -1) {
hal.scheduler->panic("Unable to open " PWM_OUTPUT_DEVICE_PATH); hal.scheduler->panic("Unable to open " PWM_OUTPUT0_DEVICE_PATH);
} }
if (ioctl(_pwm_fd, PWM_SERVO_ARM, 0) != 0) { if (ioctl(_pwm_fd, PWM_SERVO_ARM, 0) != 0) {
hal.console->printf("RCOutput: Unable to setup IO arming\n"); hal.console->printf("RCOutput: Unable to setup IO arming\n");
@ -41,7 +41,7 @@ void PX4RCOutput::init(void* unused)
return; return;
} }
_pwm_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS); _pwm_sub = orb_subscribe(ORB_ID(actuator_outputs));
// mark number of outputs given by px4io as zero // mark number of outputs given by px4io as zero
_outputs.noutputs = 0; _outputs.noutputs = 0;
@ -364,7 +364,7 @@ void PX4RCOutput::_timer_tick(void)
update_pwm: update_pwm:
bool rc_updated = false; bool rc_updated = false;
if (_pwm_sub >= 0 && orb_check(_pwm_sub, &rc_updated) == 0 && rc_updated) { if (_pwm_sub >= 0 && orb_check(_pwm_sub, &rc_updated) == 0 && rc_updated) {
orb_copy(ORB_ID_VEHICLE_CONTROLS, _pwm_sub, &_outputs); orb_copy(ORB_ID(actuator_outputs), _pwm_sub, &_outputs);
} }
} }