forked from Archive/PX4-Autopilot
rename files and add navio target
This commit is contained in:
parent
b871b322d2
commit
506d1855ff
3
Makefile
3
Makefile
|
@ -211,6 +211,9 @@ posix_rpi2_release:
|
|||
posix_bebop_default:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_navio2_release:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix: posix_sitl_default
|
||||
|
||||
broadcast: posix_sitl_broadcast
|
||||
|
|
|
@ -0,0 +1,114 @@
|
|||
include(posix/px4_impl_posix)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake)
|
||||
|
||||
set(CMAKE_PROGRAM_PATH
|
||||
"${RPI_TOOLCHAIN_DIR}/gcc-linaro-arm-linux-gnueabihf-raspbian/bin"
|
||||
${CMAKE_PROGRAM_PATH}
|
||||
)
|
||||
|
||||
# This definition allows to differentiate if this just the usual POSIX build
|
||||
# or if it is for the RPi.
|
||||
add_definitions(
|
||||
-D__PX4_POSIX_RPI2
|
||||
-D__LINUX
|
||||
)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
modules/sensors
|
||||
platforms/posix/drivers/df_mpu9250_wrapper
|
||||
platforms/posix/drivers/df_lsm9ds1_wrapper
|
||||
platforms/posix/drivers/df_ms5611_wrapper
|
||||
platforms/posix/drivers/df_hmc5883_wrapper
|
||||
platforms/posix/drivers/df_trone_wrapper
|
||||
platforms/posix/drivers/df_isl29501_wrapper
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
systemcmds/esc_calib
|
||||
systemcmds/topic_listener
|
||||
systemcmds/perf
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
#modules/attitude_estimator_ekf
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
modules/land_detector
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
|
||||
#
|
||||
# PX4 drivers
|
||||
#
|
||||
drivers/gps
|
||||
drivers/navio_sysfs_rc_in
|
||||
drivers/navio_sysfs_pwm_out
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/geo
|
||||
lib/ecl
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/external_lgpl
|
||||
lib/conversion
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# POSIX
|
||||
#
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
)
|
||||
|
||||
set(config_df_driver_list
|
||||
mpu9250
|
||||
lsm9ds1
|
||||
ms5611
|
||||
hmc5883
|
||||
trone
|
||||
isl29501
|
||||
)
|
|
@ -31,13 +31,12 @@
|
|||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__pwm_out
|
||||
MAIN pwm_out
|
||||
MODULE drivers__navio_sysfs_pwm_out
|
||||
MAIN navio_sysfs_pwm_out
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
-DMAVLINK_COMM_NUM_BUFFERS=1
|
||||
SRCS
|
||||
pwm_out.cpp
|
||||
navio_sysfs_pwm_out.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
|
@ -50,7 +50,7 @@
|
|||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/pwm_limit/pwm_limit.h>
|
||||
|
||||
namespace pwm_out
|
||||
namespace navio_sysfs_pwm_out
|
||||
{
|
||||
static px4_task_t _task_handle = -1;
|
||||
volatile bool _task_should_exit = false;
|
||||
|
@ -431,12 +431,12 @@ void usage()
|
|||
PX4_INFO(" pwm_out status");
|
||||
}
|
||||
|
||||
} // namespace pwm_out
|
||||
} // namespace navio_sysfs_pwm_out
|
||||
|
||||
/* driver 'main' command */
|
||||
extern "C" __EXPORT int pwm_out_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int navio_sysfs_pwm_out_main(int argc, char *argv[]);
|
||||
|
||||
int pwm_out_main(int argc, char *argv[])
|
||||
int navio_sysfs_pwm_out_main(int argc, char *argv[])
|
||||
{
|
||||
const char *device = nullptr;
|
||||
int ch;
|
||||
|
@ -456,43 +456,43 @@ int pwm_out_main(int argc, char *argv[])
|
|||
switch (ch) {
|
||||
case 'd':
|
||||
device = myoptarg;
|
||||
strncpy(pwm_out::_device, device, strlen(device));
|
||||
strncpy(navio_sysfs_pwm_out::_device, device, strlen(device));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// gets the parameters for the esc's pwm
|
||||
param_get(param_find("PWM_DISARMED"), &pwm_out::_pwm_disarmed);
|
||||
param_get(param_find("PWM_MIN"), &pwm_out::_pwm_min);
|
||||
param_get(param_find("PWM_MAX"), &pwm_out::_pwm_max);
|
||||
param_get(param_find("PWM_DISARMED"), &navio_sysfs_pwm_out::_pwm_disarmed);
|
||||
param_get(param_find("PWM_MIN"), &navio_sysfs_pwm_out::_pwm_min);
|
||||
param_get(param_find("PWM_MAX"), &navio_sysfs_pwm_out::_pwm_max);
|
||||
|
||||
/*
|
||||
* Start/load the driver.
|
||||
*/
|
||||
if (!strcmp(verb, "start")) {
|
||||
if (pwm_out::_is_running) {
|
||||
if (navio_sysfs_pwm_out::_is_running) {
|
||||
PX4_WARN("pwm_out already running");
|
||||
return 1;
|
||||
}
|
||||
|
||||
pwm_out::start();
|
||||
navio_sysfs_pwm_out::start();
|
||||
}
|
||||
|
||||
else if (!strcmp(verb, "stop")) {
|
||||
if (!pwm_out::_is_running) {
|
||||
if (!navio_sysfs_pwm_out::_is_running) {
|
||||
PX4_WARN("pwm_out is not running");
|
||||
return 1;
|
||||
}
|
||||
|
||||
pwm_out::stop();
|
||||
navio_sysfs_pwm_out::stop();
|
||||
}
|
||||
|
||||
else if (!strcmp(verb, "status")) {
|
||||
PX4_WARN("pwm_out is %s", pwm_out::_is_running ? "running" : "not running");
|
||||
PX4_WARN("pwm_out is %s", navio_sysfs_pwm_out::_is_running ? "running" : "not running");
|
||||
return 0;
|
||||
|
||||
} else {
|
||||
pwm_out::usage();
|
||||
navio_sysfs_pwm_out::usage();
|
||||
return 1;
|
||||
}
|
||||
|
|
@ -31,12 +31,12 @@
|
|||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE modules__rcinput
|
||||
MAIN rcinput
|
||||
MODULE drivers__navio_sysfs_rc_in
|
||||
MAIN navio_sysfs_rc_in
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS -Os
|
||||
SRCS
|
||||
rcinput.cpp
|
||||
navio_sysfs_rc_in.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
|
@ -47,10 +47,10 @@
|
|||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
|
||||
namespace rcinput
|
||||
namespace navio_sysfs_rc_in
|
||||
{
|
||||
|
||||
extern "C" __EXPORT int rcinput_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int navio_sysfs_rc_in_main(int argc, char *argv[]);
|
||||
|
||||
#define RCINPUT_DEVICE_PATH_BASE "/sys/kernel/rcio/rcin"
|
||||
|
||||
|
@ -61,20 +61,20 @@ class RcInput
|
|||
{
|
||||
public:
|
||||
RcInput() :
|
||||
_shouldExit(false),
|
||||
_isRunning(false),
|
||||
_work{},
|
||||
_rcinput_pub(nullptr),
|
||||
_channels(8), //D8R-II plus
|
||||
_data{}
|
||||
{
|
||||
memset(_ch_fd, 0, sizeof(_ch_fd));
|
||||
}
|
||||
~RcInput()
|
||||
{
|
||||
work_cancel(HPWORK, &_work);
|
||||
_isRunning = false;
|
||||
}
|
||||
_shouldExit(false),
|
||||
_isRunning(false),
|
||||
_work{},
|
||||
_rcinput_pub(nullptr),
|
||||
_channels(8), //D8R-II plus
|
||||
_data{}
|
||||
{
|
||||
memset(_ch_fd, 0, sizeof(_ch_fd));
|
||||
}
|
||||
~RcInput()
|
||||
{
|
||||
work_cancel(HPWORK, &_work);
|
||||
_isRunning = false;
|
||||
}
|
||||
|
||||
/* @return 0 on success, -errno on failure */
|
||||
int start();
|
||||
|
@ -85,49 +85,53 @@ public:
|
|||
/* Trampoline for the work queue. */
|
||||
static void cycle_trampoline(void *arg);
|
||||
|
||||
bool isRunning() { return _isRunning; }
|
||||
bool isRunning() { return _isRunning; }
|
||||
|
||||
private:
|
||||
void _cycle();
|
||||
void _measure();
|
||||
void _cycle();
|
||||
void _measure();
|
||||
|
||||
bool _shouldExit;
|
||||
bool _isRunning;
|
||||
struct work_s _work;
|
||||
bool _shouldExit;
|
||||
bool _isRunning;
|
||||
struct work_s _work;
|
||||
|
||||
orb_advert_t _rcinput_pub;
|
||||
orb_advert_t _rcinput_pub;
|
||||
|
||||
int _channels;
|
||||
int _ch_fd[input_rc_s::RC_INPUT_MAX_CHANNELS];
|
||||
struct input_rc_s _data;
|
||||
int _channels;
|
||||
int _ch_fd[input_rc_s::RC_INPUT_MAX_CHANNELS];
|
||||
struct input_rc_s _data;
|
||||
|
||||
int navio_rc_init();
|
||||
};
|
||||
|
||||
int RcInput::navio_rc_init()
|
||||
{
|
||||
int i;
|
||||
char *buf;
|
||||
int i;
|
||||
char *buf;
|
||||
|
||||
for (i = 0; i < _channels; ++i) {
|
||||
::asprintf(&buf, "%s/ch%d", RCINPUT_DEVICE_PATH_BASE, i);
|
||||
int fd = ::open(buf, O_RDONLY);
|
||||
::free(buf);
|
||||
if (fd < 0) {
|
||||
PX4_WARN("error: open %d failed", i);
|
||||
break;
|
||||
}
|
||||
_ch_fd[i] = fd;
|
||||
}
|
||||
for (; i < input_rc_s::RC_INPUT_MAX_CHANNELS; ++i) {
|
||||
_data.values[i] = UINT16_MAX;
|
||||
}
|
||||
for (i = 0; i < _channels; ++i) {
|
||||
::asprintf(&buf, "%s/ch%d", RCINPUT_DEVICE_PATH_BASE, i);
|
||||
int fd = ::open(buf, O_RDONLY);
|
||||
::free(buf);
|
||||
|
||||
_rcinput_pub = orb_advertise(ORB_ID(input_rc), &_data);
|
||||
if (_rcinput_pub == nullptr) {
|
||||
PX4_WARN("error: advertise failed");
|
||||
return -1;
|
||||
}
|
||||
if (fd < 0) {
|
||||
PX4_WARN("error: open %d failed", i);
|
||||
break;
|
||||
}
|
||||
|
||||
_ch_fd[i] = fd;
|
||||
}
|
||||
|
||||
for (; i < input_rc_s::RC_INPUT_MAX_CHANNELS; ++i) {
|
||||
_data.values[i] = UINT16_MAX;
|
||||
}
|
||||
|
||||
_rcinput_pub = orb_advertise(ORB_ID(input_rc), &_data);
|
||||
|
||||
if (_rcinput_pub == nullptr) {
|
||||
PX4_WARN("error: advertise failed");
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -140,66 +144,69 @@ int RcInput::start()
|
|||
|
||||
if (result != 0) {
|
||||
PX4_WARN("error: RC initialization failed");
|
||||
return -1;
|
||||
return -1;
|
||||
}
|
||||
|
||||
_isRunning = true;
|
||||
_isRunning = true;
|
||||
result = work_queue(HPWORK, &_work, (worker_t)&RcInput::cycle_trampoline, this, 0);
|
||||
if (result == -1) {
|
||||
_isRunning = false;
|
||||
}
|
||||
|
||||
return result;
|
||||
if (result == -1) {
|
||||
_isRunning = false;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
void RcInput::stop()
|
||||
{
|
||||
_shouldExit = true;
|
||||
_shouldExit = true;
|
||||
}
|
||||
|
||||
void RcInput::cycle_trampoline(void *arg)
|
||||
{
|
||||
RcInput *dev = reinterpret_cast<RcInput *>(arg);
|
||||
dev->_cycle();
|
||||
RcInput *dev = reinterpret_cast<RcInput *>(arg);
|
||||
dev->_cycle();
|
||||
}
|
||||
|
||||
void RcInput::_cycle()
|
||||
{
|
||||
_measure();
|
||||
_measure();
|
||||
|
||||
if (!_shouldExit) {
|
||||
work_queue(HPWORK, &_work, (worker_t)&RcInput::cycle_trampoline, this,
|
||||
USEC2TICK(RCINPUT_MEASURE_INTERVAL_US));
|
||||
}
|
||||
if (!_shouldExit) {
|
||||
work_queue(HPWORK, &_work, (worker_t)&RcInput::cycle_trampoline, this,
|
||||
USEC2TICK(RCINPUT_MEASURE_INTERVAL_US));
|
||||
}
|
||||
}
|
||||
|
||||
void RcInput::_measure(void)
|
||||
{
|
||||
uint64_t ts;
|
||||
char buf[12];
|
||||
uint64_t ts;
|
||||
char buf[12];
|
||||
|
||||
for (int i = 0; i < _channels; ++i) {
|
||||
int res;
|
||||
if ((res = ::pread(_ch_fd[i], buf, sizeof(buf) - 1, 0)) < 0) {
|
||||
_data.values[i] = UINT16_MAX;
|
||||
continue;
|
||||
}
|
||||
buf[sizeof(buf) -1] = '\0';
|
||||
for (int i = 0; i < _channels; ++i) {
|
||||
int res;
|
||||
|
||||
_data.values[i] = atoi(buf);
|
||||
}
|
||||
if ((res = ::pread(_ch_fd[i], buf, sizeof(buf) - 1, 0)) < 0) {
|
||||
_data.values[i] = UINT16_MAX;
|
||||
continue;
|
||||
}
|
||||
|
||||
ts = hrt_absolute_time();
|
||||
_data.timestamp_publication = ts;
|
||||
_data.timestamp_last_signal = ts;
|
||||
_data.channel_count = _channels;
|
||||
_data.rssi = 100;
|
||||
_data.rc_lost_frame_count = 0;
|
||||
_data.rc_total_frame_count = 1;
|
||||
_data.rc_ppm_frame_length = 100;
|
||||
_data.rc_failsafe = false;
|
||||
_data.rc_lost = false;
|
||||
_data.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM;
|
||||
buf[sizeof(buf) - 1] = '\0';
|
||||
|
||||
_data.values[i] = atoi(buf);
|
||||
}
|
||||
|
||||
ts = hrt_absolute_time();
|
||||
_data.timestamp_publication = ts;
|
||||
_data.timestamp_last_signal = ts;
|
||||
_data.channel_count = _channels;
|
||||
_data.rssi = 100;
|
||||
_data.rc_lost_frame_count = 0;
|
||||
_data.rc_total_frame_count = 1;
|
||||
_data.rc_ppm_frame_length = 100;
|
||||
_data.rc_failsafe = false;
|
||||
_data.rc_lost = false;
|
||||
_data.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM;
|
||||
|
||||
orb_publish(ORB_ID(input_rc), _rcinput_pub, &_data);
|
||||
}
|
||||
|
@ -216,12 +223,12 @@ usage(const char *reason)
|
|||
PX4_ERR("%s", reason);
|
||||
}
|
||||
|
||||
PX4_INFO("usage: rcinput {start|stop|status}");
|
||||
PX4_INFO("usage: navio_sysfs_rc_in {start|stop|status}");
|
||||
}
|
||||
|
||||
static RcInput *rc_input = nullptr;
|
||||
|
||||
int rcinput_main(int argc, char *argv[])
|
||||
int navio_sysfs_rc_in_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2) {
|
||||
usage("missing command");
|
||||
|
@ -294,4 +301,4 @@ int rcinput_main(int argc, char *argv[])
|
|||
|
||||
}
|
||||
|
||||
}; // namespace rcinput
|
||||
}; // namespace navio_sysfs_rc_in
|
|
@ -59,7 +59,7 @@ __END_DECLS
|
|||
# define HW_ARCH "LINUXTEST"
|
||||
#elif defined(CONFIG_ARCH_BOARD_EXCELSIOR)
|
||||
# define HW_ARCH "LINUXTEST"
|
||||
#elif defined(CONFIG_ARCH_BOARD_RPI2)
|
||||
#elif defined(CONFIG_ARCH_BOARD_RPI2) || defined(CONFIG_ARCH_BOARD_NAVIO2)
|
||||
# define HW_ARCH "LINUXTEST"
|
||||
#elif defined(CONFIG_ARCH_BOARD_BEBOP)
|
||||
# define HW_ARCH "LINUXTEST"
|
||||
|
|
Loading…
Reference in New Issue