17 changed files with 558 additions and 43 deletions
@ -0,0 +1,88 @@
@@ -0,0 +1,88 @@
|
||||
#!nsh |
||||
# |
||||
# PX4FMU startup script for logging purposes |
||||
# |
||||
|
||||
# |
||||
# Try to mount the microSD card. |
||||
# |
||||
echo "[init] looking for microSD..." |
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd |
||||
then |
||||
echo "[init] card mounted at /fs/microsd" |
||||
# Start playing the startup tune |
||||
tone_alarm start |
||||
else |
||||
echo "[init] no microSD card found" |
||||
# Play SOS |
||||
tone_alarm error |
||||
fi |
||||
|
||||
uorb start |
||||
|
||||
# |
||||
# Start sensor drivers here. |
||||
# |
||||
|
||||
ms5611 start |
||||
adc start |
||||
|
||||
# mag might be external |
||||
if hmc5883 start |
||||
then |
||||
echo "using HMC5883" |
||||
fi |
||||
|
||||
if mpu6000 start |
||||
then |
||||
echo "using MPU6000" |
||||
fi |
||||
|
||||
if l3gd20 start |
||||
then |
||||
echo "using L3GD20(H)" |
||||
fi |
||||
|
||||
if lsm303d start |
||||
then |
||||
set BOARD fmuv2 |
||||
else |
||||
set BOARD fmuv1 |
||||
fi |
||||
|
||||
# Start airspeed sensors |
||||
if meas_airspeed start |
||||
then |
||||
echo "using MEAS airspeed sensor" |
||||
else |
||||
if ets_airspeed start |
||||
then |
||||
echo "using ETS airspeed sensor (bus 3)" |
||||
else |
||||
if ets_airspeed start -b 1 |
||||
then |
||||
echo "Using ETS airspeed sensor (bus 1)" |
||||
fi |
||||
fi |
||||
fi |
||||
|
||||
# |
||||
# Start the sensor collection task. |
||||
# IMPORTANT: this also loads param offsets |
||||
# ALWAYS start this task before the |
||||
# preflight_check. |
||||
# |
||||
if sensors start |
||||
then |
||||
echo "SENSORS STARTED" |
||||
fi |
||||
|
||||
sdlog2 start -r 250 -e -b 16 |
||||
|
||||
if sercon |
||||
then |
||||
echo "[init] USB interface connected" |
||||
|
||||
# Try to get an USB console |
||||
nshterm /dev/ttyACM0 & |
||||
fi |
@ -0,0 +1,157 @@
@@ -0,0 +1,157 @@
|
||||
#
|
||||
# Makefile for the px4fmu_default configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS, copy the px4iov2 firmware into
|
||||
# the ROMFS if it's available
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_logging
|
||||
ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v2_default.bin
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/stm32/adc
|
||||
MODULES += drivers/stm32/tone_alarm
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/px4fmu
|
||||
MODULES += drivers/px4io
|
||||
MODULES += drivers/boards/px4fmu-v2
|
||||
MODULES += drivers/rgbled
|
||||
MODULES += drivers/mpu6000
|
||||
MODULES += drivers/lsm303d
|
||||
MODULES += drivers/l3gd20
|
||||
MODULES += drivers/hmc5883
|
||||
MODULES += drivers/ms5611
|
||||
MODULES += drivers/mb12xx
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/hott/hott_telemetry
|
||||
MODULES += drivers/hott/hott_sensors
|
||||
MODULES += drivers/blinkm
|
||||
MODULES += drivers/roboclaw
|
||||
MODULES += drivers/airspeed
|
||||
MODULES += drivers/ets_airspeed
|
||||
MODULES += drivers/meas_airspeed
|
||||
MODULES += modules/sensors
|
||||
|
||||
# Needs to be burned to the ground and re-written; for now,
|
||||
# just don't build it.
|
||||
#MODULES += drivers/mkblctrl
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/ramtron
|
||||
MODULES += systemcmds/bl_update
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/preflight_check
|
||||
MODULES += systemcmds/pwm
|
||||
MODULES += systemcmds/esc_calib
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/top
|
||||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
MODULES += modules/commander
|
||||
MODULES += modules/navigator
|
||||
MODULES += modules/mavlink
|
||||
MODULES += modules/mavlink_onboard
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/attitude_estimator_so3
|
||||
MODULES += modules/att_pos_estimator_ekf
|
||||
MODULES += modules/position_estimator_inav
|
||||
MODULES += examples/flow_position_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
#MODULES += modules/segway # XXX Needs GCC 4.7 fix
|
||||
MODULES += modules/fw_pos_control_l1
|
||||
MODULES += modules/fw_att_control
|
||||
MODULES += modules/multirotor_att_control
|
||||
MODULES += modules/multirotor_pos_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
MODULES += modules/sdlog2
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
#MODULES += modules/unit_test
|
||||
#MODULES += modules/commander/commander_tests
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/controllib
|
||||
MODULES += modules/uORB
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/ecl
|
||||
MODULES += lib/external_lgpl
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/conversion
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
#MODULES += examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/hello_sky
|
||||
MODULES += examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/daemon
|
||||
#MODULES += examples/px4_daemon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/debug_values
|
||||
#MODULES += examples/px4_mavlink_debug
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
|
||||
#MODULES += examples/fixedwing_control
|
||||
|
||||
# Hardware test
|
||||
#MODULES += examples/hwtest
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
# In general, these should move to modules over time.
|
||||
#
|
||||
# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B |
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef |
||||
|
||||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, sercon, , 2048, sercon_main ) \
|
||||
$(call _B, serdis, , 2048, serdis_main )
|
@ -0,0 +1,146 @@
@@ -0,0 +1,146 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file test_ppm_loopback.c |
||||
* Tests the PWM outputs and PPM input |
||||
* |
||||
*/ |
||||
|
||||
#include <nuttx/config.h> |
||||
|
||||
#include <sys/types.h> |
||||
|
||||
#include <stdio.h> |
||||
#include <poll.h> |
||||
#include <stdlib.h> |
||||
#include <unistd.h> |
||||
#include <fcntl.h> |
||||
#include <errno.h> |
||||
#include <debug.h> |
||||
|
||||
#include <arch/board/board.h> |
||||
#include <drivers/drv_pwm_output.h> |
||||
#include <drivers/drv_rc_input.h> |
||||
#include <systemlib/err.h> |
||||
|
||||
#include "tests.h" |
||||
|
||||
#include <math.h> |
||||
#include <float.h> |
||||
|
||||
int test_rc(int argc, char *argv[]) |
||||
{ |
||||
|
||||
int _rc_sub = orb_subscribe(ORB_ID(input_rc)); |
||||
|
||||
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */ |
||||
struct rc_input_values rc_input; |
||||
struct rc_input_values rc_last; |
||||
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input); |
||||
usleep(100000); |
||||
|
||||
/* open PPM input and expect values close to the output values */ |
||||
|
||||
bool rc_updated; |
||||
orb_check(_rc_sub, &rc_updated); |
||||
|
||||
warnx("Reading PPM values - press any key to abort"); |
||||
warnx("This test guarantees: 10 Hz update rates, no glitches (channel values), no channel count changes."); |
||||
|
||||
if (rc_updated) { |
||||
|
||||
/* copy initial set */ |
||||
for (unsigned i = 0; i < rc_input.channel_count; i++) { |
||||
rc_last.values[i] = rc_input.values[i]; |
||||
} |
||||
|
||||
rc_last.channel_count = rc_input.channel_count; |
||||
|
||||
/* poll descriptor */ |
||||
struct pollfd fds[2]; |
||||
fds[0].fd = _rc_sub; |
||||
fds[0].events = POLLIN; |
||||
fds[1].fd = 0; |
||||
fds[1].events = POLLIN; |
||||
|
||||
while (true) { |
||||
|
||||
int ret = poll(fds, 2, 200); |
||||
|
||||
if (ret > 0) { |
||||
|
||||
if (fds[0].revents & POLLIN) { |
||||
|
||||
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input); |
||||
|
||||
/* go and check values */ |
||||
for (unsigned i = 0; i < rc_input.channel_count; i++) { |
||||
if (fabsf(rc_input.values[i] - rc_last.values[i]) > 20) { |
||||
warnx("comparison fail: RC: %d, expected: %d", rc_input.values[i], rc_last.values[i]); |
||||
(void)close(_rc_sub); |
||||
return ERROR; |
||||
} |
||||
|
||||
rc_last.values[i] = rc_input.values[i]; |
||||
} |
||||
|
||||
if (rc_last.channel_count != rc_input.channel_count) { |
||||
warnx("channel count mismatch: last: %d, now: %d", rc_last.channel_count, rc_input.channel_count); |
||||
(void)close(_rc_sub); |
||||
return ERROR; |
||||
} |
||||
|
||||
if (hrt_absolute_time() - rc_input.timestamp > 100000) { |
||||
warnx("TIMEOUT, less than 10 Hz updates"); |
||||
(void)close(_rc_sub); |
||||
return ERROR; |
||||
}
|
||||
|
||||
} else { |
||||
/* key pressed, bye bye */ |
||||
return 0; |
||||
} |
||||
|
||||
} |
||||
} |
||||
|
||||
} else { |
||||
warnx("failed reading RC input data"); |
||||
return ERROR; |
||||
} |
||||
|
||||
warnx("PPM CONTINUITY TEST PASSED SUCCESSFULLY!"); |
||||
|
||||
return 0; |
||||
} |
Loading…
Reference in new issue