PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Driver for the PX4IO board. More...
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/sem.hpp>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
#include <debug.h>
#include <time.h>
#include <queue.h>
#include <errno.h>
#include <string.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
#include <math.h>
#include <crc32.h>
#include <arch/board/board.h>
#include <drivers/device/device.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_sbus.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>
#include <rc/dsm.h>
#include <lib/mathlib/mathlib.h>
#include <lib/mixer/MixerGroup.hpp>
#include <lib/mixer/MultirotorMixer/MultirotorMixer.hpp>
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <parameters/param.h>
#include <circuit_breaker/circuit_breaker.h>
#include <systemlib/mavlink_log.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/safety.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/servorail_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/multirotor_motor_limits.h>
#include <uORB/topics/test_motor.h>
#include <modules/px4iofirmware/protocol.h>
#include "uploader.h"
#include "modules/dataman/dataman.h"
#include "px4io_driver.h"
Go to the source code of this file.
Classes | |
class | PX4IO |
The PX4IO class. More... | |
struct | PX4IO::MotorTest |
Macros | |
#define | PX4IO_SET_DEBUG _IOC(0xff00, 0) |
#define | PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1) |
#define | PX4IO_REBOOT_BOOTLOADER _IOC(0xff00, 2) |
#define | PX4IO_CHECK_CRC _IOC(0xff00, 3) |
#define | ORB_CHECK_INTERVAL 200000 |
#define | IO_POLL_INTERVAL 20000 |
#define | PX4IO_DEVICE_PATH "/dev/px4io" |
Functions | |
__EXPORT int | px4io_main (int argc, char *argv[]) |
Variables | |
static constexpr unsigned | UPDATE_INTERVAL_MIN {2} |
static constexpr unsigned | UPDATE_INTERVAL_MAX {100} |
Driver for the PX4IO board.
PX4IO is connected via DMA enabled high-speed UART.
Definition in file px4io.cpp.
#define IO_POLL_INTERVAL 20000 |
Definition at line 116 of file px4io.cpp.
Referenced by PX4IO::task_main().
#define ORB_CHECK_INTERVAL 200000 |
Definition at line 115 of file px4io.cpp.
Referenced by PX4IO::task_main().
#define PX4IO_CHECK_CRC _IOC(0xff00, 3) |
Definition at line 110 of file px4io.cpp.
Referenced by PX4IO::ioctl(), and PX4IO::set_update_rate().
#define PX4IO_DEVICE_PATH "/dev/px4io" |
Definition at line 470 of file px4io.cpp.
Referenced by PX4IO::set_update_rate().
#define PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1) |
Definition at line 108 of file px4io.cpp.
Referenced by PX4IO::ioctl(), and px4io_main().
#define PX4IO_REBOOT_BOOTLOADER _IOC(0xff00, 2) |
Definition at line 109 of file px4io.cpp.
Referenced by PX4IO::ioctl(), and px4io_main().
#define PX4IO_SET_DEBUG _IOC(0xff00, 0) |
Definition at line 107 of file px4io.cpp.
Referenced by PX4IO::ioctl(), and px4io_main().
int px4io_main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 3396 of file px4io.cpp.
References PX4IO::detect(), errx, fn, ets_airspeed::g_dev, Airspeed::ioctl(), OK, PWM_SERVO_SET_FORCE_SAFETY_OFF, PWM_SERVO_SET_FORCE_SAFETY_ON, PX4IO::PX4IO(), PX4IO_INAIR_RESTART_ENABLE, PX4IO_REBOOT_BOOTLOADER, PX4IO_SET_DEBUG, RC_INPUT_ENABLE_RSSI_ANALOG, RC_INPUT_ENABLE_RSSI_PWM, SBUS_SET_PROTO_VERSION, start(), lps25h::test(), PX4IO_Uploader::upload(), and warnx.
Referenced by PX4IO::set_update_rate().
|
static |
Definition at line 113 of file px4io.cpp.
Referenced by PX4IO::set_update_rate(), and PX4IO::task_main().
|
static |
Definition at line 112 of file px4io.cpp.
Referenced by PX4IO::set_update_rate(), and PX4IO::task_main().