mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-18 06:07:36 +08:00
Merge branch 'master' into beta
This commit is contained in:
+1
-1
@@ -47,4 +47,4 @@ unittests/build
|
||||
*.generated.h
|
||||
.vagrant
|
||||
*.pretty
|
||||
|
||||
xcode
|
||||
|
||||
@@ -16,3 +16,6 @@
|
||||
[submodule "unittests/gtest"]
|
||||
path = unittests/gtest
|
||||
url = https://github.com/sjwilks/gtest.git
|
||||
[submodule "src/lib/eigen"]
|
||||
path = src/lib/eigen
|
||||
url = https://github.com/PX4/eigen.git
|
||||
|
||||
+41
-21
@@ -3,28 +3,51 @@
|
||||
|
||||
language: cpp
|
||||
|
||||
# use travis-ci docker based infrastructure
|
||||
sudo: false
|
||||
|
||||
cache:
|
||||
directories:
|
||||
- $HOME/.ccache
|
||||
|
||||
addons:
|
||||
apt:
|
||||
sources:
|
||||
- ubuntu-toolchain-r-test
|
||||
packages:
|
||||
- build-essential
|
||||
- ccache
|
||||
- cmake
|
||||
- g++-4.8
|
||||
- gcc-4.8
|
||||
- genromfs
|
||||
- libc6-i386
|
||||
- libncurses5-dev
|
||||
- python-argparse
|
||||
- python-empy
|
||||
- python-serial
|
||||
- s3cmd
|
||||
- texinfo
|
||||
- zlib1g-dev
|
||||
|
||||
before_script:
|
||||
- sudo add-apt-repository --yes ppa:ubuntu-toolchain-r/test
|
||||
- sudo apt-get update -qq
|
||||
- if [ "$CXX" = "g++" ]; then sudo apt-get install -qq g++-4.8 gcc-4.8 libstdc++-4.8-dev; fi
|
||||
- if [ "$CXX" = "g++" ]; then export CXX="g++-4.8" CC="gcc-4.8"; fi
|
||||
# Travis specific tools
|
||||
- sudo apt-get install s3cmd grep zip mailutils
|
||||
# General toolchain dependencies
|
||||
- sudo apt-get install libc6:i386 libgcc1:i386 gcc-4.6-base:i386 libstdc++5:i386 libstdc++6:i386
|
||||
- sudo apt-get install python-serial python-argparse python-empy
|
||||
- sudo apt-get install flex bison libncurses5-dev autoconf texinfo build-essential libtool zlib1g-dev genromfs git wget cmake
|
||||
- pushd .
|
||||
- cd ~
|
||||
- wget https://launchpadlibrarian.net/174121628/gcc-arm-none-eabi-4_7-2014q2-20140408-linux.tar.bz2
|
||||
- tar -jxf gcc-arm-none-eabi-4_7-2014q2-20140408-linux.tar.bz2
|
||||
- exportline="export PATH=$HOME/gcc-arm-none-eabi-4_7-2014q2/bin:\$PATH"
|
||||
- wget https://launchpadlibrarian.net/186124160/gcc-arm-none-eabi-4_8-2014q3-20140805-linux.tar.bz2
|
||||
- tar -jxf gcc-arm-none-eabi-4_8-2014q3-20140805-linux.tar.bz2
|
||||
- exportline="export PATH=$HOME/gcc-arm-none-eabi-4_8-2014q3/bin:\$PATH"
|
||||
- if grep -Fxq "$exportline" ~/.profile; then echo nothing to do ; else echo $exportline >> ~/.profile; fi
|
||||
- . ~/.profile
|
||||
- popd
|
||||
|
||||
git:
|
||||
depth: 500
|
||||
# setup ccache
|
||||
- mkdir -p ~/bin
|
||||
- ln -s /usr/bin/ccache ~/bin/arm-none-eabi-g++
|
||||
- ln -s /usr/bin/ccache ~/bin/arm-none-eabi-gcc
|
||||
- ln -s /usr/bin/ccache ~/bin/g++-4.8
|
||||
- ln -s /usr/bin/ccache ~/bin/gcc-4.8
|
||||
- export PATH=~/bin:$PATH
|
||||
|
||||
env:
|
||||
global:
|
||||
@@ -33,13 +56,9 @@ env:
|
||||
# AWS SECRET: $PX4_AWS_SECRET
|
||||
- secure: "h6oajlW68dWIr+wZhO58Dv6e68dZHrBLVA6lPXZmheFQBW6Xam1HuLGA0LOW6cL9TnrAsOZ8g4goB58eMQnMEijFZKi3mhRwZhd/Xjq/ZGJOWBUrLoQHZUw2dQk5ja5vmUlKEoQnFZjDuMjx8KfX5ZMNy8A3yssWZtJYHD8c+bk="
|
||||
- PX4_AWS_BUCKET=px4-travis
|
||||
- PX4_EMAIL_SUBJECT="Travis CI result"
|
||||
# Email address: $PX4_EMAIL
|
||||
- secure: "ei3hKAw6Pk+vEkQBI5Y2Ak74BRAaXcK2UHVnVadviBHI4EVPwn1YGP6A4Y0wnLe4U7ETTl0UiijRoVxyDW0Mq896Pv0siw02amNpjSZZYu+RfN1+//MChB48OxsLDirUdHVrULhl/bOARM02h2Bg28jDE2g7IqmJwg3em3oMbjU="
|
||||
- PX4_REPORT=report.txt
|
||||
- BUILD_URI=https://px4-travis.s3.amazonaws.com/archives/Firmware/$TRAVIS_BRANCH/$TRAVIS_BUILD_ID/Firmware.zip
|
||||
|
||||
script:
|
||||
- ccache -z
|
||||
- arm-none-eabi-gcc --version
|
||||
- echo 'Running Tests..' && echo -en 'travis_fold:start:script.1\\r'
|
||||
- make tests
|
||||
@@ -47,9 +66,11 @@ script:
|
||||
- echo -en 'travis_fold:end:script.1\\r'
|
||||
- echo 'Building NuttX..' && echo -en 'travis_fold:start:script.2\\r'
|
||||
- make archives
|
||||
- ccache -s
|
||||
- echo -en 'travis_fold:end:script.2\\r'
|
||||
- echo 'Building Firmware..' && echo -en 'travis_fold:start:script.3\\r'
|
||||
- make -j6
|
||||
- make -j4
|
||||
- ccache -s
|
||||
- echo -en 'travis_fold:end:script.3\\r'
|
||||
- zip Firmware.zip Images/*.px4
|
||||
|
||||
@@ -85,4 +106,3 @@ notifications:
|
||||
- https://webhooks.gitter.im/e/2b9c4a4cb2211f8befba
|
||||
on_success: always # options: [always|never|change] default: always
|
||||
on_failure: always # options: [always|never|change] default: always
|
||||
on_start: false # default: false
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -0,0 +1,12 @@
|
||||
{
|
||||
"board_id": 99,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the STM32F4Discovery board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "PX4/STM32F4Discovery",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -8,7 +8,14 @@
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MIXER firefly6
|
||||
set PWM_OUT 123456
|
||||
|
||||
set MIXER_AUX firefly6
|
||||
set PWM_AUX_RATE 50
|
||||
set PWM_AUX_OUT 1234
|
||||
set PWM_AUX_DISARMED 1000
|
||||
set PWM_AUX_MIN 1000
|
||||
set PWM_AUX_MAX 2000
|
||||
|
||||
set PWM_OUT 12345678
|
||||
param set VT_MOT_COUNT 6
|
||||
param set VT_IDLE_PWM_MC 1080
|
||||
|
||||
+2
-2
@@ -1,10 +1,10 @@
|
||||
#!nsh
|
||||
#
|
||||
# Generic rover
|
||||
# loading default values for the axialracing ax10
|
||||
#
|
||||
|
||||
#load some defaults e.g. PWM values
|
||||
sh /etc/init.d/rc.rover_defaults
|
||||
sh /etc/init.d/rc.axialracing_ax10_defaults
|
||||
|
||||
#choose a mixer, for rover control we need a plain passthrough to the servos
|
||||
set MIXER IO_pass
|
||||
@@ -287,10 +287,10 @@ fi
|
||||
|
||||
|
||||
#
|
||||
# Ground Rover
|
||||
# Ground Rover AxialRacing AX10
|
||||
#
|
||||
if param compare SYS_AUTOSTART 50001
|
||||
then
|
||||
sh /etc/init.d/50001_rover
|
||||
sh /etc/init.d/50001_axialracing_ax10
|
||||
fi
|
||||
|
||||
|
||||
+2
-1
@@ -6,4 +6,5 @@
|
||||
|
||||
ekf_att_pos_estimator start
|
||||
|
||||
rover_steering_control start
|
||||
# disabled the start of steering control app due to use of offboard mode only
|
||||
# rover_steering_control start
|
||||
@@ -15,4 +15,11 @@ then
|
||||
param set FW_T_RLL2THR 15
|
||||
param set FW_T_SRATE_P 0.01
|
||||
param set FW_T_TIME_CONST 5
|
||||
|
||||
param set PE_VELNE_NOISE 0.3
|
||||
param set PE_VELD_NOISE 0.5
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
param set PE_POSD_NOISE 0.5
|
||||
param set PE_GBIAS_PNOISE 0.000001
|
||||
param set PE_ABIAS_PNOISE 0.0002
|
||||
fi
|
||||
|
||||
@@ -45,7 +45,7 @@ then
|
||||
|
||||
if mixer load $OUTPUT_DEV $MIXER_FILE
|
||||
then
|
||||
echo "[i] Mixer: $MIXER_FILE"
|
||||
echo "[i] Mixer: $MIXER_FILE on $OUTPUT_DEV"
|
||||
else
|
||||
echo "[i] Error loading mixer: $MIXER_FILE"
|
||||
tone_alarm $TUNE_ERR
|
||||
@@ -105,14 +105,14 @@ then
|
||||
set MIXER_AUX_FILE none
|
||||
set OUTPUT_AUX_DEV /dev/pwm_output1
|
||||
|
||||
if [ -f $SDCARD_MIXERS_PATH/$MIXER_AUX.mix ]
|
||||
if [ -f $SDCARD_MIXERS_PATH/$MIXER_AUX.aux.mix ]
|
||||
then
|
||||
set MIXER_AUX_FILE $SDCARD_MIXERS_PATH/$MIXER_AUX.mix
|
||||
set MIXER_AUX_FILE $SDCARD_MIXERS_PATH/$MIXER_AUX.aux.mix
|
||||
else
|
||||
|
||||
if [ -f /etc/mixers/$MIXER_AUX.mix ]
|
||||
if [ -f /etc/mixers/$MIXER_AUX.aux.mix ]
|
||||
then
|
||||
set MIXER_AUX_FILE /etc/mixers/$MIXER_AUX.mix
|
||||
set MIXER_AUX_FILE /etc/mixers/$MIXER_AUX.aux.mix
|
||||
fi
|
||||
fi
|
||||
|
||||
@@ -120,7 +120,12 @@ then
|
||||
then
|
||||
if fmu mode_pwm
|
||||
then
|
||||
mixer load $OUTPUT_AUX_DEV $MIXER_AUX_FILE
|
||||
if mixer load $OUTPUT_AUX_DEV $MIXER_AUX_FILE
|
||||
then
|
||||
echo "[i] Mixer: $MIXER_AUX_FILE on $OUTPUT_AUX_DEV"
|
||||
else
|
||||
echo "[i] Error loading mixer: $MIXER_AUX_FILE"
|
||||
fi
|
||||
else
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
@@ -7,10 +7,12 @@ if [ -d /fs/microsd ]
|
||||
then
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
echo "Start sdlog2 at 50Hz"
|
||||
sdlog2 start -r 40 -a -b 3 -t
|
||||
if sdlog2 start -r 40 -a -b 3 -t
|
||||
then
|
||||
fi
|
||||
else
|
||||
echo "Start sdlog2 at 200Hz"
|
||||
sdlog2 start -r 200 -a -b 22 -t
|
||||
if sdlog2 start -r 200 -a -b 22 -t
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
@@ -40,6 +40,8 @@ then
|
||||
param set PE_VELD_NOISE 0.7
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
param set PE_POSD_NOISE 1.0
|
||||
param set PE_GBIAS_PNOISE 0.000001
|
||||
param set PE_ABIAS_PNOISE 0.0001
|
||||
|
||||
param set NAV_ACC_RAD 2.0
|
||||
param set RTL_RETURN_ALT 30.0
|
||||
|
||||
@@ -9,12 +9,12 @@ adc start
|
||||
if ver hwcmp PX4FMU_V2
|
||||
then
|
||||
# External I2C bus
|
||||
if hmc5883 -C -X start
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal I2C bus
|
||||
if hmc5883 -C -I -R 4 start
|
||||
if hmc5883 -C -T -I -R 4 start
|
||||
then
|
||||
fi
|
||||
|
||||
@@ -43,7 +43,7 @@ then
|
||||
then
|
||||
fi
|
||||
|
||||
if hmc5883 -S -R 8 start
|
||||
if hmc5883 -C -T -S -R 8 start
|
||||
then
|
||||
fi
|
||||
|
||||
@@ -115,9 +115,7 @@ then
|
||||
fi
|
||||
|
||||
#
|
||||
# Start sensors -> preflight_check
|
||||
# Start sensors
|
||||
#
|
||||
if sensors start
|
||||
then
|
||||
preflight_check &
|
||||
fi
|
||||
sensors start
|
||||
|
||||
|
||||
@@ -32,6 +32,13 @@ then
|
||||
param set FW_RR_I 0.00
|
||||
param set FW_RR_IMAX 0.2
|
||||
param set FW_RR_P 0.02
|
||||
|
||||
param set PE_VELNE_NOISE 0.5
|
||||
param set PE_VELD_NOISE 0.7
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
param set PE_POSD_NOISE 1.0
|
||||
param set PE_GBIAS_PNOISE 0.000001
|
||||
param set PE_ABIAS_PNOISE 0.0001
|
||||
fi
|
||||
|
||||
set PWM_DISARMED 900
|
||||
|
||||
@@ -17,8 +17,8 @@ set MODE autostart
|
||||
|
||||
set FRC /fs/microsd/etc/rc.txt
|
||||
set FCONFIG /fs/microsd/etc/config.txt
|
||||
|
||||
set TUNE_ERR ML<<CP4CP4CP4CP4CP4
|
||||
set LOG_FILE /fs/microsd/bootlog.txt
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
@@ -27,12 +27,24 @@ set TUNE_ERR ML<<CP4CP4CP4CP4CP4
|
||||
echo "[i] Looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
set LOG_FILE /fs/microsd/bootlog.txt
|
||||
echo "[i] microSD mounted: /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
set LOG_FILE /dev/null
|
||||
tone_alarm MBAGP
|
||||
if mkfatfs /dev/mmcsd0
|
||||
then
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[i] microSD card formatted"
|
||||
else
|
||||
echo "[i] format failed"
|
||||
tone_alarm MNBG
|
||||
set LOG_FILE /dev/null
|
||||
fi
|
||||
else
|
||||
set LOG_FILE /dev/null
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
@@ -289,6 +301,11 @@ then
|
||||
then
|
||||
fi
|
||||
|
||||
#
|
||||
# Sensors System (start before Commander so Preflight checks are properly run)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
# Needs to be this early for in-air-restarts
|
||||
commander start
|
||||
|
||||
@@ -455,9 +472,8 @@ then
|
||||
sh /etc/init.d/rc.uavcan
|
||||
|
||||
#
|
||||
# Sensors, Logging, GPS
|
||||
# Logging, GPS
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
sh /etc/init.d/rc.logging
|
||||
|
||||
if [ $GPS == yes ]
|
||||
@@ -593,7 +609,7 @@ then
|
||||
then
|
||||
set MAV_TYPE 19
|
||||
fi
|
||||
if [ $MIXER == firefly6_rotors ]
|
||||
if [ $MIXER == firefly6 ]
|
||||
then
|
||||
set MAV_TYPE 21
|
||||
fi
|
||||
@@ -631,7 +647,7 @@ then
|
||||
# Start standard rover apps
|
||||
if [ $LOAD_DAPPS == yes ]
|
||||
then
|
||||
sh /etc/init.d/rc.rover_apps
|
||||
sh /etc/init.d/rc.axialracing_ax10_apps
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
@@ -1,4 +1,14 @@
|
||||
# mixer for the FireFly6 elevons
|
||||
# mixer for the FireFly6 tilt mechansim servo, elevons and landing gear
|
||||
=======================================================================
|
||||
|
||||
Tilt mechanism servo mixer
|
||||
---------------------------
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 4 10000 10000 0 -10000 10000
|
||||
|
||||
Elevon mixers
|
||||
-------------
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 7500 7500 0 -10000 10000
|
||||
@@ -8,3 +18,9 @@ M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 7500 7500 0 -10000 10000
|
||||
S: 1 1 -8000 -8000 0 -10000 10000
|
||||
|
||||
Landing gear mixer
|
||||
------------------
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 3 6 10000 10000 0 -10000 10000
|
||||
|
||||
@@ -0,0 +1,58 @@
|
||||
clear all;
|
||||
close all;
|
||||
|
||||
% Measurement data
|
||||
% 1045 propeller
|
||||
% Robbe Roxxy Motor (1100 kV, data collected in 2010)
|
||||
data = [ 45, 7.4;...
|
||||
38, 5.6;...
|
||||
33, 4.3;...
|
||||
26, 3.0;...
|
||||
18, 2.0;...
|
||||
10, 1.0 ];
|
||||
|
||||
% Normalize the data, as we're operating later
|
||||
% anyways in normalized units
|
||||
data(:,1) = data(:,1) ./ max(data(:,1));
|
||||
data(:,2) = data(:,2) ./ max(data(:,2));
|
||||
|
||||
% Fit a 2nd degree polygon to the data and
|
||||
% print the x2, x1, x0 coefficients
|
||||
p = polyfit(data(:,2), data(:,1),2)
|
||||
|
||||
% Override the first coffefficient for testing
|
||||
% purposes
|
||||
pf = 0.62;
|
||||
|
||||
% Generate plotting data
|
||||
px1 = linspace(0, max(data(:,2)));
|
||||
py1 = polyval(p, px1);
|
||||
|
||||
pyt = zeros(size(data, 1), 1);
|
||||
corr = zeros(size(data, 1), 1);
|
||||
|
||||
% Actual code test
|
||||
% the two lines below are the ones needed to be ported to C:
|
||||
% pf: Power factor parameter.
|
||||
% px1(i): The current normalized motor command (-1..1)
|
||||
% corr(i): The required correction. The motor speed is:
|
||||
% px1(i)
|
||||
for i=1:size(px1, 2)
|
||||
|
||||
% The actual output throttle
|
||||
pyt(i) = -pf * (px1(i) * px1(i)) + (1 + pf) * px1(i);
|
||||
|
||||
% Solve for input throttle
|
||||
% y = -p * x^2 + (1+p) * x;
|
||||
%
|
||||
end
|
||||
|
||||
plot(data(:,2), data(:,1), '*r');
|
||||
hold on;
|
||||
plot(px1, py1, '*b');
|
||||
hold on;
|
||||
plot([0 px1(end)], [0 py1(end)], '-k');
|
||||
hold on;
|
||||
plot(px1, pyt, '-b');
|
||||
hold on;
|
||||
plot(px1, corr, '-m');
|
||||
Regular → Executable
+25
-7
@@ -1,6 +1,7 @@
|
||||
#!/usr/bin/env python
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
# Copyright (C) 2012-2015 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
|
||||
@@ -31,11 +32,28 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Information about FMU and IO boards connected
|
||||
#
|
||||
# send BOOT command to a device
|
||||
|
||||
MODULE_COMMAND = boardinfo
|
||||
SRCS = boardinfo.c
|
||||
import argparse
|
||||
import serial, sys
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
from sys import platform as _platform
|
||||
|
||||
# Parse commandline arguments
|
||||
parser = argparse.ArgumentParser(description="Send boot command to a device")
|
||||
parser.add_argument('--baud', action="store", type=int, default=115200, help="Baud rate of the serial port")
|
||||
parser.add_argument('port', action="store", help="Serial port(s) to which the FMU may be attached")
|
||||
args = parser.parse_args()
|
||||
|
||||
REBOOT = b'\x30'
|
||||
EOC = b'\x20'
|
||||
|
||||
print("Sending reboot to %s" % args.port)
|
||||
try:
|
||||
port = serial.Serial(args.port, args.baud, timeout=0.5)
|
||||
except Exception:
|
||||
print("Unable to open %s" % args.port)
|
||||
sys.exit(1)
|
||||
port.write(REBOOT + EOC)
|
||||
port.close()
|
||||
sys.exit(0)
|
||||
@@ -3,7 +3,8 @@ set -eu
|
||||
failed=0
|
||||
for fn in $(find . -path './src/lib/uavcan' -prune -o \
|
||||
-path './src/lib/mathlib/CMSIS' -prune -o \
|
||||
-path './src/modules/attitude_estimator_ekf/codegen/' -prune -o \
|
||||
-path './src/lib/eigen' -prune -o \
|
||||
-path './src/modules/attitude_estimator_ekf/codegen' -prune -o \
|
||||
-path './NuttX' -prune -o \
|
||||
-path './Build' -prune -o \
|
||||
-path './mavlink' -prune -o \
|
||||
|
||||
@@ -74,6 +74,28 @@ else
|
||||
git submodule update;
|
||||
fi
|
||||
|
||||
if [ -d src/lib/eigen ]
|
||||
then
|
||||
STATUSRETVAL=$(git submodule summary | grep -A20 -i eigen | grep "<")
|
||||
if [ -z "$STATUSRETVAL" ]
|
||||
then
|
||||
echo "Checked Eigen submodule, correct version found"
|
||||
else
|
||||
echo ""
|
||||
echo ""
|
||||
echo "New commits required:"
|
||||
echo "$(git submodule summary)"
|
||||
echo ""
|
||||
echo ""
|
||||
echo "eigen sub repo not at correct version. Try 'git submodule update'"
|
||||
echo "or follow instructions on http://pixhawk.org/dev/git/submodules"
|
||||
exit 1
|
||||
fi
|
||||
else
|
||||
git submodule init;
|
||||
git submodule update;
|
||||
fi
|
||||
|
||||
if [ -d Tools/gencpp ]
|
||||
then
|
||||
STATUSRETVAL=$(git submodule summary | grep -A20 -i gencpp | grep "<")
|
||||
|
||||
@@ -12,11 +12,11 @@ class DokuWikiTablesOutput():
|
||||
result += "^ Name ^ Description ^ Min ^ Max ^ Default ^\n"
|
||||
result += "^ ::: ^ Comment ^^^^\n"
|
||||
for param in group.GetParams():
|
||||
code = param.GetFieldValue("code")
|
||||
code = param.GetName()
|
||||
def_val = param.GetDefault()
|
||||
name = param.GetFieldValue("short_desc")
|
||||
min_val = param.GetFieldValue("min")
|
||||
max_val = param.GetFieldValue("max")
|
||||
def_val = param.GetFieldValue("default")
|
||||
long_desc = param.GetFieldValue("long_desc")
|
||||
|
||||
if name == code:
|
||||
|
||||
@@ -37,20 +37,30 @@ class Parameter(object):
|
||||
|
||||
# Define sorting order of the fields
|
||||
priority = {
|
||||
"code": 10,
|
||||
"type": 9,
|
||||
"board": 9,
|
||||
"short_desc": 8,
|
||||
"long_desc": 7,
|
||||
"default": 6,
|
||||
"min": 5,
|
||||
"max": 4,
|
||||
"unit": 3,
|
||||
# all others == 0 (sorted alphabetically)
|
||||
}
|
||||
|
||||
def __init__(self):
|
||||
def __init__(self, name, type, default = ""):
|
||||
self.fields = {}
|
||||
self.name = name
|
||||
self.type = type
|
||||
self.default = default
|
||||
|
||||
def GetName(self):
|
||||
return self.name
|
||||
|
||||
def GetType(self):
|
||||
return self.type
|
||||
|
||||
def GetDefault(self):
|
||||
return self.default
|
||||
|
||||
def SetField(self, code, value):
|
||||
"""
|
||||
Set named field value
|
||||
@@ -83,11 +93,12 @@ class SourceParser(object):
|
||||
re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)')
|
||||
re_comment_end = re.compile(r'(.*?)\s*\*\/')
|
||||
re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;')
|
||||
re_px4_parameter_definition = re.compile(r'PX4_PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*\)\s*;')
|
||||
re_cut_type_specifier = re.compile(r'[a-z]+$')
|
||||
re_is_a_number = re.compile(r'^-?[0-9\.]')
|
||||
re_remove_dots = re.compile(r'\.+$')
|
||||
|
||||
valid_tags = set(["group", "min", "max", "unit"])
|
||||
valid_tags = set(["group", "board", "min", "max", "unit"])
|
||||
|
||||
# Order of parameter groups
|
||||
priority = {
|
||||
@@ -176,15 +187,12 @@ class SourceParser(object):
|
||||
# Non-empty line outside the comment
|
||||
m = self.re_parameter_definition.match(line)
|
||||
if m:
|
||||
tp, code, defval = m.group(1, 2, 3)
|
||||
tp, name, defval = m.group(1, 2, 3)
|
||||
# Remove trailing type specifier from numbers: 0.1f => 0.1
|
||||
if self.re_is_a_number.match(defval):
|
||||
defval = self.re_cut_type_specifier.sub('', defval)
|
||||
param = Parameter()
|
||||
param.SetField("code", code)
|
||||
param.SetField("short_desc", code)
|
||||
param.SetField("type", tp)
|
||||
param.SetField("default", defval)
|
||||
param = Parameter(name, tp, defval)
|
||||
param.SetField("short_desc", name)
|
||||
# If comment was found before the parameter declaration,
|
||||
# inject its data into the newly created parameter.
|
||||
group = "Miscellaneous"
|
||||
@@ -206,8 +214,36 @@ class SourceParser(object):
|
||||
if group not in self.param_groups:
|
||||
self.param_groups[group] = ParameterGroup(group)
|
||||
self.param_groups[group].AddParameter(param)
|
||||
# Reset parsed comment.
|
||||
state = None
|
||||
else:
|
||||
# Nasty code dup, but this will all go away soon, so quick and dirty (DonLakeFlyer)
|
||||
m = self.re_px4_parameter_definition.match(line)
|
||||
if m:
|
||||
tp, name = m.group(1, 2)
|
||||
param = Parameter(name, tp)
|
||||
param.SetField("short_desc", name)
|
||||
# If comment was found before the parameter declaration,
|
||||
# inject its data into the newly created parameter.
|
||||
group = "Miscellaneous"
|
||||
if state == "comment-processed":
|
||||
if short_desc is not None:
|
||||
param.SetField("short_desc",
|
||||
self.re_remove_dots.sub('', short_desc))
|
||||
if long_desc is not None:
|
||||
param.SetField("long_desc", long_desc)
|
||||
for tag in tags:
|
||||
if tag == "group":
|
||||
group = tags[tag]
|
||||
elif tag not in self.valid_tags:
|
||||
sys.stderr.write("Skipping invalid "
|
||||
"documentation tag: '%s'\n" % tag)
|
||||
else:
|
||||
param.SetField(tag, tags[tag])
|
||||
# Store the parameter
|
||||
if group not in self.param_groups:
|
||||
self.param_groups[group] = ParameterGroup(group)
|
||||
self.param_groups[group].AddParameter(param)
|
||||
# Reset parsed comment.
|
||||
state = None
|
||||
|
||||
def GetParamGroups(self):
|
||||
"""
|
||||
|
||||
+48
-18
@@ -1,26 +1,56 @@
|
||||
from xml.dom.minidom import getDOMImplementation
|
||||
import xml.etree.ElementTree as ET
|
||||
import codecs
|
||||
|
||||
def indent(elem, level=0):
|
||||
i = "\n" + level*" "
|
||||
if len(elem):
|
||||
if not elem.text or not elem.text.strip():
|
||||
elem.text = i + " "
|
||||
if not elem.tail or not elem.tail.strip():
|
||||
elem.tail = i
|
||||
for elem in elem:
|
||||
indent(elem, level+1)
|
||||
if not elem.tail or not elem.tail.strip():
|
||||
elem.tail = i
|
||||
else:
|
||||
if level and (not elem.tail or not elem.tail.strip()):
|
||||
elem.tail = i
|
||||
|
||||
class XMLOutput():
|
||||
def __init__(self, groups):
|
||||
impl = getDOMImplementation()
|
||||
xml_document = impl.createDocument(None, "parameters", None)
|
||||
xml_parameters = xml_document.documentElement
|
||||
|
||||
def __init__(self, groups, board):
|
||||
xml_parameters = ET.Element("parameters")
|
||||
xml_version = ET.SubElement(xml_parameters, "version")
|
||||
xml_version.text = "3"
|
||||
last_param_name = ""
|
||||
board_specific_param_set = False
|
||||
for group in groups:
|
||||
xml_group = xml_document.createElement("group")
|
||||
xml_group.setAttribute("name", group.GetName())
|
||||
xml_parameters.appendChild(xml_group)
|
||||
xml_group = ET.SubElement(xml_parameters, "group")
|
||||
xml_group.attrib["name"] = group.GetName()
|
||||
for param in group.GetParams():
|
||||
xml_param = xml_document.createElement("parameter")
|
||||
xml_group.appendChild(xml_param)
|
||||
for code in param.GetFieldCodes():
|
||||
value = param.GetFieldValue(code)
|
||||
xml_field = xml_document.createElement(code)
|
||||
xml_param.appendChild(xml_field)
|
||||
xml_value = xml_document.createTextNode(value)
|
||||
xml_field.appendChild(xml_value)
|
||||
self.xml_document = xml_document
|
||||
if (last_param_name == param.GetName() and not board_specific_param_set) or last_param_name != param.GetName():
|
||||
xml_param = ET.SubElement(xml_group, "parameter")
|
||||
xml_param.attrib["name"] = param.GetName()
|
||||
xml_param.attrib["default"] = param.GetDefault()
|
||||
xml_param.attrib["type"] = param.GetType()
|
||||
last_param_name = param.GetName()
|
||||
for code in param.GetFieldCodes():
|
||||
value = param.GetFieldValue(code)
|
||||
if code == "board":
|
||||
if value == board:
|
||||
board_specific_param_set = True
|
||||
xml_field = ET.SubElement(xml_param, code)
|
||||
xml_field.text = value
|
||||
else:
|
||||
xml_group.remove(xml_param)
|
||||
else:
|
||||
xml_field = ET.SubElement(xml_param, code)
|
||||
xml_field.text = value
|
||||
if last_param_name != param.GetName():
|
||||
board_specific_param_set = False
|
||||
indent(xml_parameters)
|
||||
self.xml_document = ET.ElementTree(xml_parameters)
|
||||
|
||||
def Save(self, filename):
|
||||
with codecs.open(filename, 'w', 'utf-8') as f:
|
||||
self.xml_document.writexml(f, indent=" ", addindent=" ", newl="\n")
|
||||
self.xml_document.write(f)
|
||||
|
||||
@@ -105,6 +105,7 @@ if args.git_identity != None:
|
||||
if args.parameter_xml != None:
|
||||
f = open(args.parameter_xml, "rb")
|
||||
bytes = f.read()
|
||||
desc['parameter_xml_size'] = len(bytes)
|
||||
desc['parameter_xml'] = base64.b64encode(zlib.compress(bytes,9)).decode('utf-8')
|
||||
if args.image != None:
|
||||
f = open(args.image, "rb")
|
||||
|
||||
@@ -65,6 +65,11 @@ def main():
|
||||
metavar="FILENAME",
|
||||
help="Create XML file"
|
||||
" (default FILENAME: parameters.xml)")
|
||||
parser.add_argument("-b", "--board",
|
||||
nargs='?',
|
||||
const="",
|
||||
metavar="BOARD",
|
||||
help="Board to create xml parameter xml for")
|
||||
parser.add_argument("-w", "--wiki",
|
||||
nargs='?',
|
||||
const="parameters.wiki",
|
||||
@@ -116,7 +121,7 @@ def main():
|
||||
# Output to XML file
|
||||
if args.xml:
|
||||
print("Creating XML file " + args.xml)
|
||||
out = xmlout.XMLOutput(param_groups)
|
||||
out = xmlout.XMLOutput(param_groups, args.board)
|
||||
out.Save(args.xml)
|
||||
|
||||
# Output to DokuWiki tables
|
||||
|
||||
@@ -161,6 +161,7 @@ class uploader(object):
|
||||
GET_OTP = b'\x2a' # rev4+ , get a word from OTP area
|
||||
GET_SN = b'\x2b' # rev4+ , get a word from SN area
|
||||
GET_CHIP = b'\x2c' # rev5+ , get chip version
|
||||
SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
|
||||
REBOOT = b'\x30'
|
||||
|
||||
INFO_BL_REV = b'\x01' # bootloader protocol revision
|
||||
@@ -405,6 +406,12 @@ class uploader(object):
|
||||
raise RuntimeError("Program CRC failed")
|
||||
self.__drawProgressBar(label, 100, 100)
|
||||
|
||||
def __set_boot_delay(self, boot_delay):
|
||||
self.__send(uploader.SET_BOOT_DELAY
|
||||
+ struct.pack("b", boot_delay)
|
||||
+ uploader.EOC)
|
||||
self.__getSync()
|
||||
|
||||
# get basic data about the board
|
||||
def identify(self):
|
||||
# make sure we are in sync before starting
|
||||
@@ -472,6 +479,9 @@ class uploader(object):
|
||||
else:
|
||||
self.__verify_v3("Verify ", fw)
|
||||
|
||||
if args.boot_delay is not None:
|
||||
self.__set_boot_delay(args.boot_delay)
|
||||
|
||||
print("\nRebooting.\n")
|
||||
self.__reboot()
|
||||
self.port.close()
|
||||
@@ -501,6 +511,7 @@ parser = argparse.ArgumentParser(description="Firmware uploader for the PX autop
|
||||
parser.add_argument('--port', action="store", required=True, help="Serial port(s) to which the FMU may be attached")
|
||||
parser.add_argument('--baud', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200), only required for true serial ports.")
|
||||
parser.add_argument('--force', action='store_true', default=False, help='Override board type check and continue loading')
|
||||
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
|
||||
parser.add_argument('firmware', action="store", help="Firmware file to be uploaded")
|
||||
args = parser.parse_args()
|
||||
|
||||
|
||||
@@ -1,41 +0,0 @@
|
||||
#!/bin/sh
|
||||
# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
|
||||
|
||||
# main ROS Setup
|
||||
# following http://wiki.ros.org/indigo/Installation/Ubuntu
|
||||
# also adding drcsim http://gazebosim.org/tutorials?tut=drcsim_install
|
||||
# run this file with . ./px4_ros_setup_ubuntu.sh
|
||||
|
||||
## add ROS repository
|
||||
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list'
|
||||
|
||||
## add key
|
||||
wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -O - | \
|
||||
sudo apt-key add -
|
||||
|
||||
## Install main ROS pacakges
|
||||
sudo apt-get update
|
||||
sudo apt-get -y install ros-indigo-desktop-full
|
||||
sudo rosdep init
|
||||
rosdep update
|
||||
|
||||
## Setup environment variables
|
||||
echo "source /opt/ros/indigo/setup.bash" >> ~/.bashrc
|
||||
. ~/.bashrc
|
||||
|
||||
# get rosinstall
|
||||
sudo apt-get -y install python-rosinstall
|
||||
|
||||
# additional dependencies
|
||||
sudo apt-get -y install ros-indigo-octomap-msgs ros-indigo-joy
|
||||
|
||||
## drcsim setup (for models)
|
||||
### add osrf repository
|
||||
sudo sh -c 'echo "deb http://packages.osrfoundation.org/drc/ubuntu trusty main" > /etc/apt/sources.list.d/drc-latest.list'
|
||||
|
||||
### add key
|
||||
wget http://packages.osrfoundation.org/drc.key -O - | sudo apt-key add -
|
||||
|
||||
### install drcsim
|
||||
sudo apt-get update
|
||||
sudo apt-get -y install drcsim
|
||||
@@ -1,9 +0,0 @@
|
||||
#!/bin/sh
|
||||
# this script creates a catkin_ws in the current folder
|
||||
# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
|
||||
|
||||
mkdir -p catkin_ws/src
|
||||
cd catkin_ws/src
|
||||
catkin_init_workspace
|
||||
cd ..
|
||||
catkin_make
|
||||
@@ -1,30 +0,0 @@
|
||||
#!/bin/bash
|
||||
# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
|
||||
|
||||
# run this script from the root of your catkin_ws
|
||||
source devel/setup.bash
|
||||
cd src
|
||||
|
||||
# PX4 Firmware
|
||||
git clone https://github.com/PX4/Firmware.git
|
||||
|
||||
# euroc simulator
|
||||
git clone https://github.com/PX4/euroc_simulator.git
|
||||
cd euroc_simulator
|
||||
git checkout px4_nodes
|
||||
cd ..
|
||||
|
||||
# mav comm
|
||||
git clone https://github.com/PX4/mav_comm.git
|
||||
|
||||
# glog catkin
|
||||
git clone https://github.com/ethz-asl/glog_catkin.git
|
||||
|
||||
# catkin simple
|
||||
git clone https://github.com/catkin/catkin_simple.git
|
||||
|
||||
# drcsim (for scenery and models)
|
||||
|
||||
cd ..
|
||||
|
||||
catkin_make
|
||||
@@ -37,7 +37,6 @@
|
||||
#
|
||||
PKG = 'px4'
|
||||
|
||||
import sys
|
||||
import unittest
|
||||
import rospy
|
||||
|
||||
@@ -50,36 +49,40 @@ from manual_input import ManualInput
|
||||
#
|
||||
class ManualInputTest(unittest.TestCase):
|
||||
|
||||
def setUp(self):
|
||||
self.actuator_status = actuator_armed()
|
||||
self.control_mode = vehicle_control_mode()
|
||||
|
||||
#
|
||||
# General callback functions used in tests
|
||||
#
|
||||
def actuator_armed_callback(self, data):
|
||||
self.actuatorStatus = data
|
||||
self.actuator_status = data
|
||||
|
||||
def vehicle_control_mode_callback(self, data):
|
||||
self.controlMode = data
|
||||
self.control_mode = data
|
||||
|
||||
#
|
||||
# Test arming
|
||||
#
|
||||
def test_manual_input(self):
|
||||
rospy.init_node('test_node', anonymous=True)
|
||||
rospy.Subscriber('px4_multicopter/actuator_armed', actuator_armed, self.actuator_armed_callback)
|
||||
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
rospy.Subscriber('actuator_armed', actuator_armed, self.actuator_armed_callback)
|
||||
rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
|
||||
man = ManualInput()
|
||||
man_in = ManualInput()
|
||||
|
||||
# Test arming
|
||||
man.arm()
|
||||
self.assertEquals(self.actuatorStatus.armed, True, "did not arm")
|
||||
man_in.arm()
|
||||
self.assertEquals(self.actuator_status.armed, True, "did not arm")
|
||||
|
||||
# Test posctl
|
||||
man.posctl()
|
||||
self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")
|
||||
man_in.posctl()
|
||||
self.assertTrue(self.control_mode.flag_control_position_enabled, "flag_control_position_enabled is not set")
|
||||
|
||||
# Test offboard
|
||||
man.offboard()
|
||||
self.assertTrue(self.controlMode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
|
||||
man_in.offboard()
|
||||
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
@@ -37,23 +37,22 @@
|
||||
#
|
||||
PKG = 'px4'
|
||||
|
||||
import sys
|
||||
import unittest
|
||||
import rospy
|
||||
import rosbag
|
||||
|
||||
from numpy import linalg
|
||||
import numpy as np
|
||||
|
||||
from px4.msg import vehicle_local_position
|
||||
from px4.msg import vehicle_control_mode
|
||||
from px4.msg import actuator_armed
|
||||
from px4.msg import position_setpoint_triplet
|
||||
from px4.msg import position_setpoint
|
||||
from sensor_msgs.msg import Joy
|
||||
from std_msgs.msg import Header
|
||||
from px4.msg import vehicle_local_position_setpoint
|
||||
|
||||
from manual_input import ManualInput
|
||||
from flight_path_assertion import FlightPathAssertion
|
||||
from px4_test_helper import PX4TestHelper
|
||||
|
||||
#
|
||||
# Tests flying a path in offboard control by directly sending setpoints
|
||||
@@ -66,33 +65,42 @@ class DirectOffboardPosctlTest(unittest.TestCase):
|
||||
|
||||
def setUp(self):
|
||||
rospy.init_node('test_node', anonymous=True)
|
||||
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
rospy.Subscriber("px4_multicopter/vehicle_local_position", vehicle_local_position, self.position_callback)
|
||||
self.pubSpt = rospy.Publisher('px4_multicopter/position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
|
||||
self.helper = PX4TestHelper("direct_offboard_posctl_test")
|
||||
self.helper.setUp()
|
||||
|
||||
rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
self.sub_vlp = rospy.Subscriber("vehicle_local_position", vehicle_local_position, self.position_callback)
|
||||
self.pub_spt = rospy.Publisher('position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
|
||||
self.rate = rospy.Rate(10) # 10hz
|
||||
self.has_pos = False
|
||||
self.local_position = vehicle_local_position()
|
||||
self.control_mode = vehicle_control_mode()
|
||||
|
||||
def tearDown(self):
|
||||
if (self.fpa):
|
||||
if self.fpa:
|
||||
self.fpa.stop()
|
||||
|
||||
self.helper.tearDown()
|
||||
|
||||
#
|
||||
# General callback functions used in tests
|
||||
#
|
||||
|
||||
def position_callback(self, data):
|
||||
self.hasPos = True
|
||||
self.localPosition = data
|
||||
self.has_pos = True
|
||||
self.local_position = data
|
||||
|
||||
def vehicle_control_mode_callback(self, data):
|
||||
self.controlMode = data
|
||||
self.control_mode = data
|
||||
|
||||
|
||||
#
|
||||
# Helper methods
|
||||
#
|
||||
def is_at_position(self, x, y, z, offset):
|
||||
rospy.logdebug("current position %f, %f, %f" % (self.localPosition.x, self.localPosition.y, self.localPosition.z))
|
||||
rospy.logdebug("current position %f, %f, %f" % (self.local_position.x, self.local_position.y, self.local_position.z))
|
||||
desired = np.array((x, y, z))
|
||||
pos = np.array((self.localPosition.x, self.localPosition.y, self.localPosition.z))
|
||||
pos = np.array((self.local_position.x, self.local_position.y, self.local_position.z))
|
||||
return linalg.norm(desired - pos) < offset
|
||||
|
||||
def reach_position(self, x, y, z, timeout):
|
||||
@@ -105,12 +113,13 @@ class DirectOffboardPosctlTest(unittest.TestCase):
|
||||
pos.position_valid = True
|
||||
stp = position_setpoint_triplet()
|
||||
stp.current = pos
|
||||
self.pubSpt.publish(stp)
|
||||
self.pub_spt.publish(stp)
|
||||
self.helper.bag_write('px4/position_setpoint_triplet', stp)
|
||||
|
||||
# does it reach the position in X seconds?
|
||||
count = 0
|
||||
while(count < timeout):
|
||||
if(self.is_at_position(pos.x, pos.y, pos.z, 0.5)):
|
||||
while count < timeout:
|
||||
if self.is_at_position(pos.x, pos.y, pos.z, 0.5):
|
||||
break
|
||||
count = count + 1
|
||||
self.rate.sleep()
|
||||
@@ -121,22 +130,23 @@ class DirectOffboardPosctlTest(unittest.TestCase):
|
||||
# Test offboard position control
|
||||
#
|
||||
def test_posctl(self):
|
||||
manIn = ManualInput()
|
||||
man_in = ManualInput()
|
||||
|
||||
# arm and go into offboard
|
||||
manIn.arm()
|
||||
manIn.offboard()
|
||||
self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set")
|
||||
self.assertTrue(self.controlMode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
|
||||
self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")
|
||||
man_in.arm()
|
||||
man_in.offboard()
|
||||
self.assertTrue(self.control_mode.flag_armed, "flag_armed is not set")
|
||||
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
|
||||
self.assertTrue(self.control_mode.flag_control_position_enabled, "flag_control_position_enabled is not set")
|
||||
|
||||
# prepare flight path
|
||||
positions = (
|
||||
(0,0,0),
|
||||
(2,2,-2),
|
||||
(2,-2,-2),
|
||||
(-2,-2,-2),
|
||||
(2,2,-2))
|
||||
(0, 0, 0),
|
||||
(0, 0, -2),
|
||||
(2, 2, -2),
|
||||
(2, -2, -2),
|
||||
(-2, -2, -2),
|
||||
(2, 2, -2))
|
||||
|
||||
# flight path assertion
|
||||
self.fpa = FlightPathAssertion(positions, 1, 0)
|
||||
@@ -147,12 +157,10 @@ class DirectOffboardPosctlTest(unittest.TestCase):
|
||||
self.assertFalse(self.fpa.failed, "breached flight path tunnel (%d)" % i)
|
||||
|
||||
# does it hold the position for Y seconds?
|
||||
positionHeld = True
|
||||
count = 0
|
||||
timeout = 50
|
||||
while(count < timeout):
|
||||
if(not self.is_at_position(2, 2, -2, 0.5)):
|
||||
positionHeld = False
|
||||
while count < timeout:
|
||||
if not self.is_at_position(2, 2, -2, 0.5):
|
||||
break
|
||||
count = count + 1
|
||||
self.rate.sleep()
|
||||
|
||||
@@ -2,8 +2,9 @@
|
||||
<arg name="headless" default="true"/>
|
||||
<arg name="gui" default="false"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="false"/>
|
||||
<arg name="log_file" default="iris"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find px4)/launch/gazebo_iris_empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
@@ -11,8 +12,11 @@
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
<test test-name="direct_manual_input_test" pkg="px4" type="direct_manual_input_test.py" />
|
||||
<test test-name="direct_offboard_posctl_test" pkg="px4" type="direct_offboard_posctl_test.py" />
|
||||
<group ns="$(arg ns)">
|
||||
<test test-name="direct_manual_input_test" pkg="px4" type="direct_manual_input_test.py" />
|
||||
<test test-name="direct_offboard_posctl_test" pkg="px4" type="direct_offboard_posctl_test.py" />
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
@@ -35,7 +35,6 @@
|
||||
#
|
||||
# @author Andreas Antener <andreas@uaventure.com>
|
||||
#
|
||||
import sys
|
||||
import rospy
|
||||
import threading
|
||||
|
||||
@@ -48,7 +47,6 @@ from geometry_msgs.msg import Twist
|
||||
|
||||
from numpy import linalg
|
||||
import numpy as np
|
||||
import math
|
||||
|
||||
#
|
||||
# Helper to test if vehicle stays on expected flight path.
|
||||
@@ -62,30 +60,52 @@ class FlightPathAssertion(threading.Thread):
|
||||
# TODO: yaw validation
|
||||
# TODO: fail main test thread
|
||||
#
|
||||
def __init__(self, positions, tunnelRadius = 1, yawOffset = 0.2):
|
||||
def __init__(self, positions, tunnelRadius=1, yaw_offset=0.2):
|
||||
threading.Thread.__init__(self)
|
||||
rospy.Subscriber("px4_multicopter/vehicle_local_position", vehicle_local_position, self.position_callback)
|
||||
self.spawnModel = rospy.ServiceProxy('gazebo/spawn_sdf_model', SpawnModel)
|
||||
self.setModelState = rospy.ServiceProxy('gazebo/set_model_state', SetModelState)
|
||||
self.deleteModel = rospy.ServiceProxy('gazebo/delete_model', DeleteModel)
|
||||
rospy.Subscriber("vehicle_local_position", vehicle_local_position, self.position_callback)
|
||||
self.spawn_model = rospy.ServiceProxy('/gazebo/spawn_sdf_model', SpawnModel)
|
||||
self.set_model_state = rospy.ServiceProxy('/gazebo/set_model_state', SetModelState)
|
||||
self.delete_model = rospy.ServiceProxy('/gazebo/delete_model', DeleteModel)
|
||||
|
||||
self.positions = positions
|
||||
self.tunnelRadius = tunnelRadius
|
||||
self.yawOffset = yawOffset
|
||||
self.hasPos = False
|
||||
self.shouldStop = False
|
||||
self.tunnel_radius = tunnelRadius
|
||||
self.yaw_offset = yaw_offset
|
||||
self.has_pos = False
|
||||
self.should_stop = False
|
||||
self.center = positions[0]
|
||||
self.endOfSegment = False
|
||||
self.end_of_segment = False
|
||||
self.failed = False
|
||||
self.local_position = vehicle_local_position
|
||||
|
||||
def position_callback(self, data):
|
||||
self.hasPos = True
|
||||
self.localPosition = data
|
||||
self.has_pos = True
|
||||
self.local_position = data
|
||||
|
||||
def spawn_indicator(self):
|
||||
self.deleteModel("indicator")
|
||||
xml = "<?xml version='1.0'?><sdf version='1.4'><model name='indicator'><static>true</static><link name='link'><visual name='visual'><transparency>0.7</transparency><geometry><sphere><radius>%f</radius></sphere></geometry><material><ambient>1 0 0 0.5</ambient><diffuse>1 0 0 0.5</diffuse></material></visual></link></model></sdf>" % self.tunnelRadius
|
||||
self.spawnModel("indicator", xml, "", Pose(), "")
|
||||
self.delete_model("indicator")
|
||||
xml = (
|
||||
"<?xml version='1.0'?>" +
|
||||
"<sdf version='1.4'>" +
|
||||
"<model name='indicator'>" +
|
||||
"<static>true</static>" +
|
||||
"<link name='link'>" +
|
||||
"<visual name='visual'>" +
|
||||
"<transparency>0.7</transparency>" +
|
||||
"<geometry>" +
|
||||
"<sphere>" +
|
||||
"<radius>%f</radius>" +
|
||||
"</sphere>" +
|
||||
"</geometry>" +
|
||||
"<material>" +
|
||||
"<ambient>1 0 0 0.5</ambient>" +
|
||||
"<diffuse>1 0 0 0.5</diffuse>" +
|
||||
"</material>" +
|
||||
"</visual>" +
|
||||
"</link>" +
|
||||
"</model>" +
|
||||
"</sdf>") % self.tunnel_radius
|
||||
|
||||
self.spawn_model("indicator", xml, "", Pose(), "")
|
||||
|
||||
def position_indicator(self):
|
||||
state = SetModelState()
|
||||
@@ -97,7 +117,7 @@ class FlightPathAssertion(threading.Thread):
|
||||
state.pose = pose
|
||||
state.twist = Twist()
|
||||
state.reference_frame = ""
|
||||
self.setModelState(state)
|
||||
self.set_model_state(state)
|
||||
|
||||
def distance_to_line(self, a, b, pos):
|
||||
v = b - a
|
||||
@@ -111,7 +131,7 @@ class FlightPathAssertion(threading.Thread):
|
||||
c2 = np.dot(v, v)
|
||||
if c2 <= c1: # after b
|
||||
self.center = b
|
||||
self.endOfSegment = True
|
||||
self.end_of_segment = True
|
||||
return linalg.norm(pos - b)
|
||||
|
||||
x = c1 / c2
|
||||
@@ -120,52 +140,58 @@ class FlightPathAssertion(threading.Thread):
|
||||
return linalg.norm(pos - l)
|
||||
|
||||
def stop(self):
|
||||
self.shouldStop = True
|
||||
self.should_stop = True
|
||||
|
||||
def run(self):
|
||||
rate = rospy.Rate(10) # 10hz
|
||||
self.spawn_indicator()
|
||||
|
||||
current = 0
|
||||
|
||||
while not self.shouldStop:
|
||||
if (self.hasPos):
|
||||
count = 0
|
||||
while not self.should_stop:
|
||||
if self.has_pos:
|
||||
# calculate distance to line segment between first two points
|
||||
# if distances > tunnelRadius
|
||||
# if distances > tunnel_radius
|
||||
# exit with error
|
||||
# advance current pos if not on the line anymore or distance to next point < tunnelRadius
|
||||
# advance current pos if not on the line anymore or distance to next point < tunnel_radius
|
||||
# exit if current pos is now the last position
|
||||
|
||||
self.position_indicator()
|
||||
|
||||
pos = np.array((self.localPosition.x,
|
||||
self.localPosition.y,
|
||||
self.localPosition.z))
|
||||
aPos = np.array((self.positions[current][0],
|
||||
self.positions[current][1],
|
||||
self.positions[current][2]))
|
||||
bPos = np.array((self.positions[current + 1][0],
|
||||
self.positions[current + 1][1],
|
||||
self.positions[current + 1][2]))
|
||||
pos = np.array((self.local_position.x,
|
||||
self.local_position.y,
|
||||
self.local_position.z))
|
||||
a_pos = np.array((self.positions[current][0],
|
||||
self.positions[current][1],
|
||||
self.positions[current][2]))
|
||||
b_pos = np.array((self.positions[current + 1][0],
|
||||
self.positions[current + 1][1],
|
||||
self.positions[current + 1][2]))
|
||||
|
||||
dist = self.distance_to_line(aPos, bPos, pos)
|
||||
bDist = linalg.norm(pos - bPos)
|
||||
dist = self.distance_to_line(a_pos, b_pos, pos)
|
||||
b_dist = linalg.norm(pos - b_pos)
|
||||
|
||||
rospy.logdebug("distance to line: %f, distance to end: %f" % (dist, bDist))
|
||||
rospy.logdebug("distance to line: %f, distance to end: %f" % (dist, b_dist))
|
||||
|
||||
if (dist > self.tunnelRadius):
|
||||
msg = "left tunnel at position (%f, %f, %f)" % (self.localPosition.x, self.localPosition.y, self.localPosition.z)
|
||||
if dist > self.tunnel_radius:
|
||||
msg = "left tunnel at position (%f, %f, %f)" % (self.local_position.x, self.local_position.y, self.local_position.z)
|
||||
rospy.logerr(msg)
|
||||
self.failed = True
|
||||
break
|
||||
|
||||
if (self.endOfSegment or bDist < self.tunnelRadius):
|
||||
if self.end_of_segment or b_dist < self.tunnel_radius:
|
||||
rospy.loginfo("next segment")
|
||||
self.endOfSegment = False
|
||||
self.end_of_segment = False
|
||||
current = current + 1
|
||||
|
||||
if (current == len(self.positions) - 1):
|
||||
if current == len(self.positions) - 1:
|
||||
rospy.loginfo("no more positions")
|
||||
break
|
||||
|
||||
rate.sleep()
|
||||
count = count + 1
|
||||
|
||||
if count > 10 and not self.has_pos: # no position after 1 sec
|
||||
rospy.logerr("no position")
|
||||
self.failed = True
|
||||
break
|
||||
|
||||
@@ -35,7 +35,6 @@
|
||||
#
|
||||
# @author Andreas Antener <andreas@uaventure.com>
|
||||
#
|
||||
import sys
|
||||
import rospy
|
||||
|
||||
from px4.msg import manual_control_setpoint
|
||||
@@ -46,17 +45,12 @@ from std_msgs.msg import Header
|
||||
#
|
||||
# Manual input control helper
|
||||
#
|
||||
# FIXME: this is not the way to do it! ATM it fakes input to iris/command/attitude because else
|
||||
# the simulator does not instantiate our controller. Probably this whole class will disappear once
|
||||
# arming works correctly.
|
||||
#
|
||||
class ManualInput:
|
||||
class ManualInput(object):
|
||||
|
||||
def __init__(self):
|
||||
rospy.init_node('test_node', anonymous=True)
|
||||
self.pubMcsp = rospy.Publisher('px4_multicopter/manual_control_setpoint', manual_control_setpoint, queue_size=10)
|
||||
self.pubOff = rospy.Publisher('px4_multicopter/offboard_control_mode', offboard_control_mode, queue_size=10)
|
||||
self.pubAtt = rospy.Publisher('iris/command/attitude', CommandAttitudeThrust, queue_size=10)
|
||||
self.pub_mcsp = rospy.Publisher('manual_control_setpoint', manual_control_setpoint, queue_size=10)
|
||||
self.pub_off = rospy.Publisher('offboard_control_mode', offboard_control_mode, queue_size=10)
|
||||
|
||||
def arm(self):
|
||||
rate = rospy.Rate(10) # 10hz
|
||||
@@ -81,11 +75,9 @@ class ManualInput:
|
||||
rospy.loginfo("zeroing")
|
||||
time = rospy.get_rostime().now()
|
||||
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
|
||||
self.pubMcsp.publish(pos)
|
||||
# Fake input to iris commander
|
||||
self.pubAtt.publish(att)
|
||||
self.pub_mcsp.publish(pos)
|
||||
rate.sleep()
|
||||
count = count + 1
|
||||
count = count + 1
|
||||
|
||||
pos.r = 1
|
||||
count = 0
|
||||
@@ -93,7 +85,7 @@ class ManualInput:
|
||||
rospy.loginfo("arming")
|
||||
time = rospy.get_rostime().now()
|
||||
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
|
||||
self.pubMcsp.publish(pos)
|
||||
self.pub_mcsp.publish(pos)
|
||||
rate.sleep()
|
||||
count = count + 1
|
||||
|
||||
@@ -118,7 +110,7 @@ class ManualInput:
|
||||
rospy.loginfo("triggering posctl")
|
||||
time = rospy.get_rostime().now()
|
||||
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
|
||||
self.pubMcsp.publish(pos)
|
||||
self.pub_mcsp.publish(pos)
|
||||
rate.sleep()
|
||||
count = count + 1
|
||||
|
||||
@@ -147,7 +139,7 @@ class ManualInput:
|
||||
rospy.loginfo("setting offboard mode")
|
||||
time = rospy.get_rostime().now()
|
||||
mode.timestamp = time.secs * 1e6 + time.nsecs / 1000
|
||||
self.pubOff.publish(mode)
|
||||
self.pub_off.publish(mode)
|
||||
rate.sleep()
|
||||
count = count + 1
|
||||
|
||||
@@ -169,7 +161,7 @@ class ManualInput:
|
||||
rospy.loginfo("triggering offboard")
|
||||
time = rospy.get_rostime().now()
|
||||
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
|
||||
self.pubMcsp.publish(pos)
|
||||
self.pub_mcsp.publish(pos)
|
||||
rate.sleep()
|
||||
count = count + 1
|
||||
|
||||
|
||||
@@ -37,79 +37,63 @@
|
||||
#
|
||||
PKG = 'px4'
|
||||
|
||||
import sys
|
||||
import unittest
|
||||
import rospy
|
||||
import math
|
||||
|
||||
from numpy import linalg
|
||||
import numpy as np
|
||||
import rosbag
|
||||
|
||||
from px4.msg import vehicle_control_mode
|
||||
from px4.msg import vehicle_local_position
|
||||
from px4.msg import vehicle_attitude_setpoint
|
||||
from px4.msg import vehicle_attitude
|
||||
from std_msgs.msg import Header
|
||||
from std_msgs.msg import Float64
|
||||
from geometry_msgs.msg import PoseStamped, Quaternion
|
||||
from tf.transformations import quaternion_from_euler
|
||||
from mavros.srv import CommandBool
|
||||
|
||||
from manual_input import ManualInput
|
||||
from px4_test_helper import PX4TestHelper
|
||||
|
||||
#
|
||||
# Tests flying a path in offboard control by sending position setpoints
|
||||
# Tests flying a path in offboard control by sending attitude and thrust setpoints
|
||||
# over MAVROS.
|
||||
#
|
||||
# For the test to be successful it needs to reach all setpoints in a certain time.
|
||||
# FIXME: add flight path assertion (needs transformation from ROS frame to NED)
|
||||
# For the test to be successful it needs to cross a certain boundary in time.
|
||||
#
|
||||
class MavrosOffboardAttctlTest(unittest.TestCase):
|
||||
|
||||
def setUp(self):
|
||||
rospy.init_node('test_node', anonymous=True)
|
||||
rospy.wait_for_service('mavros/cmd/arming', 30)
|
||||
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
rospy.Subscriber("mavros/position/local", PoseStamped, self.position_callback)
|
||||
self.pubAtt = rospy.Publisher('mavros/setpoint/attitude', PoseStamped, queue_size=10)
|
||||
self.pubThr = rospy.Publisher('mavros/setpoint/att_throttle', Float64, queue_size=10)
|
||||
self.cmdArm = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
|
||||
self.helper = PX4TestHelper("mavros_offboard_attctl_test")
|
||||
self.helper.setUp()
|
||||
|
||||
rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
rospy.Subscriber("mavros/local_position/local", PoseStamped, self.position_callback)
|
||||
self.pub_att = rospy.Publisher('mavros/setpoint_attitude/attitude', PoseStamped, queue_size=10)
|
||||
self.pub_thr = rospy.Publisher('mavros/setpoint_attitude/att_throttle', Float64, queue_size=10)
|
||||
self.rate = rospy.Rate(10) # 10hz
|
||||
self.rateSec = rospy.Rate(1)
|
||||
self.hasPos = False
|
||||
self.controlMode = vehicle_control_mode()
|
||||
self.has_pos = False
|
||||
self.control_mode = vehicle_control_mode()
|
||||
self.local_position = PoseStamped()
|
||||
|
||||
def tearDown(self):
|
||||
self.helper.tearDown()
|
||||
|
||||
#
|
||||
# General callback functions used in tests
|
||||
#
|
||||
def position_callback(self, data):
|
||||
self.hasPos = True
|
||||
self.localPosition = data
|
||||
self.has_pos = True
|
||||
self.local_position = data
|
||||
|
||||
def vehicle_control_mode_callback(self, data):
|
||||
self.controlMode = data
|
||||
|
||||
|
||||
#
|
||||
# Helper methods
|
||||
#
|
||||
def arm(self):
|
||||
return self.cmdArm(value=True)
|
||||
self.control_mode = data
|
||||
|
||||
#
|
||||
# Test offboard position control
|
||||
#
|
||||
def test_attctl(self):
|
||||
# FIXME: this must go ASAP when arming is implemented
|
||||
manIn = ManualInput()
|
||||
manIn.arm()
|
||||
manIn.offboard_attctl()
|
||||
|
||||
self.assertTrue(self.arm(), "Could not arm")
|
||||
self.rateSec.sleep()
|
||||
self.rateSec.sleep()
|
||||
self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set after 2 seconds")
|
||||
|
||||
# set some attitude and thrust
|
||||
att = PoseStamped()
|
||||
att.header = Header()
|
||||
att.header = Header()
|
||||
att.header.frame_id = "base_footprint"
|
||||
att.header.stamp = rospy.Time.now()
|
||||
quaternion = quaternion_from_euler(0.15, 0.15, 0)
|
||||
@@ -121,21 +105,27 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
|
||||
# does it cross expected boundaries in X seconds?
|
||||
count = 0
|
||||
timeout = 120
|
||||
while(count < timeout):
|
||||
while count < timeout:
|
||||
# update timestamp for each published SP
|
||||
att.header.stamp = rospy.Time.now()
|
||||
self.pubAtt.publish(att)
|
||||
self.pubThr.publish(throttle)
|
||||
|
||||
if (self.localPosition.pose.position.x > 5
|
||||
and self.localPosition.pose.position.z > 5
|
||||
and self.localPosition.pose.position.y < -5):
|
||||
break
|
||||
count = count + 1
|
||||
|
||||
self.pub_att.publish(att)
|
||||
self.helper.bag_write('mavros/setpoint_attitude/attitude', att)
|
||||
self.pub_thr.publish(throttle)
|
||||
self.helper.bag_write('mavros/setpoint_attitude/att_throttle', throttle)
|
||||
self.rate.sleep()
|
||||
|
||||
if (self.local_position.pose.position.x > 5
|
||||
and self.local_position.pose.position.z > 5
|
||||
and self.local_position.pose.position.y < -5):
|
||||
break
|
||||
count = count + 1
|
||||
|
||||
self.assertTrue(self.control_mode.flag_armed, "flag_armed is not set")
|
||||
self.assertTrue(self.control_mode.flag_control_attitude_enabled, "flag_control_attitude_enabled is not set")
|
||||
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
|
||||
self.assertTrue(count < timeout, "took too long to cross boundaries")
|
||||
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
import rostest
|
||||
|
||||
@@ -37,21 +37,21 @@
|
||||
#
|
||||
PKG = 'px4'
|
||||
|
||||
import sys
|
||||
import unittest
|
||||
import rospy
|
||||
import math
|
||||
import rosbag
|
||||
|
||||
from numpy import linalg
|
||||
import numpy as np
|
||||
|
||||
from px4.msg import vehicle_control_mode
|
||||
from px4.msg import vehicle_local_position
|
||||
from px4.msg import vehicle_local_position_setpoint
|
||||
from std_msgs.msg import Header
|
||||
from geometry_msgs.msg import PoseStamped, Quaternion
|
||||
from tf.transformations import quaternion_from_euler
|
||||
from mavros.srv import CommandBool
|
||||
|
||||
from manual_input import ManualInput
|
||||
from px4_test_helper import PX4TestHelper
|
||||
|
||||
#
|
||||
# Tests flying a path in offboard control by sending position setpoints
|
||||
@@ -64,43 +64,53 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
|
||||
|
||||
def setUp(self):
|
||||
rospy.init_node('test_node', anonymous=True)
|
||||
rospy.wait_for_service('mavros/cmd/arming', 30)
|
||||
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
rospy.Subscriber("mavros/position/local", PoseStamped, self.position_callback)
|
||||
self.pubSpt = rospy.Publisher('mavros/setpoint/local_position', PoseStamped, queue_size=10)
|
||||
self.cmdArm = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
|
||||
self.helper = PX4TestHelper("mavros_offboard_posctl_test")
|
||||
self.helper.setUp()
|
||||
|
||||
rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
|
||||
rospy.Subscriber("mavros/local_position/local", PoseStamped, self.position_callback)
|
||||
self.pub_spt = rospy.Publisher('mavros/setpoint_position/local', PoseStamped, queue_size=10)
|
||||
self.rate = rospy.Rate(10) # 10hz
|
||||
self.rateSec = rospy.Rate(1)
|
||||
self.hasPos = False
|
||||
self.controlMode = vehicle_control_mode()
|
||||
self.has_pos = False
|
||||
self.local_position = PoseStamped()
|
||||
self.control_mode = vehicle_control_mode()
|
||||
|
||||
def tearDown(self):
|
||||
self.helper.tearDown()
|
||||
|
||||
#
|
||||
# General callback functions used in tests
|
||||
#
|
||||
def position_callback(self, data):
|
||||
self.hasPos = True
|
||||
self.localPosition = data
|
||||
self.has_pos = True
|
||||
self.local_position = data
|
||||
|
||||
def vehicle_control_mode_callback(self, data):
|
||||
self.controlMode = data
|
||||
self.control_mode = data
|
||||
|
||||
|
||||
#
|
||||
# Helper methods
|
||||
#
|
||||
def is_at_position(self, x, y, z, offset):
|
||||
if(not self.hasPos):
|
||||
if not self.has_pos:
|
||||
return False
|
||||
|
||||
rospy.logdebug("current position %f, %f, %f" % (self.localPosition.pose.position.x, self.localPosition.pose.position.y, self.localPosition.pose.position.z))
|
||||
rospy.logdebug("current position %f, %f, %f" %
|
||||
(self.local_position.pose.position.x,
|
||||
self.local_position.pose.position.y,
|
||||
self.local_position.pose.position.z))
|
||||
|
||||
desired = np.array((x, y, z))
|
||||
pos = np.array((self.localPosition.pose.position.x, self.localPosition.pose.position.y, self.localPosition.pose.position.z))
|
||||
pos = np.array((self.local_position.pose.position.x,
|
||||
self.local_position.pose.position.y,
|
||||
self.local_position.pose.position.z))
|
||||
return linalg.norm(desired - pos) < offset
|
||||
|
||||
def reach_position(self, x, y, z, timeout):
|
||||
# set a position setpoint
|
||||
pos = PoseStamped()
|
||||
pos.header = Header()
|
||||
pos.header = Header()
|
||||
pos.header.frame_id = "base_footprint"
|
||||
pos.pose.position.x = x
|
||||
pos.pose.position.y = y
|
||||
@@ -114,59 +124,47 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
|
||||
|
||||
# does it reach the position in X seconds?
|
||||
count = 0
|
||||
while(count < timeout):
|
||||
while count < timeout:
|
||||
# update timestamp for each published SP
|
||||
pos.header.stamp = rospy.Time.now()
|
||||
self.pubSpt.publish(pos)
|
||||
|
||||
if(self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5)):
|
||||
self.pub_spt.publish(pos)
|
||||
self.helper.bag_write('mavros/setpoint_position/local', pos)
|
||||
|
||||
if self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5):
|
||||
break
|
||||
count = count + 1
|
||||
self.rate.sleep()
|
||||
|
||||
self.assertTrue(count < timeout, "took too long to get to position")
|
||||
|
||||
def arm(self):
|
||||
return self.cmdArm(value=True)
|
||||
|
||||
#
|
||||
# Test offboard position control
|
||||
#
|
||||
def test_posctl(self):
|
||||
# FIXME: this must go ASAP when arming is implemented
|
||||
manIn = ManualInput()
|
||||
manIn.arm()
|
||||
manIn.offboard_posctl()
|
||||
|
||||
self.assertTrue(self.arm(), "Could not arm")
|
||||
self.rateSec.sleep()
|
||||
self.rateSec.sleep()
|
||||
self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set after 2 seconds")
|
||||
|
||||
# prepare flight path
|
||||
positions = (
|
||||
(0,0,0),
|
||||
(2,2,2),
|
||||
(2,-2,2),
|
||||
(-2,-2,2),
|
||||
(2,2,2))
|
||||
(0, 0, 0),
|
||||
(2, 2, 2),
|
||||
(2, -2, 2),
|
||||
(-2, -2, 2),
|
||||
(2, 2, 2))
|
||||
|
||||
for i in range(0, len(positions)):
|
||||
self.reach_position(positions[i][0], positions[i][1], positions[i][2], 120)
|
||||
|
||||
# does it hold the position for Y seconds?
|
||||
positionHeld = True
|
||||
|
||||
count = 0
|
||||
timeout = 50
|
||||
while(count < timeout):
|
||||
if(not self.is_at_position(2, 2, 2, 0.5)):
|
||||
positionHeld = False
|
||||
while count < timeout:
|
||||
if not self.is_at_position(2, 2, 2, 0.5):
|
||||
break
|
||||
count = count + 1
|
||||
self.rate.sleep()
|
||||
|
||||
self.assertTrue(self.control_mode.flag_armed, "flag_armed is not set")
|
||||
self.assertTrue(self.control_mode.flag_control_position_enabled, "flag_control_position_enabled is not set")
|
||||
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
|
||||
self.assertTrue(count == timeout, "position could not be held")
|
||||
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
import rostest
|
||||
|
||||
@@ -2,8 +2,9 @@
|
||||
<arg name="headless" default="true"/>
|
||||
<arg name="gui" default="false"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="false"/>
|
||||
<arg name="log_file" default="iris"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find px4)/launch/gazebo_iris_empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
@@ -11,9 +12,14 @@
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch" />
|
||||
|
||||
<test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" />
|
||||
<test test-name="mavros_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" />
|
||||
<group ns="$(arg ns)">
|
||||
<test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" />
|
||||
<test test-name="mavros_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" />
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
@@ -0,0 +1,111 @@
|
||||
#!/usr/bin/env python
|
||||
#***************************************************************************
|
||||
#
|
||||
# Copyright (c) 2015 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.
|
||||
#
|
||||
#***************************************************************************/
|
||||
|
||||
#
|
||||
# @author Andreas Antener <andreas@uaventure.com>
|
||||
#
|
||||
PKG = 'px4'
|
||||
|
||||
import unittest
|
||||
import rospy
|
||||
import rosbag
|
||||
|
||||
from px4.msg import vehicle_local_position
|
||||
from px4.msg import vehicle_attitude_setpoint
|
||||
from px4.msg import vehicle_attitude
|
||||
from px4.msg import vehicle_local_position_setpoint
|
||||
|
||||
from threading import Condition
|
||||
|
||||
#
|
||||
# Test helper
|
||||
#
|
||||
class PX4TestHelper(object):
|
||||
|
||||
def __init__(self, test_name):
|
||||
self.test_name = test_name
|
||||
|
||||
def setUp(self):
|
||||
self.condition = Condition()
|
||||
self.closed = False
|
||||
|
||||
rospy.init_node('test_node', anonymous=True)
|
||||
self.bag = rosbag.Bag(self.test_name + '.bag', 'w', compression="lz4")
|
||||
|
||||
self.sub_vlp = rospy.Subscriber("iris/vehicle_local_position",
|
||||
vehicle_local_position, self.vehicle_position_callback)
|
||||
self.sub_vasp = rospy.Subscriber("iris/vehicle_attitude_setpoint",
|
||||
vehicle_attitude_setpoint, self.vehicle_attitude_setpoint_callback)
|
||||
self.sub_va = rospy.Subscriber("iris/vehicle_attitude",
|
||||
vehicle_attitude, self.vehicle_attitude_callback)
|
||||
self.sub_vlps = rospy.Subscriber("iris/vehicle_local_position_setpoint",
|
||||
vehicle_local_position_setpoint, self.vehicle_local_position_setpoint_callback)
|
||||
|
||||
|
||||
def tearDown(self):
|
||||
try:
|
||||
self.condition.acquire()
|
||||
self.closed = True
|
||||
|
||||
self.sub_vlp.unregister()
|
||||
self.sub_vasp.unregister()
|
||||
self.sub_va.unregister()
|
||||
self.sub_vlps.unregister()
|
||||
self.bag.close()
|
||||
|
||||
finally:
|
||||
self.condition.release()
|
||||
|
||||
def vehicle_position_callback(self, data):
|
||||
self.bag_write('px4/vehicle_local_position', data)
|
||||
|
||||
def vehicle_attitude_setpoint_callback(self, data):
|
||||
self.bag_write('px4/vehicle_attitude_setpoint', data)
|
||||
|
||||
def vehicle_attitude_callback(self, data):
|
||||
self.bag_write('px4/vehicle_attitude', data)
|
||||
|
||||
def vehicle_local_position_setpoint_callback(self, data):
|
||||
self.bag_write('px4/vehicle_local_position_setpoint', data)
|
||||
|
||||
def bag_write(self, topic, data):
|
||||
try:
|
||||
self.condition.acquire()
|
||||
if not self.closed:
|
||||
self.bag.write(topic, data)
|
||||
else:
|
||||
rospy.logwarn("Trying to write to bag but it's already closed")
|
||||
finally:
|
||||
self.condition.release()
|
||||
|
||||
@@ -1,14 +1,19 @@
|
||||
<launch>
|
||||
<arg name="ns"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter_x.launch" />
|
||||
<include file="$(find px4)/launch/multicopter_x.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
<group ns="px4_multicopter">
|
||||
<group ns="$(arg ns)">
|
||||
<param name="MPC_XY_P" type="double" value="1.0" />
|
||||
<param name="MPC_XY_FF" type="double" value="0.0" />
|
||||
<param name="MPC_XY_FF" type="double" value="0.1" />
|
||||
<param name="MPC_XY_VEL_P" type="double" value="0.01" />
|
||||
<param name="MPC_XY_VEL_I" type="double" value="0.0" />
|
||||
<param name="MPC_XY_VEL_D" type="double" value="0.01" />
|
||||
<param name="MPC_XY_VEL_MAX" type="double" value="2.0" />
|
||||
<param name="MPC_Z_VEL_P" type="double" value="0.3" />
|
||||
<param name="MPC_Z_P" type="double" value="2" />
|
||||
<param name="vehicle_model" type="string" value="ardrone" />
|
||||
</group>
|
||||
|
||||
|
||||
@@ -3,16 +3,19 @@
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="false"/>
|
||||
<arg name="log_file" default="ardrone"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/ardrone_empty_world_with_joy.launch">
|
||||
<include file="$(find rotors_gazebo)/launch/ardrone_empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/ardrone.launch" />
|
||||
<include file="$(find px4)/launch/ardrone.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -1,9 +1,14 @@
|
||||
|
||||
<launch>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
|
||||
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" />
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch" />
|
||||
|
||||
<node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/>
|
||||
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<group ns="$(arg ns)">
|
||||
<node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/>
|
||||
</group>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -1,9 +1,14 @@
|
||||
|
||||
<launch>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
|
||||
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" />
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch" />
|
||||
|
||||
<node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/>
|
||||
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<group ns="$(arg ns)">
|
||||
<node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/>
|
||||
</group>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -4,15 +4,18 @@
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="log_file" default="ardrone"/>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/ardrone_house_world_with_joy.launch">
|
||||
<include file="$(find rotors_gazebo)/launch/ardrone_house_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/ardrone.launch" />
|
||||
<include file="$(find px4)/launch/ardrone.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -4,15 +4,18 @@
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="log_file" default="iris"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/iris_empty_world_with_joy.launch">
|
||||
<include file="$(find rotors_gazebo)/launch/iris_empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/iris.launch" />
|
||||
<include file="$(find px4)/launch/iris.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -4,7 +4,8 @@
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="log_file" default="iris"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/iris_house_world_with_joy.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
@@ -13,6 +14,8 @@
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/iris.launch" />
|
||||
<include file="$(find px4)/launch/iris.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -4,7 +4,8 @@
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="log_file" default="iris"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/iris_outdoor_world_with_joy.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
@@ -13,6 +14,8 @@
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/iris.launch" />
|
||||
<include file="$(find px4)/launch/iris.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
+7
-2
@@ -1,8 +1,11 @@
|
||||
<launch>
|
||||
<arg name="ns"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter_w.launch" />
|
||||
<include file="$(find px4)/launch/multicopter_w.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
<group ns="px4_multicopter">
|
||||
<group ns="$(arg ns)">
|
||||
<param name="mixer" type="string" value="i" />
|
||||
<param name="MPC_XY_P" type="double" value="1.0" />
|
||||
<param name="MPC_XY_FF" type="double" value="0.0" />
|
||||
@@ -10,6 +13,8 @@
|
||||
<param name="MPC_XY_VEL_I" type="double" value="0.0" />
|
||||
<param name="MPC_XY_VEL_D" type="double" value="0.01" />
|
||||
<param name="MPC_XY_VEL_MAX" type="double" value="2.0" />
|
||||
<param name="MPC_Z_VEL_P" type="double" value="0.3" />
|
||||
<param name="MPC_Z_P" type="double" value="2" />
|
||||
<param name="vehicle_model" type="string" value="iris" />
|
||||
</group>
|
||||
|
||||
|
||||
@@ -1,16 +1,16 @@
|
||||
<launch>
|
||||
<!-- vim: set ft=xml noet : -->
|
||||
<!-- example launch script for PX4 based FCU's -->
|
||||
<!-- vim: set ft=xml noet : -->
|
||||
<!-- example launch script for PX4 based FCU's -->
|
||||
|
||||
<arg name="ns" default="/" />
|
||||
<group ns="$(arg ns)">
|
||||
<arg name="fcu_url" default="udp://localhost:14560@localhost:14565" />
|
||||
<arg name="gcs_url" default="" />
|
||||
<arg name="tgt_system" default="1" />
|
||||
<arg name="tgt_component" default="50" />
|
||||
|
||||
<param name="mavros/setpoint/attitude/listen_twist" type="bool" value="false" />
|
||||
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="blacklist_yaml" value="$(find mavros)/launch/px4_blacklist.yaml" />
|
||||
<arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml" />
|
||||
<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />
|
||||
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
@@ -18,4 +18,5 @@
|
||||
<arg name="tgt_system" value="$(arg tgt_system)" />
|
||||
<arg name="tgt_component" value="$(arg tgt_component)" />
|
||||
</include>
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
<launch>
|
||||
<arg name="ns"/>
|
||||
|
||||
<group ns="px4_multicopter">
|
||||
<group ns="$(arg ns)">
|
||||
<node pkg="joy" name="joy_node" type="joy_node"/>
|
||||
<node pkg="px4" name="manual_input" type="manual_input"/>
|
||||
<node pkg="px4" name="commander" type="commander"/>
|
||||
|
||||
@@ -1,8 +1,11 @@
|
||||
<launch>
|
||||
<arg name="ns"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter.launch" />
|
||||
<include file="$(find px4)/launch/multicopter.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
<group ns="px4_multicopter">
|
||||
<group ns="$(arg ns)">
|
||||
<param name="mixer" type="string" value="w" />
|
||||
</group>
|
||||
|
||||
|
||||
@@ -1,8 +1,11 @@
|
||||
<launch>
|
||||
<arg name="ns"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter.launch" />
|
||||
<include file="$(find px4)/launch/multicopter.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
<group ns="px4_multicopter">
|
||||
<group ns="$(arg ns)">
|
||||
<param name="mixer" type="string" value="x" />
|
||||
</group>
|
||||
|
||||
|
||||
@@ -0,0 +1,11 @@
|
||||
#
|
||||
# Board-specific definitions for the PX4_STM32F4DISCOVERY
|
||||
#
|
||||
|
||||
#
|
||||
# Configure the toolchain
|
||||
#
|
||||
CONFIG_ARCH = CORTEXM4F
|
||||
CONFIG_BOARD = PX4_STM32F4DISCOVERY
|
||||
|
||||
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
|
||||
@@ -27,11 +27,10 @@ MODULES += modules/sensors
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/ver
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/preflight_check
|
||||
MODULES += systemcmds/pwm
|
||||
MODULES += systemcmds/esc_calib
|
||||
MODULES += systemcmds/reboot
|
||||
|
||||
@@ -0,0 +1,92 @@
|
||||
#
|
||||
# Makefile for the px4fmu_default configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS, copy the PX4_STM32F4DISCOVERY firmware into
|
||||
# the ROMFS if it's available
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
|
||||
ROMFS_OPTIONAL_FILES =
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/boards/px4-stm32f4discovery
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/bl_update
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/top
|
||||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
MODULES += systemcmds/ver
|
||||
|
||||
#
|
||||
# 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
|
||||
MODULES += platforms/nuttx
|
||||
|
||||
#
|
||||
# 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 )
|
||||
@@ -45,7 +45,6 @@ MODULES += systemcmds/mtd
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/preflight_check
|
||||
MODULES += systemcmds/pwm
|
||||
MODULES += systemcmds/esc_calib
|
||||
MODULES += systemcmds/reboot
|
||||
|
||||
@@ -50,11 +50,9 @@ MODULES += drivers/gimbal
|
||||
# System commands
|
||||
#
|
||||
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
|
||||
|
||||
@@ -48,11 +48,9 @@ MODULES += drivers/px4flow
|
||||
# System commands
|
||||
#
|
||||
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
|
||||
|
||||
@@ -42,11 +42,9 @@ MODULES += modules/sensors
|
||||
# System commands
|
||||
#
|
||||
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
|
||||
|
||||
@@ -180,11 +180,6 @@ GLOBAL_DEPS += $(MAKEFILE_LIST)
|
||||
EXTRA_CLEANS =
|
||||
|
||||
|
||||
#
|
||||
# Extra defines for compilation
|
||||
#
|
||||
export EXTRADEFINES := -DGIT_VERSION=$(GIT_DESC)
|
||||
|
||||
#
|
||||
# Append the per-board driver directory to the header search path.
|
||||
#
|
||||
@@ -499,7 +494,7 @@ $(filter %.S.o,$(OBJS)): $(WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
|
||||
$(PRODUCT_BUNDLE): $(PRODUCT_BIN)
|
||||
@$(ECHO) %% Generating $@
|
||||
ifdef GEN_PARAM_XML
|
||||
python $(PX4_BASE)/Tools/px_process_params.py --src-path $(PX4_BASE)/src --xml
|
||||
python $(PX4_BASE)/Tools/px_process_params.py --src-path $(PX4_BASE)/src --board CONFIG_ARCH_BOARD_$(CONFIG_BOARD) --xml
|
||||
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
|
||||
--git_identity $(PX4_BASE) \
|
||||
--parameter_xml $(PRODUCT_PARAMXML) \
|
||||
|
||||
@@ -296,6 +296,9 @@ endef
|
||||
#
|
||||
# - compile an empty file to generate a suitable object file
|
||||
# - relink the object and insert the binary file
|
||||
# - extract the length
|
||||
# - create const unsigned $3_len with the extracted length as its value and compile it to an object file
|
||||
# - link the two generated object files together
|
||||
# - edit symbol names to suit
|
||||
#
|
||||
# NOTE: exercise caution using this with absolute pathnames; it looks
|
||||
@@ -320,11 +323,14 @@ define BIN_TO_OBJ
|
||||
@$(MKDIR) -p $(dir $2)
|
||||
$(Q) $(ECHO) > $2.c
|
||||
$(call COMPILE,$2.c,$2.c.o)
|
||||
$(Q) $(LD) -r -o $2 $2.c.o -b binary $1
|
||||
$(Q) $(LD) -r -o $2.bin.o $2.c.o -b binary $1
|
||||
$(Q) $(ECHO) "const unsigned int $3_len = 0x`$(NM) -p --radix=x $2.bin.o | $(GREP) $(call BIN_SYM_PREFIX,$1)_size$$ | $(GREP) -o ^[0-9a-fA-F]*`;" > $2.c
|
||||
$(call COMPILE,$2.c,$2.c.o)
|
||||
$(Q) $(LD) -r -o $2 $2.c.o $2.bin.o
|
||||
$(Q) $(OBJCOPY) $2 \
|
||||
--redefine-sym $(call BIN_SYM_PREFIX,$1)_start=$3 \
|
||||
--redefine-sym $(call BIN_SYM_PREFIX,$1)_size=$3_len \
|
||||
--strip-symbol $(call BIN_SYM_PREFIX,$1)_size \
|
||||
--strip-symbol $(call BIN_SYM_PREFIX,$1)_end \
|
||||
--rename-section .data=.rodata
|
||||
$(Q) $(REMOVE) $2.c $2.c.o
|
||||
$(Q) $(REMOVE) $2.c $2.c.o $2.bin.o
|
||||
endef
|
||||
|
||||
+2
-1
@@ -33,7 +33,8 @@ upload-serial-px4fmu-v2: $(BUNDLE) $(UPLOADER)
|
||||
upload-serial-aerocore:
|
||||
openocd -f $(PX4_BASE)/makefiles/gumstix-aerocore.cfg -c 'init; reset halt; flash write_image erase $(PX4_BASE)/../Bootloader/px4aerocore_bl.bin 0x08000000; flash write_image erase $(PX4_BASE)/Build/aerocore_default.build/firmware.bin 0x08004000; reset run; exit'
|
||||
|
||||
|
||||
upload-serial-px4-stm32f4discovery: $(BUNDLE) $(UPLOADER)
|
||||
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
|
||||
|
||||
#
|
||||
# JTAG firmware uploading with OpenOCD
|
||||
|
||||
Submodule mavlink/include/mavlink/v1.0 updated: 7ae438b86e...475e7cc434
@@ -0,0 +1,5 @@
|
||||
uint64 timestamp # in microseconds since system start
|
||||
|
||||
float32 roll_rate_integ # roll rate inegrator
|
||||
float32 pitch_rate_integ # pitch rate integrator
|
||||
float32 yaw_rate_integ # yaw rate integrator
|
||||
@@ -112,6 +112,7 @@ bool condition_airspeed_valid # set to true by the commander app if there is a
|
||||
bool condition_landed # true if vehicle is landed, always true if disarmed
|
||||
bool condition_power_input_valid # set if input power is valid
|
||||
float32 avionics_power_rail_voltage # voltage of the avionics power rail
|
||||
bool usb_connected # status of the USB power supply
|
||||
|
||||
bool rc_signal_found_once
|
||||
bool rc_signal_lost # true if RC reception lost
|
||||
|
||||
@@ -145,7 +145,7 @@
|
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* Note: TIM1,8 are on APB2, others on APB1
|
||||
*/
|
||||
|
||||
@@ -203,7 +203,7 @@
|
||||
/*
|
||||
* SPI
|
||||
*/
|
||||
/* PA[4-7] SPI1 broken out on J12 */
|
||||
/* PA[4-7] SPI1 broken out on J12 */
|
||||
#define GPIO_SPI1_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) /* should be GPIO_SPI1_NSS_2 but use as a GPIO */
|
||||
#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI1_MISO (GPIO_SPI1_MISO_1|GPIO_SPEED_50MHz)
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
||||
|
||||
@@ -0,0 +1,273 @@
|
||||
/************************************************************************************
|
||||
* configs/stm32f4discovery/include/board.h
|
||||
* include/arch/board/board.h
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 NuttX 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
|
||||
#define __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdio.h"
|
||||
#include "stm32.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The STM32F4 Discovery board features a single 8MHz crystal. Space is provided
|
||||
* for a 32kHz RTC backup crystal, but it is not stuffed.
|
||||
*
|
||||
* This is the canonical configuration:
|
||||
* System Clock source : PLL (HSE)
|
||||
* SYSCLK(Hz) : 168000000 Determined by PLL configuration
|
||||
* HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
|
||||
* AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
|
||||
* APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
|
||||
* APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
|
||||
* HSE Frequency(Hz) : 8000000 (STM32_BOARD_XTAL)
|
||||
* PLLM : 8 (STM32_PLLCFG_PLLM)
|
||||
* PLLN : 336 (STM32_PLLCFG_PLLN)
|
||||
* PLLP : 2 (STM32_PLLCFG_PLLP)
|
||||
* PLLQ : 7 (STM32_PLLCFG_PLLQ)
|
||||
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
|
||||
* Flash Latency(WS) : 5
|
||||
* Prefetch Buffer : OFF
|
||||
* Instruction cache : ON
|
||||
* Data cache : ON
|
||||
* Require 48MHz for USB OTG FS, : Enabled
|
||||
* SDIO and RNG clock
|
||||
*/
|
||||
|
||||
/* HSI - 16 MHz RC factory-trimmed
|
||||
* LSI - 32 KHz RC
|
||||
* HSE - On-board crystal frequency is 8MHz
|
||||
* LSE - 32.768 kHz
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 8000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 32768
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE
|
||||
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
* = (8,000,000 / 8) * 336
|
||||
* = 336,000,000
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* = 336,000,000 / 2 = 168,000,000
|
||||
* USB OTG FS, SDIO and RNG Clock
|
||||
* = PLL_VCO / PLLQ
|
||||
* = 48,000,000
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
|
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
|
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
|
||||
|
||||
#define STM32_SYSCLK_FREQUENCY 168000000ul
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (168MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
|
||||
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
|
||||
|
||||
/* Timers driven from APB1 will be twice PCLK1 */
|
||||
|
||||
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* Timers driven from APB2 will be twice PCLK2 */
|
||||
|
||||
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* Note: TIM1,8 are on APB2, others on APB1
|
||||
*/
|
||||
|
||||
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
|
||||
* way. The following definitions are used to access individual LEDs.
|
||||
*/
|
||||
|
||||
/* LED index values for use with stm32_setled() */
|
||||
|
||||
#define BOARD_LED1 0
|
||||
#define BOARD_LED2 1
|
||||
#define BOARD_NLEDS 2
|
||||
|
||||
#define BOARD_LED_BLUE BOARD_LED1
|
||||
#define BOARD_LED_RED BOARD_LED2
|
||||
|
||||
/* LED bits for use with stm32_setleds() */
|
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1)
|
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2)
|
||||
|
||||
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the
|
||||
* px4fmu-v1. The following definitions describe how NuttX controls the LEDs:
|
||||
*/
|
||||
|
||||
#define LED_STARTED 0 /* LED1 */
|
||||
#define LED_HEAPALLOCATE 1 /* LED2 */
|
||||
#define LED_IRQSENABLED 2 /* LED1 */
|
||||
#define LED_STACKCREATED 3 /* LED1 + LED2 */
|
||||
#define LED_INIRQ 4 /* LED1 */
|
||||
#define LED_SIGNAL 5 /* LED2 */
|
||||
#define LED_ASSERTION 6 /* LED1 + LED2 */
|
||||
#define LED_PANIC 7 /* LED1 + LED2 */
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/* UART2:
|
||||
*
|
||||
* The STM32F4 Discovery has no on-board serial devices, but the console is
|
||||
* brought out to PA2 (TX) and PA3 (RX) for connection to an external serial device.
|
||||
* (See the README.txt file for other options)
|
||||
*/
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_1
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_1
|
||||
|
||||
/* SPI - There is a MEMS device on SPI1 using these pins: */
|
||||
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
|
||||
|
||||
/*
|
||||
* I2C
|
||||
*
|
||||
* The optional _GPIO configurations allow the I2C driver to manually
|
||||
* reset the bus to clear stuck slaves. They match the pin configuration,
|
||||
* but are normally-high GPIOs.
|
||||
*/
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the intitialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
EXTERN void stm32_boardinitialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_ledinit, stm32_setled, and stm32_setleds
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
|
||||
* CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
|
||||
* control the LEDs from user applications.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef CONFIG_ARCH_LEDS
|
||||
EXTERN void stm32_ledinit(void);
|
||||
EXTERN void stm32_setled(int led, bool ledon);
|
||||
EXTERN void stm32_setleds(uint8_t ledset);
|
||||
#endif
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H */
|
||||
@@ -0,0 +1,42 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* nsh_romfsetc.h
|
||||
*
|
||||
* This file is a stub for 'make export' purposes; the actual ROMFS
|
||||
* must be supplied by the library client.
|
||||
*/
|
||||
|
||||
extern unsigned char romfs_img[];
|
||||
extern unsigned int romfs_img_len;
|
||||
@@ -0,0 +1,179 @@
|
||||
############################################################################
|
||||
# configs/px4fmu-v2/nsh/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# 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 NuttX 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
include ${TOPDIR}/tools/Config.mk
|
||||
|
||||
#
|
||||
# We only support building with the ARM bare-metal toolchain from
|
||||
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
|
||||
#
|
||||
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
|
||||
|
||||
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)nm
|
||||
OBJCOPY = $(CROSSDEV)objcopy
|
||||
OBJDUMP = $(CROSSDEV)objdump
|
||||
|
||||
MAXOPTIMIZATION = -O3
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m4 \
|
||||
-mthumb \
|
||||
-march=armv7e-m \
|
||||
-mfpu=fpv4-sp-d16 \
|
||||
-mfloat-abi=hard
|
||||
|
||||
|
||||
# enable precise stack overflow tracking
|
||||
INSTRUMENTATIONDEFINES = -finstrument-functions \
|
||||
-ffixed-r10
|
||||
|
||||
# pull in *just* libm from the toolchain ... this is grody
|
||||
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
|
||||
EXTRA_LIBS += $(LIBM)
|
||||
|
||||
# use our linker script
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||
else
|
||||
ifeq ($(PX4_WINTOOL),y)
|
||||
# Windows-native toolchains (MSYS)
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||
endif
|
||||
endif
|
||||
|
||||
# tool versions
|
||||
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
|
||||
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
|
||||
|
||||
# optimisation flags
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
|
||||
-fno-strict-aliasing \
|
||||
-fno-strength-reduce \
|
||||
-fomit-frame-pointer \
|
||||
-funsafe-math-optimizations \
|
||||
-fno-builtin-printf \
|
||||
-ffunction-sections \
|
||||
-fdata-sections
|
||||
|
||||
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
|
||||
ARCHOPTIMIZATION += -g
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wextra \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
-Wfloat-equal \
|
||||
-Wframe-larger-than=1024 \
|
||||
-Wpointer-arith \
|
||||
-Wlogical-op \
|
||||
-Wmissing-declarations \
|
||||
-Wpacked \
|
||||
-Wno-unused-parameter
|
||||
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
|
||||
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
|
||||
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
|
||||
|
||||
ARCHCWARNINGS = $(ARCHWARNINGS) \
|
||||
-Wbad-function-cast \
|
||||
-Wstrict-prototypes \
|
||||
-Wold-style-declaration \
|
||||
-Wmissing-parameter-type \
|
||||
-Wmissing-prototypes \
|
||||
-Wnested-externs \
|
||||
-Wunsuffixed-float-constants
|
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) \
|
||||
-Wno-psabi
|
||||
ARCHDEFINES =
|
||||
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
|
||||
|
||||
# this seems to be the only way to add linker flags
|
||||
EXTRA_LIBS += --warn-common \
|
||||
--gc-sections
|
||||
|
||||
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
|
||||
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
|
||||
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
|
||||
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
|
||||
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
|
||||
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
|
||||
|
||||
NXFLATLDFLAGS1 = -r -d -warn-common
|
||||
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
|
||||
# produce partially-linked $1 from files in $2
|
||||
define PRELINK
|
||||
@echo "PRELINK: $1"
|
||||
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
||||
+14
-10
@@ -1,6 +1,8 @@
|
||||
############################################################################
|
||||
# configs/px4fmu/nsh/appconfig
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -12,7 +14,7 @@
|
||||
# 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
|
||||
# 3. Neither the name NuttX nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
@@ -31,14 +33,16 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Pre-flight check. Locks down system for a few systems with blinking leds
|
||||
# and buzzer if the sensors do not report an OK status.
|
||||
#
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
MODULE_COMMAND = preflight_check
|
||||
SRCS = preflight_check.c
|
||||
CONFIGURED_APPS += examples/nsh
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
# The NSH application library
|
||||
CONFIGURED_APPS += nshlib
|
||||
CONFIGURED_APPS += system/readline
|
||||
|
||||
MODULE_STACKSIZE = 1800
|
||||
#ifeq ($(CONFIG_USBDEV),y)
|
||||
#ifeq ($(CONFIG_CDCACM),y)
|
||||
CONFIGURED_APPS += examples/cdcacm
|
||||
#endif
|
||||
#endif
|
||||
@@ -0,0 +1,897 @@
|
||||
#
|
||||
# Automatically generated file; DO NOT EDIT.
|
||||
# Nuttx/ Configuration
|
||||
#
|
||||
CONFIG_NUTTX_NEWCONFIG=y
|
||||
|
||||
#
|
||||
# Build Setup
|
||||
#
|
||||
# CONFIG_EXPERIMENTAL is not set
|
||||
# CONFIG_HOST_LINUX is not set
|
||||
CONFIG_HOST_OSX=y
|
||||
# CONFIG_HOST_WINDOWS is not set
|
||||
# CONFIG_HOST_OTHER is not set
|
||||
|
||||
#
|
||||
# Build Configuration
|
||||
#
|
||||
CONFIG_APPS_DIR="../apps"
|
||||
# CONFIG_BUILD_2PASS is not set
|
||||
|
||||
#
|
||||
# Binary Output Formats
|
||||
#
|
||||
# CONFIG_RRLOAD_BINARY is not set
|
||||
# CONFIG_INTELHEX_BINARY is not set
|
||||
# CONFIG_MOTOROLA_SREC is not set
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
#
|
||||
# Customize Header Files
|
||||
#
|
||||
# CONFIG_ARCH_STDBOOL_H is not set
|
||||
CONFIG_ARCH_MATH_H=y
|
||||
# CONFIG_ARCH_FLOAT_H is not set
|
||||
# CONFIG_ARCH_STDARG_H is not set
|
||||
|
||||
#
|
||||
# Debug Options
|
||||
#
|
||||
# CONFIG_DEBUG is not set
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
|
||||
#
|
||||
# System Type
|
||||
#
|
||||
# CONFIG_ARCH_8051 is not set
|
||||
CONFIG_ARCH_ARM=y
|
||||
# CONFIG_ARCH_AVR is not set
|
||||
# CONFIG_ARCH_HC is not set
|
||||
# CONFIG_ARCH_MIPS is not set
|
||||
# CONFIG_ARCH_RGMP is not set
|
||||
# CONFIG_ARCH_SH is not set
|
||||
# CONFIG_ARCH_SIM is not set
|
||||
# CONFIG_ARCH_X86 is not set
|
||||
# CONFIG_ARCH_Z16 is not set
|
||||
# CONFIG_ARCH_Z80 is not set
|
||||
CONFIG_ARCH="arm"
|
||||
|
||||
#
|
||||
# ARM Options
|
||||
#
|
||||
# CONFIG_ARCH_CHIP_C5471 is not set
|
||||
# CONFIG_ARCH_CHIP_CALYPSO is not set
|
||||
# CONFIG_ARCH_CHIP_DM320 is not set
|
||||
# CONFIG_ARCH_CHIP_IMX is not set
|
||||
# CONFIG_ARCH_CHIP_KINETIS is not set
|
||||
# CONFIG_ARCH_CHIP_KL is not set
|
||||
# CONFIG_ARCH_CHIP_LM is not set
|
||||
# CONFIG_ARCH_CHIP_LPC17XX is not set
|
||||
# CONFIG_ARCH_CHIP_LPC214X is not set
|
||||
# CONFIG_ARCH_CHIP_LPC2378 is not set
|
||||
# CONFIG_ARCH_CHIP_LPC31XX is not set
|
||||
# CONFIG_ARCH_CHIP_LPC43XX is not set
|
||||
# CONFIG_ARCH_CHIP_NUC1XX is not set
|
||||
# CONFIG_ARCH_CHIP_SAM34 is not set
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
# CONFIG_ARCH_CHIP_STR71X is not set
|
||||
CONFIG_ARCH_CORTEXM4=y
|
||||
CONFIG_ARCH_FAMILY="armv7-m"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARCH_HAVE_CMNVECTOR=y
|
||||
CONFIG_ARMV7M_CMNVECTOR=y
|
||||
CONFIG_ARCH_HAVE_FPU=y
|
||||
CONFIG_ARCH_FPU=y
|
||||
CONFIG_ARCH_HAVE_MPU=y
|
||||
# CONFIG_ARMV7M_MPU is not set
|
||||
|
||||
#
|
||||
# ARMV7M Configuration Options
|
||||
#
|
||||
# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
|
||||
CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
|
||||
CONFIG_ARMV7M_STACKCHECK=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
|
||||
#
|
||||
# STM32 Configuration Options
|
||||
#
|
||||
# CONFIG_ARCH_CHIP_STM32L151C6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151R6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151R8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151V6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151V8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152C6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152R6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152R8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152V6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152V8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100R8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RD is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100V8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VD is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103C4 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F107VC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F207IG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302CC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302RC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302VC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303CC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303RC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303VC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F405RG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F405VG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F405ZG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407VE is not set
|
||||
CONFIG_ARCH_CHIP_STM32F407VG=y
|
||||
# CONFIG_ARCH_CHIP_STM32F407ZE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407ZG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407IE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407IG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F427V is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F427Z is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F427I is not set
|
||||
# CONFIG_STM32_STM32L15XX is not set
|
||||
# CONFIG_STM32_ENERGYLITE is not set
|
||||
# CONFIG_STM32_STM32F10XX is not set
|
||||
# CONFIG_STM32_VALUELINE is not set
|
||||
# CONFIG_STM32_CONNECTIVITYLINE is not set
|
||||
# CONFIG_STM32_PERFORMANCELINE is not set
|
||||
# CONFIG_STM32_HIGHDENSITY is not set
|
||||
# CONFIG_STM32_MEDIUMDENSITY is not set
|
||||
# CONFIG_STM32_LOWDENSITY is not set
|
||||
# CONFIG_STM32_STM32F20XX is not set
|
||||
# CONFIG_STM32_STM32F30XX is not set
|
||||
CONFIG_STM32_STM32F40XX=y
|
||||
# CONFIG_STM32_STM32F427 is not set
|
||||
# CONFIG_STM32_DFU is not set
|
||||
|
||||
#
|
||||
# STM32 Peripheral Support
|
||||
#
|
||||
CONFIG_STM32_ADC1=y
|
||||
# CONFIG_STM32_ADC2 is not set
|
||||
# CONFIG_STM32_ADC3 is not set
|
||||
CONFIG_STM32_BKPSRAM=y
|
||||
# CONFIG_STM32_CAN1 is not set
|
||||
# CONFIG_STM32_CAN2 is not set
|
||||
CONFIG_STM32_CCMDATARAM=y
|
||||
# CONFIG_STM32_CRC is not set
|
||||
# CONFIG_STM32_CRYP is not set
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
# CONFIG_STM32_DAC1 is not set
|
||||
# CONFIG_STM32_DAC2 is not set
|
||||
# CONFIG_STM32_DCMI is not set
|
||||
# CONFIG_STM32_ETHMAC is not set
|
||||
# CONFIG_STM32_FSMC is not set
|
||||
# CONFIG_STM32_HASH is not set
|
||||
CONFIG_STM32_I2C1=y
|
||||
# CONFIG_STM32_I2C2 is not set
|
||||
# CONFIG_STM32_I2C3 is not set
|
||||
CONFIG_STM32_OTGFS=y
|
||||
# CONFIG_STM32_OTGHS is not set
|
||||
CONFIG_STM32_PWR=y
|
||||
# CONFIG_STM32_RNG is not set
|
||||
# CONFIG_STM32_SDIO is not set
|
||||
CONFIG_STM32_SPI1=y
|
||||
# CONFIG_STM32_SPI2 is not set
|
||||
# CONFIG_STM32_SPI3 is not set
|
||||
# CONFIG_STM32_SPI4 is not set
|
||||
# CONFIG_STM32_SPI5 is not set
|
||||
# CONFIG_STM32_SPI6 is not set
|
||||
CONFIG_STM32_SYSCFG=y
|
||||
CONFIG_STM32_TIM1=y
|
||||
# CONFIG_STM32_TIM2 is not set
|
||||
CONFIG_STM32_TIM3=y
|
||||
CONFIG_STM32_TIM4=y
|
||||
# CONFIG_STM32_TIM5 is not set
|
||||
# CONFIG_STM32_TIM6 is not set
|
||||
# CONFIG_STM32_TIM7 is not set
|
||||
# CONFIG_STM32_TIM8 is not set
|
||||
CONFIG_STM32_TIM9=y
|
||||
CONFIG_STM32_TIM10=y
|
||||
CONFIG_STM32_TIM11=y
|
||||
# CONFIG_STM32_TIM12 is not set
|
||||
# CONFIG_STM32_TIM13 is not set
|
||||
# CONFIG_STM32_TIM14 is not set
|
||||
# CONFIG_STM32_USART1 is not set
|
||||
CONFIG_STM32_USART2=y
|
||||
# CONFIG_STM32_USART3 is not set
|
||||
# CONFIG_STM32_UART4 is not set
|
||||
# CONFIG_STM32_UART5 is not set
|
||||
# CONFIG_STM32_USART6 is not set
|
||||
# CONFIG_STM32_UART7 is not set
|
||||
# CONFIG_STM32_UART8 is not set
|
||||
# CONFIG_STM32_IWDG is not set
|
||||
# CONFIG_STM32_WWDG is not set
|
||||
CONFIG_STM32_ADC=y
|
||||
CONFIG_STM32_SPI=y
|
||||
CONFIG_STM32_I2C=y
|
||||
|
||||
#
|
||||
# Alternate Pin Mapping
|
||||
#
|
||||
CONFIG_STM32_FLASH_PREFETCH=y
|
||||
# CONFIG_STM32_JTAG_DISABLE is not set
|
||||
# CONFIG_STM32_JTAG_FULL_ENABLE is not set
|
||||
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
# CONFIG_STM32_FORCEPOWER is not set
|
||||
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
|
||||
# CONFIG_STM32_CCMEXCLUDE is not set
|
||||
CONFIG_STM32_DMACAPABLE=y
|
||||
# CONFIG_STM32_TIM1_PWM is not set
|
||||
# CONFIG_STM32_TIM3_PWM is not set
|
||||
# CONFIG_STM32_TIM4_PWM is not set
|
||||
# CONFIG_STM32_TIM9_PWM is not set
|
||||
# CONFIG_STM32_TIM10_PWM is not set
|
||||
# CONFIG_STM32_TIM11_PWM is not set
|
||||
# CONFIG_STM32_TIM1_ADC is not set
|
||||
# CONFIG_STM32_TIM3_ADC is not set
|
||||
# CONFIG_STM32_TIM4_ADC is not set
|
||||
CONFIG_STM32_USART=y
|
||||
|
||||
#
|
||||
# U[S]ART Configuration
|
||||
#
|
||||
# CONFIG_USART2_RS485 is not set
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_USART_SINGLEWIRE=y
|
||||
|
||||
#
|
||||
# SPI Configuration
|
||||
#
|
||||
# CONFIG_STM32_SPI_INTERRUPTS is not set
|
||||
# CONFIG_STM32_SPI_DMA is not set
|
||||
|
||||
#
|
||||
# I2C Configuration
|
||||
#
|
||||
# CONFIG_STM32_I2C_DYNTIMEO is not set
|
||||
CONFIG_STM32_I2CTIMEOSEC=0
|
||||
CONFIG_STM32_I2CTIMEOMS=500
|
||||
CONFIG_STM32_I2CTIMEOTICKS=500
|
||||
# CONFIG_STM32_I2C_DUTY16_9 is not set
|
||||
|
||||
#
|
||||
# USB Host Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# USB Device Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# External Memory Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Architecture Options
|
||||
#
|
||||
# CONFIG_ARCH_NOINTC is not set
|
||||
# CONFIG_ARCH_VECNOTIRQ is not set
|
||||
CONFIG_ARCH_DMA=y
|
||||
CONFIG_ARCH_IRQPRIO=y
|
||||
# CONFIG_CUSTOM_STACK is not set
|
||||
# CONFIG_ADDRENV is not set
|
||||
CONFIG_ARCH_HAVE_VFORK=y
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
# CONFIG_ENDIAN_BIG is not set
|
||||
# CONFIG_ARCH_HAVE_RAMFUNCS is not set
|
||||
CONFIG_ARCH_HAVE_RAMVECTORS=y
|
||||
# CONFIG_ARCH_RAMVECTORS is not set
|
||||
|
||||
#
|
||||
# Board Settings
|
||||
#
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
# CONFIG_ARCH_CALIBRATION is not set
|
||||
CONFIG_DRAM_START=0x20000000
|
||||
CONFIG_DRAM_SIZE=196608
|
||||
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=4096
|
||||
|
||||
#
|
||||
# Boot options
|
||||
#
|
||||
# CONFIG_BOOT_RUNFROMEXTSRAM is not set
|
||||
CONFIG_BOOT_RUNFROMFLASH=y
|
||||
# CONFIG_BOOT_RUNFROMISRAM is not set
|
||||
# CONFIG_BOOT_RUNFROMSDRAM is not set
|
||||
# CONFIG_BOOT_COPYTORAM is not set
|
||||
|
||||
#
|
||||
# Board Selection
|
||||
#
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD=""
|
||||
|
||||
#
|
||||
# Common Board Options
|
||||
#
|
||||
CONFIG_NSH_MMCSDMINOR=0
|
||||
|
||||
#
|
||||
# Board-Specific Options
|
||||
#
|
||||
|
||||
#
|
||||
# RTOS Features
|
||||
#
|
||||
# CONFIG_BOARD_INITIALIZE is not set
|
||||
CONFIG_MSEC_PER_TICK=1
|
||||
CONFIG_RR_INTERVAL=0
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
# CONFIG_SCHED_HAVE_PARENT is not set
|
||||
# CONFIG_JULIAN_TIME is not set
|
||||
CONFIG_START_YEAR=1970
|
||||
CONFIG_START_MONTH=1
|
||||
CONFIG_START_DAY=1
|
||||
CONFIG_DEV_CONSOLE=y
|
||||
# CONFIG_MUTEX_TYPES is not set
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
# CONFIG_FDCLONE_DISABLE is not set
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
# CONFIG_SCHED_STARTHOOK is not set
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_ATEXIT_MAX=1
|
||||
# CONFIG_SCHED_ONEXIT is not set
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
# CONFIG_DISABLE_OS_API is not set
|
||||
|
||||
#
|
||||
# Signal Numbers
|
||||
#
|
||||
CONFIG_SIG_SIGUSR1=1
|
||||
CONFIG_SIG_SIGUSR2=2
|
||||
CONFIG_SIG_SIGALARM=3
|
||||
CONFIG_SIG_SIGCONDTIMEDOUT=16
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
|
||||
#
|
||||
# Sizes of configurable things (0 disables)
|
||||
#
|
||||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=44
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
CONFIG_MQ_MAXMSGSIZE=32
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
|
||||
#
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_IDLETHREAD_STACKSIZE=6000
|
||||
CONFIG_USERMAIN_STACKSIZE=4096
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
|
||||
#
|
||||
# Device Drivers
|
||||
#
|
||||
# CONFIG_DISABLE_POLL is not set
|
||||
CONFIG_DEV_NULL=y
|
||||
# CONFIG_DEV_ZERO is not set
|
||||
# CONFIG_LOOP is not set
|
||||
# CONFIG_RAMDISK is not set
|
||||
# CONFIG_CAN is not set
|
||||
# CONFIG_PWM is not set
|
||||
CONFIG_I2C=y
|
||||
# CONFIG_I2C_SLAVE is not set
|
||||
CONFIG_I2C_TRANSFER=y
|
||||
# CONFIG_I2C_WRITEREAD is not set
|
||||
# CONFIG_I2C_POLLED is not set
|
||||
# CONFIG_I2C_TRACE is not set
|
||||
CONFIG_ARCH_HAVE_I2CRESET=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_SPI=y
|
||||
# CONFIG_SPI_OWNBUS is not set
|
||||
CONFIG_SPI_EXCHANGE=y
|
||||
# CONFIG_SPI_CMDDATA is not set
|
||||
# CONFIG_RTC is not set
|
||||
CONFIG_WATCHDOG=y
|
||||
# CONFIG_ANALOG is not set
|
||||
# CONFIG_AUDIO_DEVICES is not set
|
||||
# CONFIG_BCH is not set
|
||||
# CONFIG_INPUT is not set
|
||||
# CONFIG_LCD is not set
|
||||
# CONFIG_MMCSD is not set
|
||||
# CONFIG_MTD is not set
|
||||
CONFIG_PIPES=y
|
||||
# CONFIG_PM is not set
|
||||
# CONFIG_POWER is not set
|
||||
# CONFIG_SENSORS is not set
|
||||
CONFIG_SERIAL=y
|
||||
# CONFIG_DEV_LOWCONSOLE is not set
|
||||
CONFIG_SERIAL_REMOVABLE=y
|
||||
# CONFIG_16550_UART is not set
|
||||
CONFIG_ARCH_HAVE_USART2=y
|
||||
CONFIG_MCU_SERIAL=y
|
||||
CONFIG_STANDARD_SERIAL=y
|
||||
CONFIG_SERIAL_NPOLLWAITERS=2
|
||||
CONFIG_USART2_SERIAL_CONSOLE=y
|
||||
# CONFIG_NO_SERIAL_CONSOLE is not set
|
||||
|
||||
#
|
||||
# USART2 Configuration
|
||||
#
|
||||
CONFIG_USART2_RXBUFSIZE=512
|
||||
CONFIG_USART2_TXBUFSIZE=512
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_BITS=8
|
||||
CONFIG_USART2_PARITY=0
|
||||
CONFIG_USART2_2STOP=0
|
||||
# CONFIG_USART2_IFLOWCONTROL is not set
|
||||
# CONFIG_USART2_OFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_IFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_OFLOWCONTROL is not set
|
||||
CONFIG_USBDEV=y
|
||||
|
||||
#
|
||||
# USB Device Controller Driver Options
|
||||
#
|
||||
# CONFIG_USBDEV_ISOCHRONOUS is not set
|
||||
# CONFIG_USBDEV_DUALSPEED is not set
|
||||
# CONFIG_USBDEV_SELFPOWERED is not set
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
# CONFIG_USBDEV_DMA is not set
|
||||
# CONFIG_USBDEV_TRACE is not set
|
||||
|
||||
#
|
||||
# USB Device Class Driver Options
|
||||
#
|
||||
# CONFIG_USBDEV_COMPOSITE is not set
|
||||
# CONFIG_PL2303 is not set
|
||||
CONFIG_CDCACM=y
|
||||
# CONFIG_CDCACM_CONSOLE is not set
|
||||
CONFIG_CDCACM_EP0MAXPACKET=64
|
||||
CONFIG_CDCACM_EPINTIN=1
|
||||
CONFIG_CDCACM_EPINTIN_FSSIZE=64
|
||||
CONFIG_CDCACM_EPINTIN_HSSIZE=64
|
||||
CONFIG_CDCACM_EPBULKOUT=3
|
||||
CONFIG_CDCACM_EPBULKOUT_FSSIZE=64
|
||||
CONFIG_CDCACM_EPBULKOUT_HSSIZE=512
|
||||
CONFIG_CDCACM_EPBULKIN=2
|
||||
CONFIG_CDCACM_EPBULKIN_FSSIZE=64
|
||||
CONFIG_CDCACM_EPBULKIN_HSSIZE=512
|
||||
CONFIG_CDCACM_NWRREQS=4
|
||||
CONFIG_CDCACM_NRDREQS=4
|
||||
CONFIG_CDCACM_BULKIN_REQLEN=96
|
||||
CONFIG_CDCACM_RXBUFSIZE=512
|
||||
CONFIG_CDCACM_TXBUFSIZE=2048
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_PRODUCTID=0x0011
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v2.x"
|
||||
# CONFIG_USBMSC is not set
|
||||
# CONFIG_USBHOST is not set
|
||||
# CONFIG_WIRELESS is not set
|
||||
|
||||
#
|
||||
# System Logging Device Options
|
||||
#
|
||||
|
||||
#
|
||||
# System Logging
|
||||
#
|
||||
# CONFIG_RAMLOG is not set
|
||||
|
||||
#
|
||||
# Networking Support
|
||||
#
|
||||
# CONFIG_NET is not set
|
||||
|
||||
#
|
||||
# File Systems
|
||||
#
|
||||
|
||||
#
|
||||
# File system configuration
|
||||
#
|
||||
# CONFIG_DISABLE_MOUNTPOINT is not set
|
||||
# CONFIG_FS_RAMMAP is not set
|
||||
CONFIG_FS_FAT=y
|
||||
# CONFIG_FAT_LCNAMES is not set
|
||||
# CONFIG_FAT_LFN is not set
|
||||
# CONFIG_FS_FATTIME is not set
|
||||
# CONFIG_FAT_DMAMEMORY is not set
|
||||
CONFIG_FS_NXFFS=y
|
||||
CONFIG_NXFFS_PREALLOCATED=y
|
||||
CONFIG_NXFFS_ERASEDSTATE=0xff
|
||||
CONFIG_NXFFS_PACKTHRESHOLD=32
|
||||
CONFIG_NXFFS_MAXNAMLEN=32
|
||||
CONFIG_NXFFS_TAILTHRESHOLD=2048
|
||||
CONFIG_FS_ROMFS=y
|
||||
# CONFIG_FS_SMARTFS is not set
|
||||
CONFIG_FS_BINFS=y
|
||||
|
||||
#
|
||||
# System Logging
|
||||
#
|
||||
# CONFIG_SYSLOG_ENABLE is not set
|
||||
# CONFIG_SYSLOG is not set
|
||||
|
||||
#
|
||||
# Graphics Support
|
||||
#
|
||||
# CONFIG_NX is not set
|
||||
|
||||
#
|
||||
# Memory Management
|
||||
#
|
||||
# CONFIG_MM_MULTIHEAP is not set
|
||||
# CONFIG_MM_SMALL is not set
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_GRAN=y
|
||||
# CONFIG_GRAN_SINGLE is not set
|
||||
# CONFIG_GRAN_INTR is not set
|
||||
|
||||
#
|
||||
# Audio Support
|
||||
#
|
||||
# CONFIG_AUDIO is not set
|
||||
|
||||
#
|
||||
# Binary Formats
|
||||
#
|
||||
# CONFIG_BINFMT_DISABLE is not set
|
||||
# CONFIG_BINFMT_EXEPATH is not set
|
||||
# CONFIG_NXFLAT is not set
|
||||
# CONFIG_ELF is not set
|
||||
CONFIG_BUILTIN=y
|
||||
# CONFIG_PIC is not set
|
||||
# CONFIG_SYMTAB_ORDEREDBYNAME is not set
|
||||
|
||||
#
|
||||
# Library Routines
|
||||
#
|
||||
|
||||
#
|
||||
# Standard C Library Options
|
||||
#
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STDIO_LINEBUFFER=y
|
||||
CONFIG_NUNGET_CHARS=2
|
||||
CONFIG_LIB_HOMEDIR="/"
|
||||
# CONFIG_NOPRINTF_FIELDWIDTH is not set
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIB_RAND_ORDER=1
|
||||
# CONFIG_EOL_IS_CR is not set
|
||||
# CONFIG_EOL_IS_LF is not set
|
||||
# CONFIG_EOL_IS_BOTH_CRLF is not set
|
||||
CONFIG_EOL_IS_EITHER_CRLF=y
|
||||
# CONFIG_LIBC_EXECFUNCS is not set
|
||||
CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
|
||||
CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
# CONFIG_LIBC_STRERROR_SHORT is not set
|
||||
# CONFIG_LIBC_PERROR_STDOUT is not set
|
||||
CONFIG_ARCH_LOWPUTC=y
|
||||
CONFIG_LIB_SENDFILE_BUFSIZE=512
|
||||
# CONFIG_ARCH_ROMGETC is not set
|
||||
CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y
|
||||
CONFIG_ARCH_MEMCPY=y
|
||||
# CONFIG_ARCH_MEMCMP is not set
|
||||
# CONFIG_ARCH_MEMMOVE is not set
|
||||
# CONFIG_ARCH_MEMSET is not set
|
||||
# CONFIG_MEMSET_OPTSPEED is not set
|
||||
# CONFIG_ARCH_STRCHR is not set
|
||||
# CONFIG_ARCH_STRCMP is not set
|
||||
# CONFIG_ARCH_STRCPY is not set
|
||||
# CONFIG_ARCH_STRNCPY is not set
|
||||
# CONFIG_ARCH_STRLEN is not set
|
||||
# CONFIG_ARCH_STRNLEN is not set
|
||||
# CONFIG_ARCH_BZERO is not set
|
||||
|
||||
#
|
||||
# Non-standard Library Support
|
||||
#
|
||||
CONFIG_SCHED_WORKQUEUE=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_WORKPRIORITY=192
|
||||
CONFIG_SCHED_WORKPERIOD=5000
|
||||
CONFIG_SCHED_WORKSTACKSIZE=4000
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKPERIOD=50000
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=4000
|
||||
# CONFIG_LIB_KBDCODEC is not set
|
||||
# CONFIG_LIB_SLCDCODEC is not set
|
||||
|
||||
#
|
||||
# Basic CXX Support
|
||||
#
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
# CONFIG_CXX_NEWLONG is not set
|
||||
|
||||
#
|
||||
# uClibc++ Standard C++ Library
|
||||
#
|
||||
# CONFIG_UCLIBCXX is not set
|
||||
|
||||
#
|
||||
# Application Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Built-In Applications
|
||||
#
|
||||
CONFIG_BUILTIN_PROXY_STACKSIZE=1024
|
||||
|
||||
#
|
||||
# Examples
|
||||
#
|
||||
# CONFIG_EXAMPLES_BUTTONS is not set
|
||||
# CONFIG_EXAMPLES_CAN is not set
|
||||
CONFIG_EXAMPLES_CDCACM=y
|
||||
# CONFIG_EXAMPLES_COMPOSITE is not set
|
||||
# CONFIG_EXAMPLES_CXXTEST is not set
|
||||
# CONFIG_EXAMPLES_DHCPD is not set
|
||||
# CONFIG_EXAMPLES_ELF is not set
|
||||
# CONFIG_EXAMPLES_FTPC is not set
|
||||
# CONFIG_EXAMPLES_FTPD is not set
|
||||
# CONFIG_EXAMPLES_HELLO is not set
|
||||
# CONFIG_EXAMPLES_HELLOXX is not set
|
||||
# CONFIG_EXAMPLES_JSON is not set
|
||||
# CONFIG_EXAMPLES_HIDKBD is not set
|
||||
# CONFIG_EXAMPLES_KEYPADTEST is not set
|
||||
# CONFIG_EXAMPLES_IGMP is not set
|
||||
# CONFIG_EXAMPLES_LCDRW is not set
|
||||
# CONFIG_EXAMPLES_MM is not set
|
||||
# CONFIG_EXAMPLES_MODBUS is not set
|
||||
CONFIG_EXAMPLES_MOUNT=y
|
||||
# CONFIG_EXAMPLES_NRF24L01TERM is not set
|
||||
CONFIG_EXAMPLES_NSH=y
|
||||
# CONFIG_EXAMPLES_NULL is not set
|
||||
# CONFIG_EXAMPLES_NX is not set
|
||||
# CONFIG_EXAMPLES_NXCONSOLE is not set
|
||||
# CONFIG_EXAMPLES_NXFFS is not set
|
||||
# CONFIG_EXAMPLES_NXFLAT is not set
|
||||
# CONFIG_EXAMPLES_NXHELLO is not set
|
||||
# CONFIG_EXAMPLES_NXIMAGE is not set
|
||||
# CONFIG_EXAMPLES_NXLINES is not set
|
||||
# CONFIG_EXAMPLES_NXTEXT is not set
|
||||
# CONFIG_EXAMPLES_OSTEST is not set
|
||||
# CONFIG_EXAMPLES_PASHELLO is not set
|
||||
# CONFIG_EXAMPLES_PIPE is not set
|
||||
# CONFIG_EXAMPLES_POSIXSPAWN is not set
|
||||
# CONFIG_EXAMPLES_QENCODER is not set
|
||||
# CONFIG_EXAMPLES_RGMP is not set
|
||||
# CONFIG_EXAMPLES_ROMFS is not set
|
||||
# CONFIG_EXAMPLES_SENDMAIL is not set
|
||||
# CONFIG_EXAMPLES_SERLOOP is not set
|
||||
# CONFIG_EXAMPLES_SLCD is not set
|
||||
# CONFIG_EXAMPLES_SMART_TEST is not set
|
||||
# CONFIG_EXAMPLES_SMART is not set
|
||||
# CONFIG_EXAMPLES_TCPECHO is not set
|
||||
# CONFIG_EXAMPLES_TELNETD is not set
|
||||
# CONFIG_EXAMPLES_THTTPD is not set
|
||||
# CONFIG_EXAMPLES_TIFF is not set
|
||||
# CONFIG_EXAMPLES_TOUCHSCREEN is not set
|
||||
# CONFIG_EXAMPLES_UDP is not set
|
||||
# CONFIG_EXAMPLES_UIP is not set
|
||||
# CONFIG_EXAMPLES_USBSERIAL is not set
|
||||
# CONFIG_EXAMPLES_USBMSC is not set
|
||||
# CONFIG_EXAMPLES_USBTERM is not set
|
||||
# CONFIG_EXAMPLES_WATCHDOG is not set
|
||||
|
||||
#
|
||||
# Graphics Support
|
||||
#
|
||||
# CONFIG_TIFF is not set
|
||||
|
||||
#
|
||||
# Interpreters
|
||||
#
|
||||
# CONFIG_INTERPRETERS_FICL is not set
|
||||
# CONFIG_INTERPRETERS_PCODE is not set
|
||||
|
||||
#
|
||||
# Network Utilities
|
||||
#
|
||||
|
||||
#
|
||||
# Networking Utilities
|
||||
#
|
||||
# CONFIG_NETUTILS_CODECS is not set
|
||||
# CONFIG_NETUTILS_DHCPC is not set
|
||||
# CONFIG_NETUTILS_DHCPD is not set
|
||||
# CONFIG_NETUTILS_FTPC is not set
|
||||
# CONFIG_NETUTILS_FTPD is not set
|
||||
# CONFIG_NETUTILS_JSON is not set
|
||||
# CONFIG_NETUTILS_RESOLV is not set
|
||||
# CONFIG_NETUTILS_SMTP is not set
|
||||
# CONFIG_NETUTILS_TELNETD is not set
|
||||
# CONFIG_NETUTILS_TFTPC is not set
|
||||
# CONFIG_NETUTILS_THTTPD is not set
|
||||
# CONFIG_NETUTILS_UIPLIB is not set
|
||||
# CONFIG_NETUTILS_WEBCLIENT is not set
|
||||
|
||||
#
|
||||
# FreeModBus
|
||||
#
|
||||
# CONFIG_MODBUS is not set
|
||||
|
||||
#
|
||||
# NSH Library
|
||||
#
|
||||
CONFIG_NSH_LIBRARY=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
|
||||
#
|
||||
# Disable Individual commands
|
||||
#
|
||||
# CONFIG_NSH_DISABLE_CAT is not set
|
||||
# CONFIG_NSH_DISABLE_CD is not set
|
||||
# CONFIG_NSH_DISABLE_CP is not set
|
||||
# CONFIG_NSH_DISABLE_DD is not set
|
||||
# CONFIG_NSH_DISABLE_ECHO is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_FREE is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_HELP is not set
|
||||
# CONFIG_NSH_DISABLE_HEXDUMP is not set
|
||||
# CONFIG_NSH_DISABLE_IFCONFIG is not set
|
||||
# CONFIG_NSH_DISABLE_KILL is not set
|
||||
# CONFIG_NSH_DISABLE_LOSETUP is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MB is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MKFIFO is not set
|
||||
# CONFIG_NSH_DISABLE_MKRD is not set
|
||||
# CONFIG_NSH_DISABLE_MH is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MW is not set
|
||||
# CONFIG_NSH_DISABLE_NSFMOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
# CONFIG_NSH_DISABLE_PING is not set
|
||||
# CONFIG_NSH_DISABLE_PUT is not set
|
||||
# CONFIG_NSH_DISABLE_PWD is not set
|
||||
# CONFIG_NSH_DISABLE_RM is not set
|
||||
# CONFIG_NSH_DISABLE_RMDIR is not set
|
||||
# CONFIG_NSH_DISABLE_SET is not set
|
||||
# CONFIG_NSH_DISABLE_SH is not set
|
||||
# CONFIG_NSH_DISABLE_SLEEP is not set
|
||||
# CONFIG_NSH_DISABLE_TEST is not set
|
||||
# CONFIG_NSH_DISABLE_UMOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_UNSET is not set
|
||||
# CONFIG_NSH_DISABLE_USLEEP is not set
|
||||
# CONFIG_NSH_DISABLE_WGET is not set
|
||||
# CONFIG_NSH_DISABLE_XD is not set
|
||||
|
||||
#
|
||||
# Configure Command Options
|
||||
#
|
||||
# CONFIG_NSH_CMDOPT_DF_H is not set
|
||||
CONFIG_NSH_CODECS_BUFSIZE=128
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=12
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
# CONFIG_NSH_ROMFSRC is not set
|
||||
CONFIG_NSH_ROMFSMOUNTPT="/etc"
|
||||
CONFIG_NSH_INITSCRIPT="init.d/rcS"
|
||||
CONFIG_NSH_ROMFSDEVNO=0
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_FATDEVNO=0
|
||||
CONFIG_NSH_FATSECTSIZE=512
|
||||
CONFIG_NSH_FATNSECTORS=1024
|
||||
CONFIG_NSH_FATMOUNTPT="/tmp"
|
||||
CONFIG_NSH_CONSOLE=y
|
||||
# CONFIG_NSH_USBCONSOLE is not set
|
||||
|
||||
#
|
||||
# USB Trace Support
|
||||
#
|
||||
# CONFIG_NSH_CONDEV is not set
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
|
||||
#
|
||||
# NxWidgets/NxWM
|
||||
#
|
||||
|
||||
#
|
||||
# System NSH Add-Ons
|
||||
#
|
||||
|
||||
#
|
||||
# Custom Free Memory Command
|
||||
#
|
||||
# CONFIG_SYSTEM_FREE is not set
|
||||
|
||||
#
|
||||
# I2C tool
|
||||
#
|
||||
# CONFIG_SYSTEM_I2CTOOL is not set
|
||||
|
||||
#
|
||||
# FLASH Program Installation
|
||||
#
|
||||
# CONFIG_SYSTEM_INSTALL is not set
|
||||
|
||||
#
|
||||
# FLASH Erase-all Command
|
||||
#
|
||||
|
||||
#
|
||||
# readline()
|
||||
#
|
||||
CONFIG_SYSTEM_READLINE=y
|
||||
CONFIG_READLINE_ECHO=y
|
||||
|
||||
#
|
||||
# Power Off
|
||||
#
|
||||
# CONFIG_SYSTEM_POWEROFF is not set
|
||||
|
||||
#
|
||||
# RAMTRON
|
||||
#
|
||||
# CONFIG_SYSTEM_RAMTRON is not set
|
||||
|
||||
#
|
||||
# SD Card
|
||||
#
|
||||
# CONFIG_SYSTEM_SDCARD is not set
|
||||
|
||||
#
|
||||
# Sysinfo
|
||||
#
|
||||
CONFIG_SYSTEM_SYSINFO=y
|
||||
|
||||
#
|
||||
# USB Monitor
|
||||
#
|
||||
+67
@@ -0,0 +1,67 @@
|
||||
#!/bin/bash
|
||||
# configs/stm3240g-eval/nsh/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# 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 NuttX 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.
|
||||
#
|
||||
|
||||
if [ "$_" = "$0" ] ; then
|
||||
echo "You must source this script, not run it!" 1>&2
|
||||
exit 1
|
||||
fi
|
||||
|
||||
WD=`pwd`
|
||||
if [ ! -x "setenv.sh" ]; then
|
||||
echo "This script must be executed from the top-level NuttX build directory"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ -z "${PATH_ORIG}" ]; then
|
||||
export PATH_ORIG="${PATH}"
|
||||
fi
|
||||
|
||||
# This the Cygwin path to the location where I installed the RIDE
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the RIDE toolchain in any other location
|
||||
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
|
||||
|
||||
# This the Cygwin path to the location where I installed the CodeSourcery
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the CodeSourcery toolchain in any other location
|
||||
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
|
||||
|
||||
# This the Cygwin path to the location where I build the buildroot
|
||||
# toolchain.
|
||||
#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
|
||||
|
||||
# Add the path to the toolchain to the PATH varialble
|
||||
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
|
||||
|
||||
echo "PATH : ${PATH}"
|
||||
@@ -0,0 +1,149 @@
|
||||
/****************************************************************************
|
||||
* configs/px4fmu-v1/scripts/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 NuttX 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F40VGG has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*
|
||||
* The first 0x4000 of flash is reserved for the bootloader.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
|
||||
EXTERN(_vectors) /* force the vectors to be included in the output */
|
||||
|
||||
/*
|
||||
* Ensure that abort() is present in the final object. The exception handling
|
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
|
||||
*/
|
||||
EXTERN(abort)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
|
||||
/*
|
||||
* This is a hack to make the newlib libm __errno() call
|
||||
* use the NuttX get_errno_ptr() function.
|
||||
*/
|
||||
__errno = get_errno_ptr;
|
||||
} > flash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = ABSOLUTE(.);
|
||||
KEEP(*(__param*))
|
||||
__param_end = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > flash
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > sram AT > flash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > sram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,84 @@
|
||||
############################################################################
|
||||
# configs/px4fmu/src/Makefile
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# 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 NuttX 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
-include $(TOPDIR)/Make.defs
|
||||
|
||||
CFLAGS += -I$(TOPDIR)/sched
|
||||
|
||||
ASRCS =
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
|
||||
CSRCS = empty.c
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
OBJS = $(AOBJS) $(COBJS)
|
||||
|
||||
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
|
||||
ifeq ($(WINTOOL),y)
|
||||
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
|
||||
else
|
||||
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
|
||||
endif
|
||||
|
||||
all: libboard$(LIBEXT)
|
||||
|
||||
$(AOBJS): %$(OBJEXT): %.S
|
||||
$(call ASSEMBLE, $<, $@)
|
||||
|
||||
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
|
||||
$(call COMPILE, $<, $@)
|
||||
|
||||
libboard$(LIBEXT): $(OBJS)
|
||||
$(call ARCHIVE, $@, $(OBJS))
|
||||
|
||||
.depend: Makefile $(SRCS)
|
||||
$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
|
||||
$(Q) touch $@
|
||||
|
||||
depend: .depend
|
||||
|
||||
clean:
|
||||
$(call DELFILE, libboard$(LIBEXT))
|
||||
$(call CLEAN)
|
||||
|
||||
distclean: clean
|
||||
$(call DELFILE, Make.dep)
|
||||
$(call DELFILE, .depend)
|
||||
|
||||
-include Make.dep
|
||||
|
||||
@@ -0,0 +1,4 @@
|
||||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
||||
@@ -209,7 +209,7 @@
|
||||
/* UART DMA configuration for USART1/6 */
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
|
||||
|
||||
|
||||
/*
|
||||
* CAN
|
||||
*
|
||||
|
||||
@@ -405,7 +405,7 @@ CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=42
|
||||
CONFIG_NFILE_DESCRIPTORS=44
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
||||
|
||||
@@ -146,21 +146,21 @@
|
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* Note: TIM1,8 are on APB2, others on APB1
|
||||
*/
|
||||
|
||||
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* SDIO dividers. Note that slower clocking is required when DMA is disabled
|
||||
/* SDIO dividers. Note that slower clocking is required when DMA is disabled
|
||||
* in order to avoid RX overrun/TX underrun errors due to delayed responses
|
||||
* to service FIFOs in interrupt driven mode. These values have not been
|
||||
* tuned!!!
|
||||
*
|
||||
* HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz
|
||||
*/
|
||||
|
||||
|
||||
#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz
|
||||
@@ -168,9 +168,9 @@
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SDIO_DMA
|
||||
# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz
|
||||
@@ -227,10 +227,10 @@
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
|
||||
|
||||
/*
|
||||
/*
|
||||
* CAN
|
||||
*
|
||||
* CAN1 is routed to the onboard transceiver.
|
||||
* CAN1 is routed to the onboard transceiver.
|
||||
* CAN2 is routed to the expansion connector.
|
||||
*/
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3
|
||||
|
||||
@@ -439,7 +439,7 @@ CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=42
|
||||
CONFIG_NFILE_DESCRIPTORS=44
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
|
||||
@@ -66,12 +66,20 @@ EXTERN(_vectors) /* force the vectors to be included in the output */
|
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
|
||||
*/
|
||||
EXTERN(abort)
|
||||
EXTERN(_bootdelay_signature)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
||||
|
||||
@@ -143,7 +143,7 @@ extern "C" {
|
||||
************************************************************************************/
|
||||
|
||||
EXTERN void stm32_boardinitialize(void);
|
||||
|
||||
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
||||
|
||||
@@ -138,7 +138,7 @@ extern "C" {
|
||||
************************************************************************************/
|
||||
|
||||
EXTERN void stm32_boardinitialize(void);
|
||||
|
||||
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
||||
|
||||
@@ -90,7 +90,7 @@ static const int ERROR = -1;
|
||||
class __EXPORT Airspeed : public device::I2C
|
||||
{
|
||||
public:
|
||||
Airspeed(int bus, int address, unsigned conversion_interval, const char* path);
|
||||
Airspeed(int bus, int address, unsigned conversion_interval, const char *path);
|
||||
virtual ~Airspeed();
|
||||
|
||||
virtual int init();
|
||||
@@ -108,8 +108,8 @@ private:
|
||||
perf_counter_t _buffer_overflows;
|
||||
|
||||
/* this class has pointer data members and should not be copied */
|
||||
Airspeed(const Airspeed&);
|
||||
Airspeed& operator=(const Airspeed&);
|
||||
Airspeed(const Airspeed &);
|
||||
Airspeed &operator=(const Airspeed &);
|
||||
|
||||
protected:
|
||||
virtual int probe();
|
||||
|
||||
@@ -108,8 +108,9 @@ usage(const char *reason)
|
||||
*/
|
||||
int ardrone_interface_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
if (argc < 2) {
|
||||
usage("missing command");
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
|
||||
@@ -85,7 +85,8 @@ int ar_init_motors(int ardrone_uart, int gpio);
|
||||
/**
|
||||
* Set LED pattern.
|
||||
*/
|
||||
void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green, uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
|
||||
void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green,
|
||||
uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
|
||||
|
||||
/**
|
||||
* Mix motors and output actuators
|
||||
|
||||
@@ -84,6 +84,8 @@
|
||||
#define BATT_SMBUS_ADDR 0x0B ///< I2C address
|
||||
#define BATT_SMBUS_TEMP 0x08 ///< temperature register
|
||||
#define BATT_SMBUS_VOLTAGE 0x09 ///< voltage register
|
||||
#define BATT_SMBUS_REMAINING_CAPACITY 0x0f ///< predicted remaining battery capacity as a percentage
|
||||
#define BATT_SMBUS_FULL_CHARGE_CAPACITY 0x10 ///< capacity when fully charged
|
||||
#define BATT_SMBUS_DESIGN_CAPACITY 0x18 ///< design capacity register
|
||||
#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 ///< design voltage register
|
||||
#define BATT_SMBUS_SERIALNUM 0x1c ///< serial number register
|
||||
@@ -114,6 +116,11 @@ public:
|
||||
*/
|
||||
virtual int init();
|
||||
|
||||
/**
|
||||
* ioctl for retrieving battery capacity and time to empty
|
||||
*/
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Test device
|
||||
*
|
||||
@@ -179,6 +186,7 @@ private:
|
||||
orb_advert_t _batt_topic; ///< uORB battery topic
|
||||
orb_id_t _batt_orb_id; ///< uORB battery topic ID
|
||||
uint64_t _start_time; ///< system time we first attempt to communicate with battery
|
||||
uint16_t _batt_capacity; ///< battery's design capacity in mAh (0 means unknown)
|
||||
};
|
||||
|
||||
namespace
|
||||
@@ -197,7 +205,8 @@ BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) :
|
||||
_reports(nullptr),
|
||||
_batt_topic(-1),
|
||||
_batt_orb_id(nullptr),
|
||||
_start_time(0)
|
||||
_start_time(0),
|
||||
_batt_capacity(0)
|
||||
{
|
||||
// work_cancel in the dtor will explode if we don't do this...
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
@@ -247,6 +256,31 @@ BATT_SMBUS::init()
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
BATT_SMBUS::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = -ENODEV;
|
||||
|
||||
switch (cmd) {
|
||||
case BATT_SMBUS_GET_CAPACITY:
|
||||
|
||||
/* return battery capacity as uint16 */
|
||||
if (_enabled) {
|
||||
*((uint16_t *)arg) = _batt_capacity;
|
||||
ret = OK;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
/* see if the parent class can make any use of it */
|
||||
ret = CDev::ioctl(filp, cmd, arg);
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
BATT_SMBUS::test()
|
||||
{
|
||||
@@ -263,7 +297,8 @@ BATT_SMBUS::test()
|
||||
|
||||
if (updated) {
|
||||
if (orb_copy(ORB_ID(battery_status), sub, &status) == OK) {
|
||||
warnx("V=%4.2f C=%4.2f", status.voltage_v, status.current_a);
|
||||
warnx("V=%4.2f C=%4.2f DismAh=%4.2f Cap:%d", (float)status.voltage_v, (float)status.current_a,
|
||||
(float)status.discharged_mah, (int)_batt_capacity);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -279,6 +314,7 @@ BATT_SMBUS::search()
|
||||
{
|
||||
bool found_slave = false;
|
||||
uint16_t tmp;
|
||||
int16_t orig_addr = get_address();
|
||||
|
||||
// search through all valid SMBus addresses
|
||||
for (uint8_t i = BATT_SMBUS_ADDR_MIN; i <= BATT_SMBUS_ADDR_MAX; i++) {
|
||||
@@ -293,6 +329,9 @@ BATT_SMBUS::search()
|
||||
usleep(1);
|
||||
}
|
||||
|
||||
// restore original i2c address
|
||||
set_address(orig_addr);
|
||||
|
||||
// display completion message
|
||||
if (found_slave) {
|
||||
warnx("Done.");
|
||||
@@ -364,11 +403,27 @@ BATT_SMBUS::cycle()
|
||||
new_report.voltage_v = ((float)tmp) / 1000.0f;
|
||||
|
||||
// read current
|
||||
usleep(1);
|
||||
uint8_t buff[4];
|
||||
|
||||
if (read_block(BATT_SMBUS_CURRENT, buff, 4, false) == 4) {
|
||||
new_report.current_a = -(float)((int32_t)((uint32_t)buff[3] << 24 | (uint32_t)buff[2] << 16 | (uint32_t)buff[1] << 8 | (uint32_t)buff[0])) / 1000.0f;
|
||||
new_report.current_a = -(float)((int32_t)((uint32_t)buff[3] << 24 | (uint32_t)buff[2] << 16 | (uint32_t)buff[1] << 8 |
|
||||
(uint32_t)buff[0])) / 1000.0f;
|
||||
}
|
||||
|
||||
// read battery design capacity
|
||||
if (_batt_capacity == 0) {
|
||||
if (read_reg(BATT_SMBUS_FULL_CHARGE_CAPACITY, tmp) == OK) {
|
||||
_batt_capacity = tmp;
|
||||
}
|
||||
}
|
||||
|
||||
// read remaining capacity
|
||||
if (_batt_capacity > 0) {
|
||||
if (read_reg(BATT_SMBUS_REMAINING_CAPACITY, tmp) == OK) {
|
||||
if (tmp < _batt_capacity) {
|
||||
new_report.discharged_mah = _batt_capacity - tmp;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// publish to orb
|
||||
@@ -430,8 +485,6 @@ BATT_SMBUS::read_block(uint8_t reg, uint8_t *data, uint8_t max_len, bool append_
|
||||
{
|
||||
uint8_t buff[max_len + 2]; // buffer to hold results
|
||||
|
||||
usleep(1);
|
||||
|
||||
// read bytes including PEC
|
||||
int ret = transfer(®, 1, buff, max_len + 2);
|
||||
|
||||
|
||||
@@ -136,8 +136,8 @@ __EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
|
||||
|
||||
switch (devid) {
|
||||
case PX4_SPIDEV_GYRO:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
break;
|
||||
|
||||
@@ -54,7 +54,7 @@ __BEGIN_DECLS
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#define UDID_START 0x1FFF7A10
|
||||
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
@@ -0,0 +1,136 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 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 board_config.h
|
||||
*
|
||||
* PX4-STM32F4Discovery internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/* these headers are not C++ safe */
|
||||
#include <stm32.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#define UDID_START 0x1FFF7A10
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
/* Configuration ************************************************************************************/
|
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
/* LEDs */
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_LED4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
|
||||
|
||||
/* SPI chip selects */
|
||||
#define GPIO_SPI_CS_MEMS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
|
||||
/* USB OTG FS
|
||||
*
|
||||
* PA9 OTG_FS_VBUS VBUS sensing
|
||||
*/
|
||||
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization for NSH.
|
||||
*
|
||||
* CONFIG_NSH_ARCHINIT=y :
|
||||
* Called from the NSH library
|
||||
*
|
||||
* CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
|
||||
* CONFIG_NSH_ARCHINIT=n :
|
||||
* Called from board_initialize().
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_NSH_LIBRARY
|
||||
int nsh_archinitialize(void);
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,7 @@
|
||||
#
|
||||
# Board-specific startup code for the PX4-STM32F4Discovery
|
||||
#
|
||||
|
||||
SRCS = px4discovery_init.c \
|
||||
px4discovery_usb.c \
|
||||
px4discovery_led.c
|
||||
@@ -0,0 +1,173 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 px4discovery_init.c
|
||||
*
|
||||
* PX4-stm32f4discovery specific early startup code. This file implements the
|
||||
* nsh_archinitialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialisation.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/spi.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/gran.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_led.h>
|
||||
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) lowsyslog(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message lowsyslog
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the intitialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure LEDs */
|
||||
up_ledinit();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
__EXPORT int matherr(struct __exception *e)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
#else
|
||||
__EXPORT int matherr(struct exception *e)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
__EXPORT int nsh_archinitialize(void)
|
||||
{
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
/* configure CPU load estimation */
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
cpuload_initialize_once();
|
||||
#endif
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)stm32_serial_dma_poll,
|
||||
NULL);
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,97 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 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 px4discovery_led.c
|
||||
*
|
||||
* PX4-stm32f4discovery LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
__EXPORT void led_init()
|
||||
{
|
||||
/* Configure LED1 GPIO for output */
|
||||
|
||||
stm32_configgpio(GPIO_LED1);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
if (led == 1)
|
||||
{
|
||||
/* Pull down to switch on */
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
if (led == 1)
|
||||
{
|
||||
/* Pull up to switch off */
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
if (led == 1)
|
||||
{
|
||||
if (stm32_gpioread(GPIO_LED1))
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
else
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,108 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 px4discovery_usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the PX4-STM32F4Discovery board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_STM32_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
/* XXX We only support device mode
|
||||
stm32_configgpio(GPIO_OTGFS_PWRON);
|
||||
stm32_configgpio(GPIO_OTGFS_OVER);
|
||||
*/
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
ulldbg("resume: %d\n", resume);
|
||||
}
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user