APM:Libraries
RCInput_Navio2.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \
4  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
5 
6 #include <cstdio>
7 #include <unistd.h>
8 #include <fcntl.h>
9 #include <cstdlib>
10 
11 #include <AP_Common/AP_Common.h>
12 
13 #include "RCInput_Navio2.h"
14 
15 using namespace Linux;
16 
17 extern const AP_HAL::HAL& hal;
18 
19 #define RCIN_SYSFS_PATH "/sys/kernel/rcio/rcin"
20 
22 {
23  for (size_t i = 0; i < ARRAY_SIZE(channels); i++) {
24  channels[i] = open_channel(i);
25  if (channels[i] < 0) {
26  AP_HAL::panic("[RCInput_Navio2]: failed to open channels\n");
27  }
28  }
29 }
30 
32 {
33  if (AP_HAL::micros() - _last_timestamp < 10000) {
34  return;
35  }
36 
37  char buffer[12];
38 
39  for (size_t i = 0; i < ARRAY_SIZE(channels); i++) {
40  if (::pread(channels[i], buffer, sizeof(buffer) - 1, 0) <= 0) {
41  /* We ignore error in order not to spam the console */
42  continue;
43  }
44 
45  buffer[sizeof(buffer) - 1] = '\0';
46  periods[i] = atoi(buffer);
47  }
48 
50 
52 }
53 
55 {
56 
57 }
58 
60 {
61 }
62 
64 {
65  char *channel_path;
66  if (asprintf(&channel_path, "%s/ch%d", RCIN_SYSFS_PATH, channel) == -1) {
67  AP_HAL::panic("[RCInput_Navio2]: not enough memory\n");
68  }
69 
70  int fd = ::open(channel_path, O_RDONLY|O_CLOEXEC);
71 
72  free(channel_path);
73 
74  return fd;
75 }
76 
77 
78 #endif
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
int channels[CHANNEL_COUNT]
void _timer_tick(void) override
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
#define RCIN_SYSFS_PATH
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
uint16_t periods[ARRAY_SIZE(channels)]
void free(void *ptr)
Definition: malloc.c:81
Common definitions and utility routines for the ArduPilot libraries.
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void _update_periods(uint16_t *periods, uint8_t len)
Definition: RCInput.cpp:333
uint32_t micros()
Definition: system.cpp:152
void init() override