mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: added #defines for VRBRAIN board
This commit is contained in:
parent
1d27e0d127
commit
39d9e93904
|
@ -36,6 +36,14 @@
|
|||
#define BOARD_PWM_COUNT_DEFAULT 4
|
||||
#define BOARD_SER1_RTSCTS_DEFAULT 2
|
||||
#endif
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
#define BOARD_PWM_COUNT_DEFAULT 8
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -66,6 +74,12 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] PROGMEM = {
|
|||
// @Description: Disabling this option will disable the use of the safety switch on PX4 for arming. Use of the safety switch is highly recommended, so you should leave this option set to 1 except in unusual circumstances.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
AP_GROUPINFO("SAFETYENABLE", 3, AP_BoardConfig, _safety_enable, 1),
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// @Param: PWM_COUNT
|
||||
// @DisplayName: PWM Count
|
||||
// @Description: Number of auxillary PWMs to enable
|
||||
// @Values: 0:No PWMs,2:Two PWMs,4:Four PWMs,6:Six PWMs,8:Six PWMs
|
||||
AP_GROUPINFO("PWM_COUNT", 0, AP_BoardConfig, _pwm_count, BOARD_PWM_COUNT_DEFAULT),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
|
@ -100,5 +114,20 @@ void AP_BoardConfig::init()
|
|||
if (_safety_enable.get() == 0) {
|
||||
hal.rcout->force_safety_off();
|
||||
}
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
/* configure the VRBRAIN driver for the right number of PWMs */
|
||||
|
||||
// ensure only valid values are set, rounding up
|
||||
if (_pwm_count > 8) _pwm_count.set(8);
|
||||
if (_pwm_count < 0) _pwm_count.set(0);
|
||||
|
||||
int fd = open("/dev/px4fmu", 0);
|
||||
if (fd == -1) {
|
||||
hal.scheduler->panic("Unable to open /dev/px4fmu");
|
||||
}
|
||||
if (ioctl(fd, PWM_SERVO_SET_COUNT, _pwm_count.get()) != 0) {
|
||||
hal.console->printf("RCOutput: Unable to setup alt PWM to %u channels\n", _pwm_count.get());
|
||||
}
|
||||
close(fd);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -27,6 +27,9 @@ private:
|
|||
AP_Int8 _ser2_rtscts;
|
||||
AP_Int8 _safety_enable;
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
AP_Int8 _pwm_count;
|
||||
#endif
|
||||
};
|
||||
|
||||
#endif // __AP_BOARDCONFIG_H__
|
||||
|
|
Loading…
Reference in New Issue