3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \ 4 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE 15 using namespace Linux;
19 #define RCIN_SYSFS_PATH "/sys/kernel/rcio/rcin" 40 if (::pread(
channels[i], buffer,
sizeof(buffer) - 1, 0) <= 0) {
45 buffer[
sizeof(
buffer) - 1] =
'\0';
70 int fd =
::open(channel_path, O_RDONLY|O_CLOEXEC);
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
static uint8_t buffer[SRXL_FRAMELEN_MAX]
static const AP_HAL::HAL & hal
Common definitions and utility routines for the ArduPilot libraries.
int asprintf(char **strp, const char *fmt,...)
void panic(const char *errormsg,...) FMT_PRINTF(1