APM:Libraries
px4_drivers.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  * AP_BoardConfig - px4 driver loading and setup
17  */
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include "AP_BoardConfig.h"
21 
22 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
23 #include <sys/types.h>
24 #include <sys/stat.h>
25 #include <fcntl.h>
26 #include <unistd.h>
27 #include <drivers/drv_pwm_output.h>
28 #include <drivers/drv_sbus.h>
29 #include <nuttx/arch.h>
30 #include <spawn.h>
31 
32 extern const AP_HAL::HAL& hal;
33 
34 /*
35  declare driver main entry points
36  */
37 extern "C" {
38  int fmu_main(int, char **);
39  int px4io_main(int, char **);
40  int adc_main(int, char **);
41  int tone_alarm_main(int, char **);
42 };
43 
44 /*
45  setup PWM pins
46  */
48 {
49  /* configure the FMU driver for the right number of PWMs */
50  static const struct {
51  uint8_t mode_parm;
52  uint8_t mode_value;
53  uint8_t num_gpios;
54  } mode_table[] = {
55  /* table mapping BRD_PWM_COUNT to ioctl arguments */
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 },
63 #endif
64  };
65  uint8_t mode_parm = (uint8_t)pwm_count.get();
66  uint8_t i;
67  for (i=0; i<ARRAY_SIZE(mode_table); i++) {
68  if (mode_table[i].mode_parm == mode_parm) {
69  break;
70  }
71  }
72  if (i == ARRAY_SIZE(mode_table)) {
73  hal.console->printf("RCOutput: invalid BRD_PWM_COUNT %u\n", mode_parm);
74  } else {
75  int fd = open("/dev/px4fmu", 0);
76  if (fd == -1) {
77  AP_HAL::panic("Unable to open /dev/px4fmu");
78  }
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);
81  }
82  close(fd);
83 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
84  if (mode_table[i].num_gpios < 2) {
85  // reduce change of config mistake where relay and PWM interfere
86  AP_Param::set_default_by_name("RELAY_PIN", -1);
87  AP_Param::set_default_by_name("RELAY_PIN2", -1);
88  }
89 #endif
90  }
91 }
92 
93 /*
94  setup safety switch
95  */
97 {
98 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
99  // setup channels to ignore the armed state
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) {
103  hal.console->printf("IGNORE_SAFETY failed\n");
104  }
105  }
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) {
110  mask >>= 8;
111  }
112  if (ioctl(px4fmu_fd, PWM_SERVO_IGNORE_SAFETY, (uint16_t)mask) != 0) {
113  hal.console->printf("IGNORE_SAFETY failed\n");
114  }
115  close(px4fmu_fd);
116  }
117  if (px4io_fd != -1) {
118  close(px4io_fd);
119  }
120 #endif
121 }
122 
123 extern "C" int waitpid(pid_t, int *, int);
124 
125 /*
126  start one px4 driver
127  */
128 bool AP_BoardConfig::px4_start_driver(main_fn_t main_function, const char *name, const char *arguments)
129 {
130  char *s = strdup(arguments);
131  char *args[10];
132  uint8_t nargs = 0;
133  char *saveptr = nullptr;
134 
135  // parse into separate arguments
136  for (char *tok=strtok_r(s, " ", &saveptr); tok; tok=strtok_r(nullptr, " ", &saveptr)) {
137  args[nargs++] = tok;
138  if (nargs == ARRAY_SIZE(args)-1) {
139  break;
140  }
141  }
142  args[nargs++] = nullptr;
143 
144  printf("Starting driver %s %s\n", name, arguments);
145  pid_t pid;
146 
147  if (task_spawn(&pid, name, main_function, nullptr, nullptr,
148  args, nullptr) != 0) {
149  free(s);
150  printf("Failed to spawn %s\n", name);
151  return false;
152  }
153 
154  // wait for task to exit and gather status
155  int status = -1;
156  if (waitpid(pid, &status, 0) != pid) {
157  printf("waitpid failed for %s\n", name);
158  free(s);
159  return false;
160  }
161  free(s);
162  return (status >> 8) == 0;
163 }
164 
165 /*
166  play a tune
167  */
168 void AP_BoardConfig::px4_tone_alarm(const char *tone_string)
169 {
170  px4_start_driver(tone_alarm_main, "tone_alarm", tone_string);
171 }
172 
173 /*
174  setup px4io, possibly updating firmware
175  */
177 {
178  if (px4_start_driver(px4io_main, "px4io", "start norc")) {
179  printf("px4io started OK\n");
180  } else {
181  // might be in bootloader mode if user held down safety switch
182  // at power on
183  printf("Loading /etc/px4io/px4io.bin\n");
184  px4_tone_alarm("MBABGP");
185 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
186  // we need to close uartC to prevent conflict between bootloader and
187  // uartC reada
188  hal.uartC->end();
189 #endif
190  if (px4_start_driver(px4io_main, "px4io", "update /etc/px4io/px4io.bin")) {
191  printf("upgraded PX4IO firmware OK\n");
192  px4_tone_alarm("MSPAA");
193  } else {
194  printf("Failed to upgrade PX4IO firmware\n");
195  px4_tone_alarm("MNGGG");
196  }
197  hal.scheduler->delay(1000);
198  if (px4_start_driver(px4io_main, "px4io", "start norc")) {
199  printf("px4io started OK\n");
200  } else {
201  sensor_config_error("px4io start failed");
202  }
203  }
204 
205  /*
206  see if we need to update px4io firmware
207  */
208  if (px4_start_driver(px4io_main, "px4io", "checkcrc /etc/px4io/px4io.bin")) {
209  printf("PX4IO CRC OK\n");
210  } else {
211  printf("PX4IO CRC failure\n");
212 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
213  // we need to close uartC to prevent conflict between bootloader and
214  // uartC reada
215  hal.uartC->end();
216 #endif
217  px4_tone_alarm("MBABGP");
218  if (px4_start_driver(px4io_main, "px4io", "safety_on")) {
219  printf("PX4IO disarm OK\n");
220  } else {
221  printf("PX4IO disarm failed\n");
222  }
223  hal.scheduler->delay(1000);
224 
225  if (px4_start_driver(px4io_main, "px4io", "forceupdate 14662 /etc/px4io/px4io.bin")) {
226  hal.scheduler->delay(1000);
227  if (px4_start_driver(px4io_main, "px4io", "start norc")) {
228  printf("px4io restart OK\n");
229  px4_tone_alarm("MSPAA");
230  } else {
231  px4_tone_alarm("MNGGG");
232  sensor_config_error("PX4IO restart failed");
233  }
234  } else {
235  printf("PX4IO update failed\n");
236  px4_tone_alarm("MNGGG");
237  }
238  }
239 }
240 
241 /*
242  setup required peripherals like adc, rcinput and rcoutput
243  */
245 {
246  // always start adc
247  if (px4_start_driver(adc_main, "adc", "start")) {
248  hal.analogin->init();
249  printf("ADC started OK\n");
250  } else {
251  sensor_config_error("no ADC found");
252  }
253 
254 #if HAL_PX4_HAVE_PX4IO
255  if (state.io_enable.get() != 0) {
256  px4_setup_px4io();
257  }
258 #endif
259 
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";
264 #else
265 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
266  const char *fmu_mode = "mode_pwm";
267 #else
268  const char *fmu_mode = "mode_pwm4";
269 #endif
270 #endif
271  if (px4_start_driver(fmu_main, "fmu", fmu_mode)) {
272  printf("fmu %s started OK\n", fmu_mode);
273  } else {
274  sensor_config_error("fmu start failed");
275  }
276 
277  hal.gpio->init();
278  hal.rcin->init();
279  hal.rcout->init();
280 }
281 
282 #endif // HAL_BOARD_PX4
virtual void init()=0
int printf(const char *fmt,...)
Definition: stdio.c:113
void px4_setup_pwm(void)
Definition: px4_drivers.cpp:47
int(* main_fn_t)(int argc, char **)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
int px4io_main(int, char **)
void px4_tone_alarm(const char *tone_string)
struct AP_BoardConfig::@14 state
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
const char * name
Definition: BusTest.cpp:11
int waitpid(pid_t, int *, int)
int fmu_main(int, char **)
void px4_setup_safety_mask(void)
Definition: px4_drivers.cpp:96
virtual void delay(uint16_t ms)=0
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
virtual void init()=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual void init()=0
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.
Definition: posix.c:675
int adc_main(int, char **)
void px4_setup_peripherals(void)
virtual void end()=0
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
void free(void *ptr)
Definition: malloc.c:81
virtual void init()=0
int tone_alarm_main(int, char **)
AP_HAL::GPIO * gpio
Definition: HAL.h:111
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
void px4_setup_px4io(void)
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
AP_HAL::RCInput * rcin
Definition: HAL.h:112
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
static bool set_default_by_name(const char *name, float value)
Definition: AP_Param.cpp:2111
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
static void sensor_config_error(const char *reason)