22 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 23 #include <sys/types.h> 27 #include <drivers/drv_pwm_output.h> 28 #include <drivers/drv_sbus.h> 29 #include <nuttx/arch.h> 56 { 0, PWM_SERVO_MODE_NONE, 6 },
57 { 2, PWM_SERVO_MODE_2PWM, 4 },
58 { 4, PWM_SERVO_MODE_4PWM, 2 },
59 { 6, PWM_SERVO_MODE_6PWM, 0 },
60 { 7, PWM_SERVO_MODE_3PWM1CAP, 2 },
61 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 62 { 8, PWM_SERVO_MODE_12PWM, 0 },
65 uint8_t mode_parm = (uint8_t)
pwm_count.get();
68 if (mode_table[i].mode_parm == mode_parm) {
73 hal.
console->
printf(
"RCOutput: invalid BRD_PWM_COUNT %u\n", mode_parm);
75 int fd =
open(
"/dev/px4fmu", 0);
79 if (ioctl(fd, PWM_SERVO_SET_MODE, mode_table[i].mode_value) != 0) {
80 hal.
console->
printf(
"RCOutput: unable to setup AUX PWM with BRD_PWM_COUNT %u\n", mode_parm);
83 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 84 if (mode_table[i].num_gpios < 2) {
98 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 100 int px4io_fd =
open(
"/dev/px4io", 0);
101 if (px4io_fd != -1) {
102 if (ioctl(px4io_fd, PWM_SERVO_IGNORE_SAFETY, (uint16_t)
state.ignore_safety_channels) != 0) {
106 int px4fmu_fd =
open(
"/dev/px4fmu", 0);
107 if (px4fmu_fd != -1) {
108 uint16_t mask =
state.ignore_safety_channels;
109 if (px4io_fd != -1) {
112 if (ioctl(px4fmu_fd, PWM_SERVO_IGNORE_SAFETY, (uint16_t)mask) != 0) {
117 if (px4io_fd != -1) {
123 extern "C" int waitpid(pid_t,
int *,
int);
130 char *s = strdup(arguments);
133 char *saveptr =
nullptr;
136 for (
char *tok=strtok_r(s,
" ", &saveptr); tok; tok=strtok_r(
nullptr,
" ", &saveptr)) {
142 args[nargs++] =
nullptr;
144 printf(
"Starting driver %s %s\n", name, arguments);
147 if (task_spawn(&pid, name, main_function,
nullptr,
nullptr,
148 args,
nullptr) != 0) {
150 printf(
"Failed to spawn %s\n", name);
156 if (
waitpid(pid, &status, 0) != pid) {
157 printf(
"waitpid failed for %s\n", name);
162 return (status >> 8) == 0;
179 printf(
"px4io started OK\n");
183 printf(
"Loading /etc/px4io/px4io.bin\n");
185 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) 191 printf(
"upgraded PX4IO firmware OK\n");
194 printf(
"Failed to upgrade PX4IO firmware\n");
199 printf(
"px4io started OK\n");
211 printf(
"PX4IO CRC failure\n");
212 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) 219 printf(
"PX4IO disarm OK\n");
221 printf(
"PX4IO disarm failed\n");
228 printf(
"px4io restart OK\n");
235 printf(
"PX4IO update failed\n");
249 printf(
"ADC started OK\n");
254 #if HAL_PX4_HAVE_PX4IO 255 if (
state.io_enable.get() != 0) {
260 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) 261 const char *fmu_mode =
"mode_serial";
262 #elif defined(CONFIG_ARCH_BOARD_AEROFC_V1) 263 const char *fmu_mode =
"mode_rcin";
265 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 266 const char *fmu_mode =
"mode_pwm";
268 const char *fmu_mode =
"mode_pwm4";
272 printf(
"fmu %s started OK\n", fmu_mode);
282 #endif // HAL_BOARD_PX4
int printf(const char *fmt,...)
int(* main_fn_t)(int argc, char **)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
int px4io_main(int, char **)
void px4_tone_alarm(const char *tone_string)
struct AP_BoardConfig::@14 state
int waitpid(pid_t, int *, int)
int fmu_main(int, char **)
void px4_setup_safety_mask(void)
virtual void delay(uint16_t ms)=0
AP_HAL::UARTDriver * uartC
virtual void printf(const char *,...) FMT_PRINTF(2
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments)
int close(int fileno)
POSIX Close a file with fileno handel.
int adc_main(int, char **)
void px4_setup_peripherals(void)
int tone_alarm_main(int, char **)
void px4_setup_px4io(void)
void panic(const char *errormsg,...) FMT_PRINTF(1
AP_HAL::Scheduler * scheduler
static bool set_default_by_name(const char *name, float value)
AP_HAL::AnalogIn * analogin
static void sensor_config_error(const char *reason)