mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-22 11:37:35 +08:00
Merge branch 'master' into mavlink-ftp
This commit is contained in:
@@ -38,3 +38,4 @@ tags
|
||||
.tags_sorted_by_file
|
||||
.pydevproject
|
||||
.ropeproject
|
||||
*.orig
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -0,0 +1,12 @@
|
||||
{
|
||||
"board_id": 19,
|
||||
"magic": "AeroCore",
|
||||
"description": "Firmware for the Gumstix AeroCore board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "AEROCORE",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -18,9 +18,9 @@ then
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.004
|
||||
param set MC_YAW_P 0.5
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAW_P 2.5
|
||||
param set MC_YAWRATE_P 0.25
|
||||
param set MC_YAWRATE_I 0.25
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set BAT_V_SCALING 0.00989
|
||||
|
||||
@@ -0,0 +1,35 @@
|
||||
#!nsh
|
||||
#
|
||||
# Steadidrone QU4D
|
||||
#
|
||||
# Thomas Gubler <thomasgubler@gmail.com>
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO tune roll/pitch separately
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.13
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.004
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.004
|
||||
param set MC_YAW_P 0.5
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set BAT_N_CELLS 4
|
||||
fi
|
||||
|
||||
set MIXER FMU_quad_w
|
||||
|
||||
set PWM_MIN 1210
|
||||
set PWM_MAX 2100
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
@@ -1,7 +1,5 @@
|
||||
#!nsh
|
||||
#
|
||||
# UNTESTED UNTESTED!
|
||||
#
|
||||
# Generic 10" Hexa coaxial geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
||||
@@ -5,4 +5,4 @@
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER easystar.mix
|
||||
set MIXER easystar
|
||||
|
||||
@@ -14,19 +14,20 @@ sh /etc/init.d/rc.mc_defaults
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set MC_ROLL_P 5.0
|
||||
param set MC_ROLLRATE_P 0.13
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.0
|
||||
param set MC_PITCH_P 5.0
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.0
|
||||
param set MC_YAW_P 1.0
|
||||
param set MC_YAWRATE_P 0.15
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_ROLL_P 6.0
|
||||
param set MC_ROLLRATE_P 0.14
|
||||
param set MC_ROLLRATE_I 0.1
|
||||
param set MC_ROLLRATE_D 0.002
|
||||
param set MC_PITCH_P 6.0
|
||||
param set MC_PITCHRATE_P 0.14
|
||||
param set MC_PITCHRATE_I 0.1
|
||||
param set MC_PITCHRATE_D 0.002
|
||||
param set MC_YAW_P 2.0
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.15
|
||||
param set MC_YAW_FF 0.8
|
||||
|
||||
param set BAT_V_SCALING 0.00838095238
|
||||
fi
|
||||
|
||||
|
||||
@@ -195,6 +195,11 @@ then
|
||||
sh /etc/init.d/10016_3dr_iris
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10017
|
||||
then
|
||||
sh /etc/init.d/10017_steadidrone_qu4d
|
||||
fi
|
||||
|
||||
#
|
||||
# Hexa Coaxial
|
||||
#
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
fw_att_pos_estimator start
|
||||
ekf_att_pos_estimator start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
|
||||
@@ -11,6 +11,4 @@ then
|
||||
param set NAV_RTL_ALT 100
|
||||
param set NAV_RTL_LAND_T -1
|
||||
param set NAV_ACCEPT_RAD 50
|
||||
param set RC_SCALE_ROLL 1
|
||||
param set RC_SCALE_PITCH 1
|
||||
fi
|
||||
@@ -8,9 +8,9 @@ then
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
echo "Start sdlog2 at 50Hz"
|
||||
sdlog2 start -r 50 -a -b 8 -t
|
||||
sdlog2 start -r 50 -a -b 4 -t
|
||||
else
|
||||
echo "Start sdlog2 at 200Hz"
|
||||
sdlog2 start -r 200 -a -b 16 -t
|
||||
sdlog2 start -r 200 -a -b 22 -t
|
||||
fi
|
||||
fi
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
#
|
||||
|
||||
attitude_estimator_ekf start
|
||||
#ekf_att_pos_estimator start
|
||||
position_estimator_inav start
|
||||
|
||||
mc_att_control start
|
||||
|
||||
@@ -35,6 +35,13 @@ then
|
||||
param set MPC_TILTMAX_AIR 45.0
|
||||
param set MPC_TILTMAX_LND 15.0
|
||||
param set MPC_LAND_SPEED 1.0
|
||||
|
||||
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 NAV_ACCEPT_RAD 2.0
|
||||
fi
|
||||
|
||||
set PWM_RATE 400
|
||||
|
||||
@@ -3,16 +3,20 @@
|
||||
# USB MAVLink start
|
||||
#
|
||||
|
||||
echo "Starting MAVLink on this USB console"
|
||||
|
||||
mavlink start -r 10000 -d /dev/ttyACM0
|
||||
# Enable a number of interesting streams we want via USB
|
||||
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
|
||||
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 10
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
|
||||
usleep 100000
|
||||
|
||||
# Exit shell to make it available to MAVLink
|
||||
exit
|
||||
|
||||
@@ -65,12 +65,12 @@ then
|
||||
# Start CDC/ACM serial driver
|
||||
#
|
||||
sercon
|
||||
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
#
|
||||
uorb start
|
||||
|
||||
|
||||
#
|
||||
# Load parameters
|
||||
#
|
||||
@@ -79,7 +79,7 @@ then
|
||||
then
|
||||
set PARAM_FILE /fs/mtd_params
|
||||
fi
|
||||
|
||||
|
||||
param select $PARAM_FILE
|
||||
if param load
|
||||
then
|
||||
@@ -87,21 +87,25 @@ then
|
||||
else
|
||||
echo "[init] ERROR: Params loading failed: $PARAM_FILE"
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Start system state indicator
|
||||
#
|
||||
if rgbled start
|
||||
then
|
||||
echo "[init] Using external RGB Led"
|
||||
echo "[init] RGB Led"
|
||||
else
|
||||
if blinkm start
|
||||
then
|
||||
echo "[init] Using blinkm"
|
||||
echo "[init] BlinkM"
|
||||
blinkm systemstate
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
if pca8574 start
|
||||
then
|
||||
fi
|
||||
|
||||
#
|
||||
# Set default values
|
||||
#
|
||||
@@ -122,7 +126,7 @@ then
|
||||
set LOAD_DEFAULT_APPS yes
|
||||
set GPS yes
|
||||
set GPS_FAKE no
|
||||
|
||||
|
||||
#
|
||||
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
|
||||
#
|
||||
@@ -132,7 +136,7 @@ then
|
||||
else
|
||||
set DO_AUTOCONFIG no
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Set USE_IO flag
|
||||
#
|
||||
@@ -142,7 +146,7 @@ then
|
||||
else
|
||||
set USE_IO no
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Set parameters and env variables for selected AUTOSTART
|
||||
#
|
||||
@@ -172,9 +176,9 @@ then
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
|
||||
set IO_PRESENT no
|
||||
|
||||
|
||||
if [ $USE_IO == yes ]
|
||||
then
|
||||
#
|
||||
@@ -186,19 +190,19 @@ then
|
||||
else
|
||||
set IO_FILE /etc/extras/px4io-v1_default.bin
|
||||
fi
|
||||
|
||||
|
||||
if px4io checkcrc $IO_FILE
|
||||
then
|
||||
echo "[init] PX4IO CRC OK"
|
||||
echo "PX4IO CRC OK" >> $LOG_FILE
|
||||
|
||||
|
||||
set IO_PRESENT yes
|
||||
else
|
||||
echo "[init] Trying to update"
|
||||
echo "PX4IO Trying to update" >> $LOG_FILE
|
||||
|
||||
|
||||
tone_alarm MLL32CP8MB
|
||||
|
||||
|
||||
if px4io forceupdate 14662 $IO_FILE
|
||||
then
|
||||
usleep 500000
|
||||
@@ -207,7 +211,7 @@ then
|
||||
echo "[init] PX4IO CRC OK, update successful"
|
||||
echo "PX4IO CRC OK after updating" >> $LOG_FILE
|
||||
tone_alarm MLL8CDE
|
||||
|
||||
|
||||
set IO_PRESENT yes
|
||||
else
|
||||
echo "[init] ERROR: PX4IO update failed"
|
||||
@@ -220,14 +224,14 @@ then
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
if [ $IO_PRESENT == no ]
|
||||
then
|
||||
echo "[init] ERROR: PX4IO not found"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Set default output if not set
|
||||
#
|
||||
@@ -246,7 +250,7 @@ then
|
||||
# Need IO for output but it not present, disable output
|
||||
set OUTPUT_MODE none
|
||||
echo "[init] ERROR: PX4IO not found, disabling output"
|
||||
|
||||
|
||||
# Avoid using ttyS0 for MAVLink on FMUv1
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
@@ -270,17 +274,17 @@ then
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
|
||||
|
||||
#
|
||||
# Start the Commander (needs to be this early for in-air-restarts)
|
||||
#
|
||||
commander start
|
||||
|
||||
|
||||
#
|
||||
# Start primary output
|
||||
#
|
||||
set TTYS1_BUSY no
|
||||
|
||||
|
||||
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
|
||||
if [ $OUTPUT_MODE != none ]
|
||||
then
|
||||
@@ -296,7 +300,7 @@ then
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
echo "[init] Use FMU as primary output"
|
||||
@@ -307,7 +311,7 @@ then
|
||||
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
|
||||
@@ -320,7 +324,7 @@ then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
if [ $OUTPUT_MODE == mkblctrl ]
|
||||
then
|
||||
echo "[init] Use MKBLCTRL as primary output"
|
||||
@@ -333,7 +337,7 @@ then
|
||||
then
|
||||
set MKBLCTRL_ARG "-mkmode +"
|
||||
fi
|
||||
|
||||
|
||||
if mkblctrl $MKBLCTRL_ARG
|
||||
then
|
||||
echo "[init] MKBLCTRL started"
|
||||
@@ -341,9 +345,9 @@ then
|
||||
echo "[init] ERROR: MKBLCTRL start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
|
||||
|
||||
fi
|
||||
|
||||
|
||||
if [ $OUTPUT_MODE == hil ]
|
||||
then
|
||||
echo "[init] Use HIL as primary output"
|
||||
@@ -355,7 +359,7 @@ then
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Start IO or FMU for RC PPM input if needed
|
||||
#
|
||||
@@ -382,7 +386,7 @@ then
|
||||
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
|
||||
@@ -397,7 +401,7 @@ then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# MAVLink
|
||||
#
|
||||
@@ -418,17 +422,7 @@ then
|
||||
fi
|
||||
|
||||
mavlink start $MAVLINK_FLAGS
|
||||
|
||||
#
|
||||
# Start the datamanager
|
||||
#
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the navigator
|
||||
#
|
||||
navigator start
|
||||
|
||||
|
||||
#
|
||||
# Sensors, Logging, GPS
|
||||
#
|
||||
@@ -439,7 +433,7 @@ then
|
||||
echo "[init] Start logging"
|
||||
sh /etc/init.d/rc.logging
|
||||
fi
|
||||
|
||||
|
||||
if [ $GPS == yes ]
|
||||
then
|
||||
echo "[init] Start GPS"
|
||||
@@ -449,7 +443,7 @@ then
|
||||
gps start -f
|
||||
else
|
||||
gps start
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
@@ -466,24 +460,24 @@ then
|
||||
if [ $VEHICLE_TYPE == fw ]
|
||||
then
|
||||
echo "[init] Vehicle type: FIXED WING"
|
||||
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
# Set default mixer for fixed wing if not defined
|
||||
set MIXER FMU_AERT
|
||||
fi
|
||||
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
# Use MAV_TYPE = 1 (fixed wing) if not defined
|
||||
set MAV_TYPE 1
|
||||
fi
|
||||
|
||||
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
|
||||
# Start standard fixedwing apps
|
||||
if [ $LOAD_DEFAULT_APPS == yes ]
|
||||
then
|
||||
@@ -531,7 +525,7 @@ then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
@@ -539,10 +533,10 @@ then
|
||||
else
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
fi
|
||||
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
|
||||
# Start standard multicopter apps
|
||||
if [ $LOAD_DEFAULT_APPS == yes ]
|
||||
then
|
||||
@@ -550,6 +544,16 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the datamanager
|
||||
#
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the navigator
|
||||
#
|
||||
navigator start
|
||||
|
||||
#
|
||||
# Generic setup (autostart ID not found)
|
||||
#
|
||||
|
||||
@@ -0,0 +1,154 @@
|
||||
PX4 mixer definitions
|
||||
=====================
|
||||
|
||||
Files in this directory implement example mixers that can be used as a basis
|
||||
for customisation, or for general testing purposes.
|
||||
|
||||
Mixer basics
|
||||
------------
|
||||
|
||||
Mixers combine control values from various sources (control tasks, user inputs,
|
||||
etc.) and produce output values suitable for controlling actuators; servos,
|
||||
motors, switches and so on.
|
||||
|
||||
An actuator derives its value from the combination of one or more control
|
||||
values. Each of the control values is scaled according to the actuator's
|
||||
configuration and then combined to produce the actuator value, which may then be
|
||||
further scaled to suit the specific output type.
|
||||
|
||||
Internally, all scaling is performed using floating point values. Inputs and
|
||||
outputs are clamped to the range -1.0 to 1.0.
|
||||
|
||||
control control control
|
||||
| | |
|
||||
v v v
|
||||
scale scale scale
|
||||
| | |
|
||||
| v |
|
||||
+-------> mix <------+
|
||||
|
|
||||
scale
|
||||
|
|
||||
v
|
||||
out
|
||||
|
||||
Scaling
|
||||
-------
|
||||
|
||||
Basic scalers provide linear scaling of the input to the output.
|
||||
|
||||
Each scaler allows the input value to be scaled independently for inputs
|
||||
greater/less than zero. An offset can be applied to the output, and lower and
|
||||
upper boundary constraints can be applied. Negative scaling factors cause the
|
||||
output to be inverted (negative input produces positive output).
|
||||
|
||||
Scaler pseudocode:
|
||||
|
||||
if (input < 0)
|
||||
output = (input * NEGATIVE_SCALE) + OFFSET
|
||||
else
|
||||
output = (input * POSITIVE_SCALE) + OFFSET
|
||||
|
||||
if (output < LOWER_LIMIT)
|
||||
output = LOWER_LIMIT
|
||||
if (output > UPPER_LIMIT)
|
||||
output = UPPER_LIMIT
|
||||
|
||||
Syntax
|
||||
------
|
||||
|
||||
Mixer definitions are text files; lines beginning with a single capital letter
|
||||
followed by a colon are significant. All other lines are ignored, meaning that
|
||||
explanatory text can be freely mixed with the definitions.
|
||||
|
||||
Each file may define more than one mixer; the allocation of mixers to actuators
|
||||
is specific to the device reading the mixer definition, and the number of
|
||||
actuator outputs generated by a mixer is specific to the mixer.
|
||||
|
||||
A mixer begins with a line of the form
|
||||
|
||||
<tag>: <mixer arguments>
|
||||
|
||||
The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
|
||||
multirotor mixer, etc.
|
||||
|
||||
Null Mixer
|
||||
..........
|
||||
|
||||
A null mixer consumes no controls and generates a single actuator output whose
|
||||
value is always zero. Typically a null mixer is used as a placeholder in a
|
||||
collection of mixers in order to achieve a specific pattern of actuator outputs.
|
||||
|
||||
The null mixer definition has the form:
|
||||
|
||||
Z:
|
||||
|
||||
Simple Mixer
|
||||
............
|
||||
|
||||
A simple mixer combines zero or more control inputs into a single actuator
|
||||
output. Inputs are scaled, and the mixing function sums the result before
|
||||
applying an output scaler.
|
||||
|
||||
A simple mixer definition begins with:
|
||||
|
||||
M: <control count>
|
||||
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
|
||||
|
||||
If <control count> is zero, the sum is effectively zero and the mixer will
|
||||
output a fixed value that is <offset> constrained by <lower limit> and <upper
|
||||
limit>.
|
||||
|
||||
The second line defines the output scaler with scaler parameters as discussed
|
||||
above. Whilst the calculations are performed as floating-point operations, the
|
||||
values stored in the definition file are scaled by a factor of 10000; i.e. an
|
||||
offset of -0.5 is encoded as -5000.
|
||||
|
||||
The definition continues with <control count> entries describing the control
|
||||
inputs and their scaling, in the form:
|
||||
|
||||
S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
|
||||
|
||||
The <group> value identifies the control group from which the scaler will read,
|
||||
and the <index> value an offset within that group. These values are specific to
|
||||
the device reading the mixer definition.
|
||||
|
||||
When used to mix vehicle controls, mixer group zero is the vehicle attitude
|
||||
control group, and index values zero through three are normally roll, pitch,
|
||||
yaw and thrust respectively.
|
||||
|
||||
The remaining fields on the line configure the control scaler with parameters as
|
||||
discussed above. Whilst the calculations are performed as floating-point
|
||||
operations, the values stored in the definition file are scaled by a factor of
|
||||
10000; i.e. an offset of -0.5 is encoded as -5000.
|
||||
|
||||
Multirotor Mixer
|
||||
................
|
||||
|
||||
The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
|
||||
into a set of actuator outputs intended to drive motor speed controllers.
|
||||
|
||||
The mixer definition is a single line of the form:
|
||||
|
||||
R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
|
||||
|
||||
The supported geometries include:
|
||||
|
||||
4x - quadrotor in X configuration
|
||||
4+ - quadrotor in + configuration
|
||||
6x - hexcopter in X configuration
|
||||
6+ - hexcopter in + configuration
|
||||
8x - octocopter in X configuration
|
||||
8+ - octocopter in + configuration
|
||||
|
||||
Each of the roll, pitch and yaw scale values determine scaling of the roll,
|
||||
pitch and yaw controls relative to the thrust control. Whilst the calculations
|
||||
are performed as floating-point operations, the values stored in the definition
|
||||
file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
|
||||
|
||||
Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
|
||||
thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
|
||||
range -1.0 to 1.0.
|
||||
|
||||
In the case where an actuator saturates, all actuator values are rescaled so that
|
||||
the saturating actuator is limited to 1.0.
|
||||
@@ -16,5 +16,6 @@ astyle \
|
||||
--ignore-exclude-errors-x \
|
||||
--lineend=linux \
|
||||
--exclude=EASTL \
|
||||
--add-brackets \
|
||||
--add-brackets \
|
||||
--max-code-length=120 \
|
||||
$*
|
||||
|
||||
@@ -0,0 +1,11 @@
|
||||
#
|
||||
# Board-specific definitions for the Gumstix AeroCore
|
||||
#
|
||||
|
||||
#
|
||||
# Configure the toolchain
|
||||
#
|
||||
CONFIG_ARCH = CORTEXM4F
|
||||
CONFIG_BOARD = AEROCORE
|
||||
|
||||
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
|
||||
@@ -0,0 +1,125 @@
|
||||
#
|
||||
# Makefile for the AeroCore *default* configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS.
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/stm32/adc
|
||||
MODULES += drivers/stm32/tone_alarm
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/px4fmu
|
||||
MODULES += drivers/boards/aerocore
|
||||
MODULES += drivers/lsm303d
|
||||
MODULES += drivers/l3gd20
|
||||
MODULES += drivers/ms5611
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += modules/sensors
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/preflight_check
|
||||
MODULES += systemcmds/pwm
|
||||
MODULES += systemcmds/esc_calib
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/top
|
||||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
MODULES += systemcmds/mtd
|
||||
MODULES += systemcmds/dumpfile
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
MODULES += modules/commander
|
||||
MODULES += modules/navigator
|
||||
MODULES += modules/mavlink
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/attitude_estimator_so3
|
||||
MODULES += modules/ekf_att_pos_estimator
|
||||
MODULES += modules/position_estimator_inav
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
MODULES += modules/fw_pos_control_l1
|
||||
MODULES += modules/fw_att_control
|
||||
MODULES += modules/mc_att_control
|
||||
MODULES += modules/mc_pos_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/controllib
|
||||
MODULES += modules/uORB
|
||||
MODULES += modules/dataman
|
||||
|
||||
#
|
||||
# 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 += lib/launchdetection
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, hello, , 2048, hello_main) \
|
||||
$(call _B, i2c, , 2048, i2c_main)
|
||||
@@ -70,7 +70,7 @@ MODULES += modules/gpio_led
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/fw_att_pos_estimator
|
||||
MODULES += modules/ekf_att_pos_estimator
|
||||
MODULES += modules/position_estimator_inav
|
||||
#MODULES += examples/flow_position_estimator
|
||||
|
||||
|
||||
@@ -40,6 +40,7 @@ MODULES += drivers/meas_airspeed
|
||||
MODULES += drivers/frsky_telemetry
|
||||
MODULES += modules/sensors
|
||||
MODULES += drivers/mkblctrl
|
||||
MODULES += drivers/pca8574
|
||||
|
||||
|
||||
# Needs to be burned to the ground and re-written; for now,
|
||||
@@ -79,7 +80,7 @@ MODULES += modules/gpio_led
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/attitude_estimator_so3
|
||||
MODULES += modules/fw_att_pos_estimator
|
||||
MODULES += modules/ekf_att_pos_estimator
|
||||
MODULES += modules/position_estimator_inav
|
||||
MODULES += examples/flow_position_estimator
|
||||
|
||||
|
||||
@@ -24,6 +24,7 @@ MODULES += drivers/lsm303d
|
||||
MODULES += drivers/l3gd20
|
||||
MODULES += drivers/hmc5883
|
||||
MODULES += drivers/ms5611
|
||||
MODULES += drivers/pca8574
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/tests
|
||||
|
||||
@@ -48,6 +48,16 @@ NM = $(CROSSDEV)nm
|
||||
OBJCOPY = $(CROSSDEV)objcopy
|
||||
OBJDUMP = $(CROSSDEV)objdump
|
||||
|
||||
# Check if the right version of the toolchain is available
|
||||
#
|
||||
CROSSDEV_VER_SUPPORTED = 4.7
|
||||
CROSSDEV_VER_FOUND = $(shell $(CC) -dumpversion)
|
||||
|
||||
ifeq (,$(findstring $(CROSSDEV_VER_SUPPORTED),$(CROSSDEV_VER_FOUND)))
|
||||
$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of $(CROSSDEV_VER_SUPPORTED).x)
|
||||
endif
|
||||
|
||||
|
||||
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
|
||||
|
||||
MAXOPTIMIZATION ?= -O3
|
||||
@@ -76,7 +86,7 @@ ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions \
|
||||
ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions \
|
||||
-ffixed-r10
|
||||
|
||||
ARCHINSTRUMENTATIONDEFINES_CORTEXM3 =
|
||||
ARCHINSTRUMENTATIONDEFINES_CORTEXM3 =
|
||||
|
||||
# Pick the right set of flags for the architecture.
|
||||
#
|
||||
@@ -265,7 +275,7 @@ define SYM_TO_BIN
|
||||
$(Q) $(OBJCOPY) -O binary $1 $2
|
||||
endef
|
||||
|
||||
# Take the raw binary $1 and make it into an object file $2.
|
||||
# Take the raw binary $1 and make it into an object file $2.
|
||||
# The symbol $3 points to the beginning of the file, and $3_len
|
||||
# gives its length.
|
||||
#
|
||||
|
||||
@@ -0,0 +1,263 @@
|
||||
/************************************************************************************
|
||||
* configs/aerocore/include/board.h
|
||||
* include/arch/board/board.h
|
||||
*
|
||||
* Copyright (C) 2009 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 __ARCH_BOARD_BOARD_H
|
||||
#define __ARCH_BOARD_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include <stm32.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The AeroCore uses a 24MHz crystal connected to the HSE.
|
||||
*
|
||||
* This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
|
||||
* 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) : 24000000 (STM32_BOARD_XTAL)
|
||||
* PLLM : 24 (STM32_PLLCFG_PLLM)
|
||||
* PLLN : 336 (STM32_PLLCFG_PLLN)
|
||||
* PLLP : 2 (STM32_PLLCFG_PLLP)
|
||||
* PLLQ : 7 (STM32_PLLCFG_PPQ)
|
||||
* 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 24MHz
|
||||
* LSE - not installed
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 24000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE
|
||||
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
* = (24,000,000 / 24) * 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(24)
|
||||
#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)
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/*
|
||||
* UARTs.
|
||||
*/
|
||||
/* USART1 on PB[6,7]: GPS */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2
|
||||
|
||||
/* USART2 on PD[5,6]: J5 Breakout */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2
|
||||
#define GPIO_USART2_CTS 0 // unused
|
||||
#define GPIO_USART2_RTS 0 // unused
|
||||
|
||||
/* USART3 on PD[8,9]: to DuoVero UART2 */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3
|
||||
#define GPIO_USART3_CTS 0 // unused
|
||||
#define GPIO_USART3_RTS 0 // unused
|
||||
|
||||
/* UART7 on PE[78]: J7 Breakout */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1
|
||||
|
||||
/*
|
||||
* UART8 on PE[0-1]: System Console on Port C of USB (J7)
|
||||
* No alternate pin config
|
||||
*/
|
||||
|
||||
/* USART[1,6] require a RX DMA configuration */
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
|
||||
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/* PB[10-11]: I2C2 is broken out on J9 header */
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
|
||||
|
||||
/*
|
||||
* SPI
|
||||
*/
|
||||
/* 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)
|
||||
#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
|
||||
|
||||
/* PB[12-15]: SPI2 connected to DuoVero SPI1 */
|
||||
#define GPIO_SPI2_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) /* should be GPIO_SPI2_NSS_2 but use as a GPIO */
|
||||
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
|
||||
|
||||
/* PC[10-12]: SPI3 connected to onboard sensors */
|
||||
#define GPIO_SPI3_SCK (GPIO_SPI3_SCK_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI3_MISO (GPIO_SPI3_MISO_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI3_MOSI (GPIO_SPI3_MOSI_2|GPIO_SPEED_50MHz)
|
||||
|
||||
/* PE[11-14]: SPI4 connected to FRAM */
|
||||
#define GPIO_SPI4_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN11) /* should be GPIO_SPI4_NSS_2 but use as a GPIO */
|
||||
#define GPIO_SPI4_SCK (GPIO_SPI4_SCK_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI4_MISO (GPIO_SPI4_MISO_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI4_MOSI (GPIO_SPI4_MOSI_2|GPIO_SPEED_50MHz)
|
||||
|
||||
/************************************************************************************
|
||||
* 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);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_BOARD_BOARD_H */
|
||||
+9
-15
@@ -1,8 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
*
|
||||
* 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
|
||||
@@ -33,16 +31,12 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* @file Fixed Wing Attitude Rate Control */
|
||||
/**
|
||||
* nsh_romfsetc.h
|
||||
*
|
||||
* This file is a stub for 'make export' purposes; the actual ROMFS
|
||||
* must be supplied by the library client.
|
||||
*/
|
||||
|
||||
#ifndef FIXEDWING_ATT_CONTROL_RATE_H_
|
||||
#define FIXEDWING_ATT_CONTROL_RATE_H_
|
||||
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
|
||||
const float rates[],
|
||||
struct actuator_controls_s *actuators);
|
||||
|
||||
#endif /* FIXEDWING_ATT_CONTROL_RATE_H_ */
|
||||
extern unsigned char romfs_img[];
|
||||
extern unsigned int romfs_img_len;
|
||||
@@ -0,0 +1,179 @@
|
||||
############################################################################
|
||||
# configs/aerocore/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 =
|
||||
|
||||
@@ -1,6 +1,8 @@
|
||||
############################################################################
|
||||
# configs/aerocore/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,12 +33,10 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Full attitude / position Extended Kalman Filter
|
||||
#
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
MODULE_COMMAND = att_pos_estimator_ekf
|
||||
CONFIGURED_APPS += examples/nsh
|
||||
|
||||
SRCS = kalman_main.cpp \
|
||||
KalmanNav.cpp \
|
||||
params.c
|
||||
# The NSH application library
|
||||
CONFIGURED_APPS += nshlib
|
||||
CONFIGURED_APPS += system/readline
|
||||
@@ -0,0 +1,950 @@
|
||||
#
|
||||
# Automatically generated file; DO NOT EDIT.
|
||||
# Nuttx/ Configuration
|
||||
#
|
||||
CONFIG_NUTTX_NEWCONFIG=y
|
||||
|
||||
#
|
||||
# Build Setup
|
||||
#
|
||||
# CONFIG_EXPERIMENTAL is not set
|
||||
CONFIG_HOST_LINUX=y
|
||||
# CONFIG_HOST_OSX is not set
|
||||
# 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 is not set
|
||||
|
||||
#
|
||||
# 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_CODEREDL is not set
|
||||
# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL 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 is not set
|
||||
# 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=y
|
||||
# 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=y
|
||||
# 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 is not set
|
||||
CONFIG_STM32_I2C2=y
|
||||
# CONFIG_STM32_I2C3 is not set
|
||||
# CONFIG_STM32_OTGFS is not set
|
||||
# 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=y
|
||||
CONFIG_STM32_SPI3=y
|
||||
CONFIG_STM32_SPI4=y
|
||||
# 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=y
|
||||
# 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 is not set
|
||||
# CONFIG_STM32_TIM11 is not set
|
||||
# CONFIG_STM32_TIM12 is not set
|
||||
# CONFIG_STM32_TIM13 is not set
|
||||
# CONFIG_STM32_TIM14 is not set
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART3=y
|
||||
# CONFIG_STM32_UART4 is not set
|
||||
# CONFIG_STM32_UART5 is not set
|
||||
# CONFIG_STM32_USART6 is not set
|
||||
CONFIG_STM32_UART7=y
|
||||
CONFIG_STM32_UART8=y
|
||||
# CONFIG_STM32_IWDG is not set
|
||||
CONFIG_STM32_WWDG=y
|
||||
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_TIM5_PWM is not set
|
||||
# CONFIG_STM32_TIM9_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_TIM5_ADC is not set
|
||||
CONFIG_STM32_USART=y
|
||||
|
||||
#
|
||||
# U[S]ART Configuration
|
||||
#
|
||||
# CONFIG_USART1_RS485 is not set
|
||||
CONFIG_USART1_RXDMA=y
|
||||
# CONFIG_USART2_RS485 is not set
|
||||
CONFIG_USART2_RXDMA=y
|
||||
# CONFIG_USART3_RS485 is not set
|
||||
CONFIG_USART3_RXDMA=y
|
||||
# CONFIG_UART7_RS485 is not set
|
||||
CONFIG_UART7_RXDMA=y
|
||||
# CONFIG_UART8_RS485 is not set
|
||||
CONFIG_UART8_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=10
|
||||
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=262144
|
||||
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=36
|
||||
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=y
|
||||
|
||||
#
|
||||
# MTD Configuration
|
||||
#
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
|
||||
#
|
||||
# MTD Device Drivers
|
||||
#
|
||||
# CONFIG_RAMMTD is not set
|
||||
# CONFIG_MTD_AT24XX is not set
|
||||
# CONFIG_MTD_AT45DB is not set
|
||||
# CONFIG_MTD_M25P is not set
|
||||
# CONFIG_MTD_SMART is not set
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_RAMTRON_FUJITSU=y
|
||||
# CONFIG_MTD_SST25 is not set
|
||||
# CONFIG_MTD_SST39FV is not set
|
||||
# CONFIG_MTD_W25 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_16550_UART is not set
|
||||
CONFIG_ARCH_HAVE_UART7=y
|
||||
CONFIG_ARCH_HAVE_UART8=y
|
||||
CONFIG_ARCH_HAVE_USART1=y
|
||||
CONFIG_ARCH_HAVE_USART2=y
|
||||
CONFIG_ARCH_HAVE_USART3=y
|
||||
CONFIG_MCU_SERIAL=y
|
||||
CONFIG_STANDARD_SERIAL=y
|
||||
CONFIG_SERIAL_NPOLLWAITERS=2
|
||||
# CONFIG_USART1_SERIAL_CONSOLE is not set
|
||||
# CONFIG_USART2_SERIAL_CONSOLE is not set
|
||||
# CONFIG_USART3_SERIAL_CONSOLE is not set
|
||||
# CONFIG_UART7_SERIAL_CONSOLE is not set
|
||||
CONFIG_UART8_SERIAL_CONSOLE=y
|
||||
# CONFIG_NO_SERIAL_CONSOLE is not set
|
||||
|
||||
#
|
||||
# USART1 Configuration
|
||||
#
|
||||
CONFIG_USART1_RXBUFSIZE=512
|
||||
CONFIG_USART1_TXBUFSIZE=512
|
||||
CONFIG_USART1_BAUD=115200
|
||||
CONFIG_USART1_BITS=8
|
||||
CONFIG_USART1_PARITY=0
|
||||
CONFIG_USART1_2STOP=0
|
||||
# CONFIG_USART1_IFLOWCONTROL is not set
|
||||
# CONFIG_USART1_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# USART2 Configuration
|
||||
#
|
||||
CONFIG_USART2_RXBUFSIZE=512
|
||||
CONFIG_USART2_TXBUFSIZE=512
|
||||
CONFIG_USART2_BAUD=115200
|
||||
CONFIG_USART2_BITS=8
|
||||
CONFIG_USART2_PARITY=0
|
||||
CONFIG_USART2_2STOP=0
|
||||
# CONFIG_USART2_IFLOWCONTROL is not set
|
||||
# CONFIG_USART2_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# USART3 Configuration
|
||||
#
|
||||
CONFIG_USART3_RXBUFSIZE=512
|
||||
CONFIG_USART3_TXBUFSIZE=512
|
||||
CONFIG_USART3_BAUD=115200
|
||||
CONFIG_USART3_BITS=8
|
||||
CONFIG_USART3_PARITY=0
|
||||
CONFIG_USART3_2STOP=0
|
||||
# CONFIG_USART3_IFLOWCONTROL is not set
|
||||
# CONFIG_USART3_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# UART7 Configuration
|
||||
#
|
||||
CONFIG_UART7_RXBUFSIZE=512
|
||||
CONFIG_UART7_TXBUFSIZE=512
|
||||
CONFIG_UART7_BAUD=115200
|
||||
CONFIG_UART7_BITS=8
|
||||
CONFIG_UART7_PARITY=0
|
||||
CONFIG_UART7_2STOP=0
|
||||
# CONFIG_UART7_IFLOWCONTROL is not set
|
||||
# CONFIG_UART7_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# UART8 Configuration
|
||||
#
|
||||
CONFIG_UART8_RXBUFSIZE=512
|
||||
CONFIG_UART8_TXBUFSIZE=512
|
||||
CONFIG_UART8_BAUD=115200
|
||||
CONFIG_UART8_BITS=8
|
||||
CONFIG_UART8_PARITY=0
|
||||
CONFIG_UART8_2STOP=0
|
||||
# CONFIG_UART8_IFLOWCONTROL is not set
|
||||
# CONFIG_UART8_OFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_IFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_OFLOWCONTROL is not set
|
||||
# CONFIG_USBDEV 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=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_MAXFNAME=32
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
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=2000
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKPERIOD=50000
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=2000
|
||||
# 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_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=y
|
||||
# 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_MTDPART is not set
|
||||
# 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=1
|
||||
CONFIG_NSH_FATSECTSIZE=512
|
||||
CONFIG_NSH_FATNSECTORS=1024
|
||||
CONFIG_NSH_FATMOUNTPT="/tmp"
|
||||
CONFIG_NSH_CONSOLE=y
|
||||
|
||||
#
|
||||
# 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=y
|
||||
CONFIG_I2CTOOL_MINBUS=0
|
||||
CONFIG_I2CTOOL_MAXBUS=3
|
||||
CONFIG_I2CTOOL_MINADDR=0x03
|
||||
CONFIG_I2CTOOL_MAXADDR=0x77
|
||||
CONFIG_I2CTOOL_MAXREGADDR=0xff
|
||||
CONFIG_I2CTOOL_DEFFREQ=4000000
|
||||
|
||||
#
|
||||
# FLASH Program Installation
|
||||
#
|
||||
# CONFIG_SYSTEM_INSTALL is not set
|
||||
|
||||
#
|
||||
# FLASH Erase-all Command
|
||||
#
|
||||
# CONFIG_SYSTEM_FLASH_ERASEALL is not set
|
||||
|
||||
#
|
||||
# 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
|
||||
#
|
||||
Regular → Executable
+36
-9
@@ -1,6 +1,8 @@
|
||||
############################################################################
|
||||
#!/bin/bash
|
||||
# configs/aerocore/nsh/setenv.sh
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
@@ -29,12 +31,37 @@
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Fixedwing PositionControl application
|
||||
#
|
||||
if [ "$_" = "$0" ] ; then
|
||||
echo "You must source this script, not run it!" 1>&2
|
||||
exit 1
|
||||
fi
|
||||
|
||||
MODULE_COMMAND = fixedwing_pos_control
|
||||
WD=`pwd`
|
||||
if [ ! -x "setenv.sh" ]; then
|
||||
echo "This script must be executed from the top-level NuttX build directory"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
SRCS = fixedwing_pos_control_main.c
|
||||
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,150 @@
|
||||
/****************************************************************************
|
||||
* configs/aerocore/common/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 STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 256Kb 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 SRAM beginning at address 0x2002:0000
|
||||
* 4) 64Kb of TCM 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 = 2032K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
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) }
|
||||
}
|
||||
@@ -1,6 +1,8 @@
|
||||
############################################################################
|
||||
# configs/aerocore/src/Makefile
|
||||
#
|
||||
# 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,52 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the position estimator
|
||||
#
|
||||
-include $(TOPDIR)/Make.defs
|
||||
|
||||
MODULE_COMMAND = position_estimator
|
||||
CFLAGS += -I$(TOPDIR)/sched
|
||||
|
||||
# XXX this should be converted to a deamon, its a pretty bad example app
|
||||
MODULE_PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
MODULE_STACKSIZE = 4096
|
||||
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
|
||||
|
||||
SRCS = position_estimator_main.c
|
||||
@@ -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.
|
||||
*/
|
||||
@@ -418,7 +418,7 @@ CONFIG_PREALLOC_TIMERS=50
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_IDLETHREAD_STACKSIZE=4096
|
||||
CONFIG_USERMAIN_STACKSIZE=4096
|
||||
CONFIG_USERMAIN_STACKSIZE=3500
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
|
||||
@@ -504,8 +504,8 @@ CONFIG_MTD_BYTE_WRITE=y
|
||||
#
|
||||
# USART1 Configuration
|
||||
#
|
||||
CONFIG_USART1_RXBUFSIZE=512
|
||||
CONFIG_USART1_TXBUFSIZE=512
|
||||
CONFIG_USART1_RXBUFSIZE=300
|
||||
CONFIG_USART1_TXBUFSIZE=300
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_BITS=8
|
||||
CONFIG_USART1_PARITY=0
|
||||
@@ -528,8 +528,8 @@ CONFIG_USART2_OFLOWCONTROL=y
|
||||
#
|
||||
# UART5 Configuration
|
||||
#
|
||||
CONFIG_UART5_RXBUFSIZE=512
|
||||
CONFIG_UART5_TXBUFSIZE=512
|
||||
CONFIG_UART5_RXBUFSIZE=300
|
||||
CONFIG_UART5_TXBUFSIZE=300
|
||||
CONFIG_UART5_BAUD=57600
|
||||
CONFIG_UART5_BITS=8
|
||||
CONFIG_UART5_PARITY=0
|
||||
@@ -540,8 +540,8 @@ CONFIG_UART5_2STOP=0
|
||||
#
|
||||
# USART6 Configuration
|
||||
#
|
||||
CONFIG_USART6_RXBUFSIZE=512
|
||||
CONFIG_USART6_TXBUFSIZE=512
|
||||
CONFIG_USART6_RXBUFSIZE=128
|
||||
CONFIG_USART6_TXBUFSIZE=64
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_BITS=8
|
||||
CONFIG_USART6_PARITY=0
|
||||
|
||||
@@ -268,6 +268,10 @@
|
||||
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
|
||||
|
||||
#define GPIO_SPI4_MISO (GPIO_SPI4_MISO_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI4_MOSI (GPIO_SPI4_MOSI_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI4_SCK (GPIO_SPI4_SCK_1|GPIO_SPEED_50MHz)
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
@@ -235,7 +235,7 @@ CONFIG_STM32_SDIO=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
CONFIG_STM32_SPI2=y
|
||||
# CONFIG_STM32_SPI3 is not set
|
||||
# CONFIG_STM32_SPI4 is not set
|
||||
CONFIG_STM32_SPI4=y
|
||||
# CONFIG_STM32_SPI5 is not set
|
||||
# CONFIG_STM32_SPI6 is not set
|
||||
CONFIG_STM32_SYSCFG=y
|
||||
|
||||
@@ -103,8 +103,6 @@
|
||||
#define GPIO_USART2_RTS 0xffffffff
|
||||
#undef GPIO_USART2_CK
|
||||
#define GPIO_USART2_CK 0xffffffff
|
||||
#undef GPIO_USART3_TX
|
||||
#define GPIO_USART3_TX 0xffffffff
|
||||
#undef GPIO_USART3_CK
|
||||
#define GPIO_USART3_CK 0xffffffff
|
||||
#undef GPIO_USART3_CTS
|
||||
|
||||
@@ -104,9 +104,9 @@ CONFIG_ARMV7M_CMNVECTOR=y
|
||||
# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
|
||||
#
|
||||
CONFIG_STM32_DFU=n
|
||||
CONFIG_STM32_JTAG_FULL_ENABLE=y
|
||||
CONFIG_STM32_JTAG_FULL_ENABLE=n
|
||||
CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=n
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
|
||||
#
|
||||
# Individual subsystems can be enabled:
|
||||
|
||||
@@ -119,7 +119,7 @@ int ardrone_interface_main(int argc, char *argv[])
|
||||
ardrone_interface_task = task_spawn_cmd("ardrone_interface",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 15,
|
||||
2048,
|
||||
1100,
|
||||
ardrone_interface_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
|
||||
@@ -38,3 +38,4 @@
|
||||
MODULE_COMMAND = ardrone_interface
|
||||
SRCS = ardrone_interface.c \
|
||||
ardrone_motor_control.c
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
@@ -194,6 +194,26 @@ private:
|
||||
|
||||
bool systemstate_run;
|
||||
|
||||
int vehicle_status_sub_fd;
|
||||
int vehicle_control_mode_sub_fd;
|
||||
int vehicle_gps_position_sub_fd;
|
||||
int actuator_armed_sub_fd;
|
||||
int safety_sub_fd;
|
||||
|
||||
int num_of_cells;
|
||||
int detected_cells_runcount;
|
||||
|
||||
int t_led_color[8];
|
||||
int t_led_blink;
|
||||
int led_thread_runcount;
|
||||
int led_interval;
|
||||
|
||||
bool topic_initialized;
|
||||
bool detected_cells_blinked;
|
||||
bool led_thread_ready;
|
||||
|
||||
int num_of_used_sats;
|
||||
|
||||
void setLEDColor(int ledcolor);
|
||||
static void led_trampoline(void *arg);
|
||||
void led();
|
||||
@@ -265,7 +285,22 @@ BlinkM::BlinkM(int bus, int blinkm) :
|
||||
led_color_7(LED_OFF),
|
||||
led_color_8(LED_OFF),
|
||||
led_blink(LED_NOBLINK),
|
||||
systemstate_run(false)
|
||||
systemstate_run(false),
|
||||
vehicle_status_sub_fd(-1),
|
||||
vehicle_control_mode_sub_fd(-1),
|
||||
vehicle_gps_position_sub_fd(-1),
|
||||
actuator_armed_sub_fd(-1),
|
||||
safety_sub_fd(-1),
|
||||
num_of_cells(0),
|
||||
detected_cells_runcount(0),
|
||||
t_led_color({0}),
|
||||
t_led_blink(0),
|
||||
led_thread_runcount(0),
|
||||
led_interval(1000),
|
||||
topic_initialized(false),
|
||||
detected_cells_blinked(false),
|
||||
led_thread_ready(true),
|
||||
num_of_used_sats(0)
|
||||
{
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
}
|
||||
@@ -382,31 +417,6 @@ void
|
||||
BlinkM::led()
|
||||
{
|
||||
|
||||
static int vehicle_status_sub_fd;
|
||||
static int vehicle_control_mode_sub_fd;
|
||||
static int vehicle_gps_position_sub_fd;
|
||||
static int actuator_armed_sub_fd;
|
||||
static int safety_sub_fd;
|
||||
|
||||
static int num_of_cells = 0;
|
||||
static int detected_cells_runcount = 0;
|
||||
|
||||
static int t_led_color[8] = { 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
static int t_led_blink = 0;
|
||||
static int led_thread_runcount=0;
|
||||
static int led_interval = 1000;
|
||||
|
||||
static int no_data_vehicle_status = 0;
|
||||
static int no_data_vehicle_control_mode = 0;
|
||||
static int no_data_actuator_armed = 0;
|
||||
static int no_data_vehicle_gps_position = 0;
|
||||
|
||||
static bool topic_initialized = false;
|
||||
static bool detected_cells_blinked = false;
|
||||
static bool led_thread_ready = true;
|
||||
|
||||
int num_of_used_sats = 0;
|
||||
|
||||
if(!topic_initialized) {
|
||||
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
|
||||
orb_set_interval(vehicle_status_sub_fd, 250);
|
||||
@@ -494,6 +504,11 @@ BlinkM::led()
|
||||
|
||||
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
|
||||
|
||||
int no_data_vehicle_status = 0;
|
||||
int no_data_vehicle_control_mode = 0;
|
||||
int no_data_actuator_armed = 0;
|
||||
int no_data_vehicle_gps_position = 0;
|
||||
|
||||
if (new_data_vehicle_status) {
|
||||
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub_fd, &vehicle_status_raw);
|
||||
no_data_vehicle_status = 0;
|
||||
@@ -638,11 +653,11 @@ BlinkM::led()
|
||||
|
||||
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
|
||||
/* indicate main control state */
|
||||
if (vehicle_status_raw.main_state == MAIN_STATE_EASY)
|
||||
if (vehicle_status_raw.main_state == MAIN_STATE_POSCTL)
|
||||
led_color_4 = LED_GREEN;
|
||||
else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
|
||||
led_color_4 = LED_BLUE;
|
||||
else if (vehicle_status_raw.main_state == MAIN_STATE_SEATBELT)
|
||||
else if (vehicle_status_raw.main_state == MAIN_STATE_ALTCTL)
|
||||
led_color_4 = LED_YELLOW;
|
||||
else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
|
||||
led_color_4 = LED_WHITE;
|
||||
|
||||
@@ -0,0 +1,282 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 aerocore_init.c
|
||||
*
|
||||
* AeroCore-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/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
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(CONFIG_FAT_DMAMEMORY)
|
||||
# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
|
||||
# error microSD DMA support requires CONFIG_GRAN
|
||||
# endif
|
||||
|
||||
static GRAN_HANDLE dma_allocator;
|
||||
|
||||
/*
|
||||
* The DMA heap size constrains the total number of things that can be
|
||||
* ready to do DMA at a time.
|
||||
*
|
||||
* For example, FAT DMA depends on one sector-sized buffer per filesystem plus
|
||||
* one sector-sized buffer per file.
|
||||
*
|
||||
* We use a fundamental alignment / granule size of 64B; this is sufficient
|
||||
* to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
|
||||
*/
|
||||
static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
|
||||
static perf_counter_t g_dma_perf;
|
||||
|
||||
static void
|
||||
dma_alloc_init(void)
|
||||
{
|
||||
dma_allocator = gran_initialize(g_dma_heap,
|
||||
sizeof(g_dma_heap),
|
||||
7, /* 128B granule - must be > alignment (XXX bug?) */
|
||||
6); /* 64B alignment */
|
||||
if (dma_allocator == NULL) {
|
||||
message("[boot] DMA allocator setup FAILED");
|
||||
} else {
|
||||
g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* DMA-aware allocator stubs for the FAT filesystem.
|
||||
*/
|
||||
|
||||
__EXPORT void *fat_dma_alloc(size_t size);
|
||||
__EXPORT void fat_dma_free(FAR void *memory, size_t size);
|
||||
|
||||
void *
|
||||
fat_dma_alloc(size_t size)
|
||||
{
|
||||
perf_count(g_dma_perf);
|
||||
return gran_alloc(dma_allocator, size);
|
||||
}
|
||||
|
||||
void
|
||||
fat_dma_free(FAR void *memory, size_t size)
|
||||
{
|
||||
gran_free(dma_allocator, memory, size);
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
# define dma_alloc_init()
|
||||
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* 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 SPI interfaces */
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure LEDs */
|
||||
up_ledinit();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static struct spi_dev_s *spi3;
|
||||
static struct spi_dev_s *spi4;
|
||||
|
||||
#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 ADC pins */
|
||||
stm32_configgpio(GPIO_ADC1_IN10); /* used by VBUS valid */
|
||||
stm32_configgpio(GPIO_ADC1_IN11); /* J1 breakout */
|
||||
stm32_configgpio(GPIO_ADC1_IN12); /* J1 breakout */
|
||||
stm32_configgpio(GPIO_ADC1_IN13); /* J1 breakout */
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
dma_alloc_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);
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_AMBER);
|
||||
|
||||
/* Configure Sensors on SPI bus #3 */
|
||||
spi3 = up_spiinitialize(3);
|
||||
if (!spi3) {
|
||||
message("[boot] FAILED to initialize SPI port 3\n");
|
||||
up_ledon(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
/* Default: 1MHz, 8 bits, Mode 3 */
|
||||
SPI_SETFREQUENCY(spi3, 10000000);
|
||||
SPI_SETBITS(spi3, 8);
|
||||
SPI_SETMODE(spi3, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_GYRO, false);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_ACCEL_MAG, false);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_BARO, false);
|
||||
up_udelay(20);
|
||||
message("[boot] Initialized SPI port 3 (SENSORS)\n");
|
||||
|
||||
/* Configure FRAM on SPI bus #4 */
|
||||
spi4 = up_spiinitialize(4);
|
||||
if (!spi4) {
|
||||
message("[boot] FAILED to initialize SPI port 4\n");
|
||||
up_ledon(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
/* Default: ~10MHz, 8 bits, Mode 3 */
|
||||
SPI_SETFREQUENCY(spi4, 10 * 1000 * 1000);
|
||||
SPI_SETBITS(spi4, 8);
|
||||
SPI_SETMODE(spi4, SPIDEV_MODE0);
|
||||
SPI_SELECT(spi4, SPIDEV_FLASH, false);
|
||||
message("[boot] Initialized SPI port 4 (FRAM)\n");
|
||||
|
||||
return OK;
|
||||
}
|
||||
+73
-69
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
@@ -32,86 +32,90 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file fw_att_pos_estimator_params.c
|
||||
* @file aerocore_led.c
|
||||
*
|
||||
* Parameters defined by the attitude and position estimator task
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* AeroCore LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Estimator parameters, accessible via MAVLink
|
||||
*
|
||||
* 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();
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
/**
|
||||
* Velocity estimate delay
|
||||
*
|
||||
* The delay in milliseconds of the velocity estimate from GPS.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PE_VEL_DELAY_MS, 230);
|
||||
__EXPORT void led_init()
|
||||
{
|
||||
stm32_configgpio(GPIO_LED0);
|
||||
stm32_configgpio(GPIO_LED1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Position estimate delay
|
||||
*
|
||||
* The delay in milliseconds of the position estimate from GPS.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PE_POS_DELAY_MS, 210);
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
stm32_gpiowrite(GPIO_LED0, true);
|
||||
break;
|
||||
|
||||
/**
|
||||
* Height estimate delay
|
||||
*
|
||||
* The delay in milliseconds of the height estimate from the barometer.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PE_HGT_DELAY_MS, 350);
|
||||
case 1:
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
break;
|
||||
|
||||
/**
|
||||
* Mag estimate delay
|
||||
*
|
||||
* The delay in milliseconds of the magnetic field estimate from
|
||||
* the magnetometer.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PE_MAG_DELAY_MS, 30);
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* True airspeeed estimate delay
|
||||
*
|
||||
* The delay in milliseconds of the airspeed estimate.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PE_TAS_DELAY_MS, 210);
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
stm32_gpiowrite(GPIO_LED0, false);
|
||||
break;
|
||||
|
||||
/**
|
||||
* GPS vs. barometric altitude update weight
|
||||
*
|
||||
* RE-CHECK this.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_GPS_ALT_WGT, 0.9f);
|
||||
case 1:
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
if (stm32_gpioread(GPIO_LED0))
|
||||
stm32_gpiowrite(GPIO_LED0, false);
|
||||
else
|
||||
stm32_gpiowrite(GPIO_LED0, true);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
if (stm32_gpioread(GPIO_LED1))
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
else
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
||||
Executable → Regular
+77
-29
@@ -1,9 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Damian Aregger <daregger@student.ethz.ch>
|
||||
* Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -35,35 +32,86 @@
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file position_estimator_mc_params.h
|
||||
*
|
||||
* Parameters for Position Estimator
|
||||
* @file aerocore_pwm_servo.c
|
||||
*
|
||||
* Configuration data for the stm32 pwm_servo driver.
|
||||
*
|
||||
* Note that these arrays must always be fully-sized.
|
||||
*/
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#include <stdint.h>
|
||||
|
||||
struct position_estimator_mc_params {
|
||||
float addNoise;
|
||||
float sigma;
|
||||
float R;
|
||||
int baro; /* consider barometer */
|
||||
#include <stm32.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_tim.h>
|
||||
|
||||
#include <drivers/stm32/drv_pwm_servo.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
|
||||
{
|
||||
.base = STM32_TIM1_BASE,
|
||||
.clock_register = STM32_RCC_APB2ENR,
|
||||
.clock_bit = RCC_APB2ENR_TIM1EN,
|
||||
.clock_freq = STM32_APB2_TIM1_CLKIN
|
||||
},
|
||||
{
|
||||
.base = STM32_TIM3_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM3EN,
|
||||
.clock_freq = STM32_APB1_TIM3_CLKIN
|
||||
}
|
||||
};
|
||||
|
||||
struct position_estimator_mc_param_handles {
|
||||
param_t addNoise;
|
||||
param_t sigma;
|
||||
param_t r;
|
||||
param_t baro_param_handle;
|
||||
__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH1OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH2OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH3OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH4OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 4,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH1OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 1,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH2OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 2,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH3OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 3,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH4OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 4,
|
||||
.default_value = 1500,
|
||||
}
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialize all parameter handles and values
|
||||
*
|
||||
*/
|
||||
int parameters_init(struct position_estimator_mc_param_handles *h);
|
||||
|
||||
/**
|
||||
* Update all parameters
|
||||
*
|
||||
*/
|
||||
int parameters_update(const struct position_estimator_mc_param_handles *h, struct position_estimator_mc_params *p);
|
||||
@@ -0,0 +1,183 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 aerocore_spi.c
|
||||
*
|
||||
* Board-specific SPI functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void weak_function stm32_spiinitialize(void)
|
||||
{
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
stm32_configgpio(GPIO_SPI1_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI1_NSS, 1);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
stm32_configgpio(GPIO_SPI2_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI2_NSS, 1);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
stm32_configgpio(GPIO_SPI_CS_GYRO);
|
||||
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
|
||||
stm32_configgpio(GPIO_SPI_CS_BARO);
|
||||
|
||||
/* De-activate all peripherals,
|
||||
* required for some peripheral
|
||||
* state machines
|
||||
*/
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
|
||||
stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
|
||||
stm32_configgpio(GPIO_EXTI_MAG_DRDY);
|
||||
stm32_configgpio(GPIO_EXTI_ACCEL_DRDY);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
stm32_configgpio(GPIO_SPI4_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI4_NSS, 1);
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* there is only one device broken-out so select it */
|
||||
stm32_gpiowrite(GPIO_SPI1_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* there is only one device broken-out so select it */
|
||||
stm32_gpiowrite(GPIO_SPI2_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* SPI select is active low, so write !selected to select the device */
|
||||
|
||||
switch (devid) {
|
||||
case PX4_SPIDEV_GYRO:
|
||||
/* 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;
|
||||
|
||||
case PX4_SPIDEV_ACCEL_MAG:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_BARO:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* there can only be one device on this bus, so always select it */
|
||||
stm32_gpiowrite(GPIO_SPI4_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
/* FRAM is always present */
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
@@ -0,0 +1,176 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
*
|
||||
* AeroCore 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
|
||||
****************************************************************************************************/
|
||||
|
||||
/* LEDs */
|
||||
#define GPIO_LED0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN10)
|
||||
|
||||
/* Gyro */
|
||||
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0)
|
||||
#define SENSOR_BOARD_ROTATION_DEFAULT 3 /* SENSOR_BOARD_ROTATION_270_DEG */
|
||||
|
||||
/* Accel & Mag */
|
||||
#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN1)
|
||||
#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN2)
|
||||
|
||||
/* GPS */
|
||||
#define GPIO_GPS_NRESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_GPS_TIMEPULSE (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPS_DEFAULT_UART_PORT "/dev/ttyS0"
|
||||
|
||||
/* SPI3--Sensors */
|
||||
#define PX4_SPI_BUS_SENSORS 3
|
||||
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
|
||||
|
||||
/* Nominal chip selects for devices on SPI bus #3 */
|
||||
#define PX4_SPIDEV_ACCEL_MAG 0
|
||||
#define PX4_SPIDEV_GYRO 1
|
||||
#define PX4_SPIDEV_BARO 2
|
||||
|
||||
/* User GPIOs broken out on J11 */
|
||||
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO8_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_GPIO9_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_GPIO10_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_GPIO11_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO8_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_GPIO9_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_GPIO10_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_GPIO11_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
/* PWM
|
||||
*
|
||||
* Eight PWM outputs are configured.
|
||||
*
|
||||
* Pins:
|
||||
*
|
||||
* CH1 : PA8 : TIM1_CH1
|
||||
* CH2 : PA9 : TIM1_CH2
|
||||
* CH3 : PA10 : TIM1_CH3
|
||||
* CH4 : PA11 : TIM1_CH4
|
||||
* CH5 : PC6 : TIM3_CH1
|
||||
* CH6 : PC7 : TIM3_CH2
|
||||
* CH7 : PC8 : TIM3_CH3
|
||||
* CH8 : PC9 : TIM3_CH4
|
||||
*/
|
||||
#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1
|
||||
#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1
|
||||
#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_1
|
||||
#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_1
|
||||
#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_3
|
||||
#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_3
|
||||
#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_2
|
||||
#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_2
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer 8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
|
||||
/* Tone Alarm (no onboard speaker )*/
|
||||
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* channel 1 */
|
||||
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
|
||||
|
||||
|
||||
/****************************************************************************************************
|
||||
* 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);
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,8 @@
|
||||
#
|
||||
# Board-specific startup code for the AeroCore
|
||||
#
|
||||
|
||||
SRCS = aerocore_init.c \
|
||||
aerocore_pwm_servo.c \
|
||||
aerocore_spi.c \
|
||||
aerocore_led.c
|
||||
@@ -85,6 +85,9 @@ __BEGIN_DECLS
|
||||
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
|
||||
#define PX4_SPI_BUS_SENSORS 1
|
||||
#define PX4_SPI_BUS_EXT 2
|
||||
|
||||
/*
|
||||
* Use these in place of the spi_dev_e enumeration to
|
||||
* select a specific SPI device on SPI1
|
||||
@@ -96,7 +99,7 @@ __BEGIN_DECLS
|
||||
/*
|
||||
* Optional devices on IO's external port
|
||||
*/
|
||||
#define PX4_SPIDEV_ACCEL_MAG 2
|
||||
#define PX4_SPIDEV_ACCEL_MAG 2
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
|
||||
@@ -106,6 +106,11 @@ __BEGIN_DECLS
|
||||
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
|
||||
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
|
||||
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
|
||||
#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
|
||||
|
||||
#define PX4_SPI_BUS_SENSORS 1
|
||||
#define PX4_SPI_BUS_EXT 4
|
||||
|
||||
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
|
||||
#define PX4_SPIDEV_GYRO 1
|
||||
@@ -113,6 +118,10 @@ __BEGIN_DECLS
|
||||
#define PX4_SPIDEV_BARO 3
|
||||
#define PX4_SPIDEV_MPU 4
|
||||
|
||||
/* External bus */
|
||||
#define PX4_SPIDEV_EXT0 1
|
||||
#define PX4_SPIDEV_EXT1 2
|
||||
|
||||
/* I2C busses */
|
||||
#define PX4_I2C_BUS_EXPANSION 1
|
||||
#define PX4_I2C_BUS_LED 2
|
||||
|
||||
@@ -192,6 +192,7 @@ stm32_boardinitialize(void)
|
||||
|
||||
static struct spi_dev_s *spi1;
|
||||
static struct spi_dev_s *spi2;
|
||||
static struct spi_dev_s *spi4;
|
||||
static struct sdio_dev_s *sdio;
|
||||
|
||||
#include <math.h>
|
||||
@@ -305,6 +306,17 @@ __EXPORT int nsh_archinitialize(void)
|
||||
|
||||
message("[boot] Initialized SPI port 2 (RAMTRON FRAM)\n");
|
||||
|
||||
spi4 = up_spiinitialize(4);
|
||||
|
||||
/* Default SPI4 to 1MHz and de-assert the known chip selects. */
|
||||
SPI_SETFREQUENCY(spi4, 10000000);
|
||||
SPI_SETBITS(spi4, 8);
|
||||
SPI_SETMODE(spi4, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi4, PX4_SPIDEV_EXT0, false);
|
||||
SPI_SELECT(spi4, PX4_SPIDEV_EXT1, false);
|
||||
|
||||
message("[boot] Initialized SPI port 4\n");
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
/* First, get an instance of the SDIO interface */
|
||||
|
||||
|
||||
@@ -94,6 +94,13 @@ __EXPORT void weak_function stm32_spiinitialize(void)
|
||||
stm32_configgpio(GPIO_SPI_CS_FRAM);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
stm32_configgpio(GPIO_SPI_CS_EXT0);
|
||||
stm32_configgpio(GPIO_SPI_CS_EXT1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
|
||||
#endif
|
||||
}
|
||||
|
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
@@ -157,3 +164,31 @@ __EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* SPI select is active low, so write !selected to select the device */
|
||||
|
||||
switch (devid) {
|
||||
case PX4_SPIDEV_EXT0:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_EXT1:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_EXT1, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
@@ -94,6 +94,14 @@
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
/*
|
||||
* AeroCore GPIO numbers and configuration.
|
||||
*
|
||||
*/
|
||||
# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
||||
/* no GPIO driver on the PX4IOv1 board */
|
||||
#endif
|
||||
@@ -146,4 +154,4 @@
|
||||
|
||||
#define GPIO_SENSOR_RAIL_RESET GPIOC(13)
|
||||
|
||||
#endif /* _DRV_GPIO_H */
|
||||
#endif /* _DRV_GPIO_H */
|
||||
|
||||
@@ -43,10 +43,14 @@
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include "drv_sensor.h"
|
||||
#include "drv_orb_dev.h"
|
||||
|
||||
#ifndef GPS_DEFAULT_UART_PORT
|
||||
#define GPS_DEFAULT_UART_PORT "/dev/ttyS3"
|
||||
#endif
|
||||
|
||||
#define GPS_DEVICE_PATH "/dev/gps"
|
||||
|
||||
|
||||
+35
-15
@@ -1,8 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
*
|
||||
* Copyright (c) 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
|
||||
@@ -33,19 +31,41 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* @file Fixed Wing Attitude Control */
|
||||
/**
|
||||
* @file drv_io_expander.h
|
||||
*
|
||||
* IO expander device API
|
||||
*/
|
||||
|
||||
#ifndef FIXEDWING_ATT_CONTROL_ATT_H_
|
||||
#define FIXEDWING_ATT_CONTROL_ATT_H_
|
||||
#pragma once
|
||||
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
||||
const struct vehicle_attitude_s *att,
|
||||
const float speed_body[],
|
||||
struct vehicle_rates_setpoint_s *rates_sp);
|
||||
/*
|
||||
* ioctl() definitions
|
||||
*/
|
||||
|
||||
#endif /* FIXEDWING_ATT_CONTROL_ATT_H_ */
|
||||
#define _IOXIOCBASE (0x2800)
|
||||
#define _IOXIOC(_n) (_IOC(_IOXIOCBASE, _n))
|
||||
|
||||
/** set a bitmask (non-blocking) */
|
||||
#define IOX_SET_MASK _IOXIOC(1)
|
||||
|
||||
/** get a bitmask (blocking) */
|
||||
#define IOX_GET_MASK _IOXIOC(2)
|
||||
|
||||
/** set device mode (non-blocking) */
|
||||
#define IOX_SET_MODE _IOXIOC(3)
|
||||
|
||||
/** set constant values (non-blocking) */
|
||||
#define IOX_SET_VALUE _IOXIOC(4)
|
||||
|
||||
/* ... to IOX_SET_VALUE + 8 */
|
||||
|
||||
/* enum passed to RGBLED_SET_MODE ioctl()*/
|
||||
enum IOX_MODE {
|
||||
IOX_MODE_OFF,
|
||||
IOX_MODE_ON,
|
||||
IOX_MODE_TEST_OUT
|
||||
};
|
||||
@@ -154,8 +154,9 @@ ETSAirspeed::collect()
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint16_t diff_pres_pa = val[1] << 8 | val[0];
|
||||
if (diff_pres_pa == 0) {
|
||||
uint16_t diff_pres_pa_raw = val[1] << 8 | val[0];
|
||||
uint16_t diff_pres_pa;
|
||||
if (diff_pres_pa_raw == 0) {
|
||||
// a zero value means the pressure sensor cannot give us a
|
||||
// value. We need to return, and not report a value or the
|
||||
// caller could end up using this value as part of an
|
||||
@@ -165,10 +166,10 @@ ETSAirspeed::collect()
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
|
||||
if (diff_pres_pa_raw < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
|
||||
diff_pres_pa = 0;
|
||||
} else {
|
||||
diff_pres_pa -= _diff_pres_offset;
|
||||
diff_pres_pa = diff_pres_pa_raw - _diff_pres_offset;
|
||||
}
|
||||
|
||||
// Track maximum differential pressure measured (so we can work out top speed).
|
||||
@@ -183,6 +184,7 @@ ETSAirspeed::collect()
|
||||
|
||||
// XXX we may want to smooth out the readings to remove noise.
|
||||
report.differential_pressure_filtered_pa = (float)diff_pres_pa;
|
||||
report.differential_pressure_raw_pa = (float)diff_pres_pa_raw;
|
||||
report.temperature = -1000.0f;
|
||||
report.voltage = 0;
|
||||
report.max_differential_pressure_pa = _max_differential_pressure_pa;
|
||||
|
||||
@@ -53,6 +53,8 @@
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
/* FrSky sensor hub data IDs */
|
||||
#define FRSKY_ID_GPS_ALT_BP 0x01
|
||||
#define FRSKY_ID_TEMP1 0x02
|
||||
@@ -192,17 +194,12 @@ void frsky_send_frame1(int uart)
|
||||
}
|
||||
|
||||
/**
|
||||
* Formats the decimal latitude/longitude to the required degrees/minutes/seconds.
|
||||
* Formats the decimal latitude/longitude to the required degrees/minutes.
|
||||
*/
|
||||
static float frsky_format_gps(float dec)
|
||||
{
|
||||
float dms_deg = (int) dec;
|
||||
float dec_deg = dec - dms_deg;
|
||||
float dms_min = (int) (dec_deg * 60);
|
||||
float dec_min = (dec_deg * 60) - dms_min;
|
||||
float dms_sec = dec_min * 60;
|
||||
|
||||
return (dms_deg * 100.0f) + dms_min + (dms_sec / 100.0f);
|
||||
float dm_deg = (int) dec;
|
||||
return (dm_deg * 100.0f) + (dec - dm_deg) * 60;
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -230,9 +227,9 @@ void frsky_send_frame2(int uart)
|
||||
struct tm *tm_gps = gmtime(&time_gps);
|
||||
|
||||
course = (global_pos.yaw + M_PI_F) / M_PI_F * 180.0f;
|
||||
lat = frsky_format_gps(abs(global_pos.lat));
|
||||
lat = frsky_format_gps(fabsf(global_pos.lat));
|
||||
lat_ns = (global_pos.lat < 0) ? 'S' : 'N';
|
||||
lon = frsky_format_gps(abs(global_pos.lon));
|
||||
lon = frsky_format_gps(fabsf(global_pos.lon));
|
||||
lon_ew = (global_pos.lon < 0) ? 'W' : 'E';
|
||||
speed = sqrtf(global_pos.vel_n * global_pos.vel_n + global_pos.vel_e * global_pos.vel_e)
|
||||
* 25.0f / 46.0f;
|
||||
|
||||
@@ -222,7 +222,7 @@ int frsky_telemetry_main(int argc, char *argv[])
|
||||
frsky_task = task_spawn_cmd("frsky_telemetry",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2048,
|
||||
2000,
|
||||
frsky_telemetry_thread_main,
|
||||
(const char **)argv);
|
||||
|
||||
|
||||
@@ -39,3 +39,5 @@ MODULE_COMMAND = frsky_telemetry
|
||||
|
||||
SRCS = frsky_data.c \
|
||||
frsky_telemetry.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
+20
-15
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
@@ -56,6 +56,7 @@
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/scheduling_priorities.h>
|
||||
#include <systemlib/err.h>
|
||||
@@ -63,6 +64,8 @@
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include "ubx.h"
|
||||
#include "mtk.h"
|
||||
|
||||
@@ -76,12 +79,6 @@
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
#ifndef CONFIG_SCHED_WORKQUEUE
|
||||
# error This requires CONFIG_SCHED_WORKQUEUE.
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
class GPS : public device::CDev
|
||||
{
|
||||
public:
|
||||
@@ -209,7 +206,8 @@ GPS::init()
|
||||
goto out;
|
||||
|
||||
/* start the GPS driver worker task */
|
||||
_task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr);
|
||||
_task = task_spawn_cmd("gps", SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_SLOW_DRIVER, 2000, (main_t)&GPS::task_main_trampoline, nullptr);
|
||||
|
||||
if (_task < 0) {
|
||||
warnx("task start failed: %d", errno);
|
||||
@@ -276,14 +274,14 @@ GPS::task_main()
|
||||
_report.timestamp_position = hrt_absolute_time();
|
||||
_report.lat = (int32_t)47.378301e7f;
|
||||
_report.lon = (int32_t)8.538777e7f;
|
||||
_report.alt = (int32_t)400e3f;
|
||||
_report.alt = (int32_t)1200e3f;
|
||||
_report.timestamp_variance = hrt_absolute_time();
|
||||
_report.s_variance_m_s = 10.0f;
|
||||
_report.p_variance_m = 10.0f;
|
||||
_report.c_variance_rad = 0.1f;
|
||||
_report.fix_type = 3;
|
||||
_report.eph_m = 3.0f;
|
||||
_report.epv_m = 7.0f;
|
||||
_report.eph_m = 0.9f;
|
||||
_report.epv_m = 1.8f;
|
||||
_report.timestamp_velocity = hrt_absolute_time();
|
||||
_report.vel_n_m_s = 0.0f;
|
||||
_report.vel_e_m_s = 0.0f;
|
||||
@@ -421,7 +419,14 @@ GPS::task_main()
|
||||
void
|
||||
GPS::cmd_reset()
|
||||
{
|
||||
//XXX add reset?
|
||||
#ifdef GPIO_GPS_NRESET
|
||||
warnx("Toggling GPS reset pin");
|
||||
stm32_configgpio(GPIO_GPS_NRESET);
|
||||
stm32_gpiowrite(GPIO_GPS_NRESET, 0);
|
||||
usleep(100);
|
||||
stm32_gpiowrite(GPIO_GPS_NRESET, 1);
|
||||
warnx("Toggled GPS reset pin");
|
||||
#endif
|
||||
}
|
||||
|
||||
void
|
||||
@@ -443,10 +448,10 @@ GPS::print_info()
|
||||
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
|
||||
|
||||
if (_report.timestamp_position != 0) {
|
||||
warnx("position lock: %dD, satellites: %d, last update: %fms ago", (int)_report.fix_type,
|
||||
_report.satellites_visible, (hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
|
||||
warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report.fix_type,
|
||||
_report.satellites_visible, (double)(hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
|
||||
warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
|
||||
warnx("eph: %.2fm, epv: %.2fm", _report.eph_m, _report.epv_m);
|
||||
warnx("eph: %.2fm, epv: %.2fm", (double)_report.eph_m, (double)_report.epv_m);
|
||||
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
|
||||
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
|
||||
warnx("rate publication:\t%6.2f Hz", (double)_rate);
|
||||
|
||||
@@ -56,7 +56,7 @@ GPS_Helper::get_velocity_update_rate()
|
||||
return _rate_vel;
|
||||
}
|
||||
|
||||
float
|
||||
void
|
||||
GPS_Helper::reset_update_rates()
|
||||
{
|
||||
_rate_count_vel = 0;
|
||||
@@ -64,7 +64,7 @@ GPS_Helper::reset_update_rates()
|
||||
_interval_rate_start = hrt_absolute_time();
|
||||
}
|
||||
|
||||
float
|
||||
void
|
||||
GPS_Helper::store_update_rates()
|
||||
{
|
||||
_rate_vel = _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f);
|
||||
|
||||
@@ -46,13 +46,17 @@
|
||||
class GPS_Helper
|
||||
{
|
||||
public:
|
||||
|
||||
GPS_Helper() {};
|
||||
virtual ~GPS_Helper() {};
|
||||
|
||||
virtual int configure(unsigned &baud) = 0;
|
||||
virtual int receive(unsigned timeout) = 0;
|
||||
int set_baudrate(const int &fd, unsigned baud);
|
||||
float get_position_update_rate();
|
||||
float get_velocity_update_rate();
|
||||
float reset_update_rates();
|
||||
float store_update_rates();
|
||||
void reset_update_rates();
|
||||
void store_update_rates();
|
||||
|
||||
protected:
|
||||
uint8_t _rate_count_lat_lon;
|
||||
|
||||
@@ -41,3 +41,5 @@ SRCS = gps.cpp \
|
||||
gps_helper.cpp \
|
||||
mtk.cpp \
|
||||
ubx.cpp
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
@@ -249,12 +249,18 @@ MTK::handle_message(gps_mtk_packet_t &packet)
|
||||
warnx("mtk: unknown revision");
|
||||
_gps_position->lat = 0;
|
||||
_gps_position->lon = 0;
|
||||
|
||||
// Indicate this data is not usable and bail out
|
||||
_gps_position->eph_m = 1000.0f;
|
||||
_gps_position->epv_m = 1000.0f;
|
||||
_gps_position->fix_type = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
|
||||
_gps_position->fix_type = packet.fix_type;
|
||||
_gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
|
||||
_gps_position->epv_m = 0.0; //unknown in mtk custom mode
|
||||
_gps_position->eph_m = packet.hdop / 100.0f; // from cm to m
|
||||
_gps_position->epv_m = _gps_position->eph_m; // unknown in mtk custom mode, so we cheat with eph
|
||||
_gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
|
||||
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
|
||||
_gps_position->satellites_visible = packet.satellites;
|
||||
|
||||
+50
-15
@@ -69,6 +69,9 @@ UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) :
|
||||
_gps_position(gps_position),
|
||||
_configured(false),
|
||||
_waiting_for_ack(false),
|
||||
_got_posllh(false),
|
||||
_got_velned(false),
|
||||
_got_timeutc(false),
|
||||
_disable_cmd_last(0)
|
||||
{
|
||||
decode_init();
|
||||
@@ -164,7 +167,7 @@ UBX::configure(unsigned &baudrate)
|
||||
send_config_packet(_fd, (uint8_t *)&cfg_rate_packet, sizeof(cfg_rate_packet));
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("ubx: configuration failed: RATE");
|
||||
warnx("CFG FAIL: RATE");
|
||||
return 1;
|
||||
}
|
||||
|
||||
@@ -185,7 +188,7 @@ UBX::configure(unsigned &baudrate)
|
||||
send_config_packet(_fd, (uint8_t *)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("ubx: configuration failed: NAV5");
|
||||
warnx("CFG FAIL: NAV5");
|
||||
return 1;
|
||||
}
|
||||
|
||||
@@ -194,35 +197,42 @@ UBX::configure(unsigned &baudrate)
|
||||
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1);
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("ubx: msg rate configuration failed: NAV POSLLH");
|
||||
warnx("MSG CFG FAIL: NAV POSLLH");
|
||||
return 1;
|
||||
}
|
||||
|
||||
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1);
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("ubx: msg rate configuration failed: NAV TIMEUTC");
|
||||
warnx("MSG CFG FAIL: NAV TIMEUTC");
|
||||
return 1;
|
||||
}
|
||||
|
||||
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1);
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("ubx: msg rate configuration failed: NAV SOL");
|
||||
warnx("MSG CFG FAIL: NAV SOL");
|
||||
return 1;
|
||||
}
|
||||
|
||||
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1);
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("ubx: msg rate configuration failed: NAV VELNED");
|
||||
warnx("MSG CFG FAIL: NAV VELNED");
|
||||
return 1;
|
||||
}
|
||||
|
||||
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5);
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("ubx: msg rate configuration failed: NAV SVINFO");
|
||||
warnx("MSG CFG FAIL: NAV SVINFO");
|
||||
return 1;
|
||||
}
|
||||
|
||||
configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1);
|
||||
|
||||
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
warnx("MSG CFG FAIL: MON HW");
|
||||
return 1;
|
||||
}
|
||||
|
||||
@@ -268,18 +278,22 @@ UBX::receive(unsigned timeout)
|
||||
bool handled = false;
|
||||
|
||||
while (true) {
|
||||
bool ready_to_return = _configured ? (_got_posllh && _got_velned && _got_timeutc) : handled;
|
||||
|
||||
/* poll for new data, wait for only UBX_PACKET_TIMEOUT (2ms) if something already received */
|
||||
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), handled ? UBX_PACKET_TIMEOUT : timeout);
|
||||
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), ready_to_return ? UBX_PACKET_TIMEOUT : timeout);
|
||||
|
||||
if (ret < 0) {
|
||||
/* something went wrong when polling */
|
||||
warnx("ubx: poll error");
|
||||
warnx("poll error");
|
||||
return -1;
|
||||
|
||||
} else if (ret == 0) {
|
||||
/* return success after short delay after receiving a packet or timeout after long delay */
|
||||
if (handled) {
|
||||
if (ready_to_return) {
|
||||
_got_posllh = false;
|
||||
_got_velned = false;
|
||||
_got_timeutc = false;
|
||||
return 1;
|
||||
|
||||
} else {
|
||||
@@ -310,7 +324,7 @@ UBX::receive(unsigned timeout)
|
||||
|
||||
/* abort after timeout if no useful packets received */
|
||||
if (time_started + timeout * 1000 < hrt_absolute_time()) {
|
||||
warnx("ubx: timeout - no useful messages");
|
||||
warnx("timeout - no useful messages");
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
@@ -383,7 +397,7 @@ UBX::parse_char(uint8_t b)
|
||||
return 1; // message received successfully
|
||||
|
||||
} else {
|
||||
warnx("ubx: checksum wrong");
|
||||
warnx("checksum wrong");
|
||||
decode_init();
|
||||
return -1;
|
||||
}
|
||||
@@ -392,7 +406,7 @@ UBX::parse_char(uint8_t b)
|
||||
_rx_count++;
|
||||
|
||||
} else {
|
||||
warnx("ubx: buffer full");
|
||||
warnx("buffer full");
|
||||
decode_init();
|
||||
return -1;
|
||||
}
|
||||
@@ -431,6 +445,7 @@ UBX::handle_message()
|
||||
|
||||
_rate_count_lat_lon++;
|
||||
|
||||
_got_posllh = true;
|
||||
ret = 1;
|
||||
break;
|
||||
}
|
||||
@@ -440,8 +455,8 @@ UBX::handle_message()
|
||||
gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
|
||||
|
||||
_gps_position->fix_type = packet->gpsFix;
|
||||
_gps_position->s_variance_m_s = packet->sAcc;
|
||||
_gps_position->p_variance_m = packet->pAcc;
|
||||
_gps_position->s_variance_m_s = (float)packet->sAcc * 1e-2f; // from cm/s to m/s
|
||||
_gps_position->p_variance_m = (float)packet->pAcc * 1e-2f; // from cm to m
|
||||
_gps_position->timestamp_variance = hrt_absolute_time();
|
||||
|
||||
ret = 1;
|
||||
@@ -475,6 +490,7 @@ UBX::handle_message()
|
||||
_gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
|
||||
_gps_position->timestamp_time = hrt_absolute_time();
|
||||
|
||||
_got_timeutc = true;
|
||||
ret = 1;
|
||||
break;
|
||||
}
|
||||
@@ -550,6 +566,7 @@ UBX::handle_message()
|
||||
|
||||
_rate_count_vel++;
|
||||
|
||||
_got_velned = true;
|
||||
ret = 1;
|
||||
break;
|
||||
}
|
||||
@@ -566,6 +583,24 @@ UBX::handle_message()
|
||||
break;
|
||||
}
|
||||
|
||||
case UBX_CLASS_MON: {
|
||||
switch (_message_id) {
|
||||
case UBX_MESSAGE_MON_HW: {
|
||||
|
||||
struct gps_bin_mon_hw_packet *p = (struct gps_bin_mon_hw_packet*) _rx_buffer;
|
||||
|
||||
_gps_position->noise_per_ms = p->noisePerMS;
|
||||
_gps_position->jamming_indicator = p->jamInd;
|
||||
|
||||
ret = 1;
|
||||
break;
|
||||
}
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
+29
-2
@@ -56,6 +56,7 @@
|
||||
//#define UBX_CLASS_RXM 0x02
|
||||
#define UBX_CLASS_ACK 0x05
|
||||
#define UBX_CLASS_CFG 0x06
|
||||
#define UBX_CLASS_MON 0x0A
|
||||
|
||||
/* MessageIDs (the ones that are used) */
|
||||
#define UBX_MESSAGE_NAV_POSLLH 0x02
|
||||
@@ -72,6 +73,8 @@
|
||||
#define UBX_MESSAGE_CFG_RATE 0x08
|
||||
#define UBX_MESSAGE_CFG_NAV5 0x24
|
||||
|
||||
#define UBX_MESSAGE_MON_HW 0x09
|
||||
|
||||
#define UBX_CFG_PRT_LENGTH 20
|
||||
#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
|
||||
#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
|
||||
@@ -210,6 +213,27 @@ typedef struct {
|
||||
uint8_t ck_b;
|
||||
} gps_bin_nav_velned_packet_t;
|
||||
|
||||
struct gps_bin_mon_hw_packet {
|
||||
uint32_t pinSel;
|
||||
uint32_t pinBank;
|
||||
uint32_t pinDir;
|
||||
uint32_t pinVal;
|
||||
uint16_t noisePerMS;
|
||||
uint16_t agcCnt;
|
||||
uint8_t aStatus;
|
||||
uint8_t aPower;
|
||||
uint8_t flags;
|
||||
uint8_t __reserved1;
|
||||
uint32_t usedMask;
|
||||
uint8_t VP[25];
|
||||
uint8_t jamInd;
|
||||
uint16_t __reserved3;
|
||||
uint32_t pinIrq;
|
||||
uint32_t pulLH;
|
||||
uint32_t pullL;
|
||||
};
|
||||
|
||||
|
||||
//typedef struct {
|
||||
// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */
|
||||
// int16_t week; /**< Measurement GPS week number */
|
||||
@@ -319,7 +343,7 @@ typedef enum {
|
||||
//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
|
||||
#pragma pack(pop)
|
||||
|
||||
#define RECV_BUFFER_SIZE 500 //The NAV-SOL messages really need such a big buffer
|
||||
#define RECV_BUFFER_SIZE 300 //The NAV-SOL messages really need such a big buffer
|
||||
|
||||
class UBX : public GPS_Helper
|
||||
{
|
||||
@@ -373,6 +397,9 @@ private:
|
||||
struct vehicle_gps_position_s *_gps_position;
|
||||
bool _configured;
|
||||
bool _waiting_for_ack;
|
||||
bool _got_posllh;
|
||||
bool _got_velned;
|
||||
bool _got_timeutc;
|
||||
uint8_t _message_class_needed;
|
||||
uint8_t _message_id_needed;
|
||||
ubx_decode_state_t _decode_state;
|
||||
@@ -383,7 +410,7 @@ private:
|
||||
uint8_t _message_class;
|
||||
uint8_t _message_id;
|
||||
unsigned _payload_size;
|
||||
uint8_t _disable_cmd_last;
|
||||
hrt_abstime _disable_cmd_last;
|
||||
};
|
||||
|
||||
#endif /* UBX_H_ */
|
||||
|
||||
@@ -122,7 +122,7 @@ private:
|
||||
actuator_controls_s _controls;
|
||||
|
||||
static void task_main_trampoline(int argc, char *argv[]);
|
||||
void task_main() __attribute__((noreturn));
|
||||
void task_main();
|
||||
|
||||
static int control_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
|
||||
@@ -158,6 +158,7 @@ private:
|
||||
int _class_instance;
|
||||
|
||||
orb_advert_t _mag_topic;
|
||||
orb_advert_t _subsystem_pub;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
@@ -324,7 +325,9 @@ HMC5883::HMC5883(int bus) :
|
||||
_reports(nullptr),
|
||||
_range_scale(0), /* default range scale from counts to gauss */
|
||||
_range_ga(1.3f),
|
||||
_collect_phase(false),
|
||||
_mag_topic(-1),
|
||||
_subsystem_pub(-1),
|
||||
_class_instance(-1),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
|
||||
@@ -1137,13 +1140,12 @@ int HMC5883::check_calibration()
|
||||
true,
|
||||
_calibrated,
|
||||
SUBSYSTEM_TYPE_MAG};
|
||||
static orb_advert_t pub = -1;
|
||||
|
||||
if (!(_pub_blocked)) {
|
||||
if (pub > 0) {
|
||||
orb_publish(ORB_ID(subsystem_info), pub, &info);
|
||||
if (_subsystem_pub > 0) {
|
||||
orb_publish(ORB_ID(subsystem_info), _subsystem_pub, &info);
|
||||
} else {
|
||||
pub = orb_advertise(ORB_ID(subsystem_info), &info);
|
||||
_subsystem_pub = orb_advertise(ORB_ID(subsystem_info), &info);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -51,6 +51,8 @@
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
/* The board is very roughly 5 deg warmer than the surrounding air */
|
||||
#define BOARD_TEMP_OFFSET_DEG 5
|
||||
|
||||
@@ -62,7 +64,6 @@ static int _airspeed_sub = -1;
|
||||
static int _esc_sub = -1;
|
||||
|
||||
static orb_advert_t _esc_pub;
|
||||
struct esc_status_s _esc;
|
||||
|
||||
static bool _home_position_set = false;
|
||||
static double _home_lat = 0.0d;
|
||||
@@ -82,8 +83,6 @@ init_sub_messages(void)
|
||||
void
|
||||
init_pub_messages(void)
|
||||
{
|
||||
memset(&_esc, 0, sizeof(_esc));
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
|
||||
}
|
||||
|
||||
void
|
||||
@@ -106,23 +105,26 @@ publish_gam_message(const uint8_t *buffer)
|
||||
size_t size = sizeof(msg);
|
||||
memset(&msg, 0, size);
|
||||
memcpy(&msg, buffer, size);
|
||||
struct esc_status_s esc;
|
||||
memset(&esc, 0, sizeof(esc));
|
||||
|
||||
// Publish it.
|
||||
esc.timestamp = hrt_absolute_time();
|
||||
esc.esc_count = 1;
|
||||
esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
|
||||
|
||||
esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
|
||||
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
|
||||
esc.esc[0].esc_temperature = msg.temperature1 - 20;
|
||||
esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
|
||||
esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
|
||||
|
||||
/* announce the esc if needed, just publish else */
|
||||
if (_esc_pub > 0) {
|
||||
orb_publish(ORB_ID(esc_status), _esc_pub, &_esc);
|
||||
orb_publish(ORB_ID(esc_status), _esc_pub, &esc);
|
||||
} else {
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &esc);
|
||||
}
|
||||
|
||||
// Publish it.
|
||||
_esc.esc_count = 1;
|
||||
_esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
|
||||
|
||||
_esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
|
||||
_esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
|
||||
_esc.esc[0].esc_temperature = msg.temperature1 - 20;
|
||||
_esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
|
||||
_esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -34,6 +34,9 @@
|
||||
/**
|
||||
* @file l3gd20.cpp
|
||||
* Driver for the ST L3GD20 MEMS gyro connected via SPI.
|
||||
*
|
||||
* Note: With the exception of the self-test feature, the ST L3G4200D is
|
||||
* also supported by this driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
@@ -89,9 +92,11 @@ static const int ERROR = -1;
|
||||
#define ADDR_WHO_AM_I 0x0F
|
||||
#define WHO_I_AM_H 0xD7
|
||||
#define WHO_I_AM 0xD4
|
||||
#define WHO_I_AM_L3G4200D 0xD3 /* for L3G4200D */
|
||||
|
||||
#define ADDR_CTRL_REG1 0x20
|
||||
#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
|
||||
|
||||
/* keep lowpass low to avoid noise issues */
|
||||
#define RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
|
||||
#define RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
|
||||
@@ -166,9 +171,14 @@ static const int ERROR = -1;
|
||||
#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
|
||||
|
||||
#define L3GD20_DEFAULT_RATE 760
|
||||
#define L3G4200D_DEFAULT_RATE 800
|
||||
#define L3GD20_DEFAULT_RANGE_DPS 2000
|
||||
#define L3GD20_DEFAULT_FILTER_FREQ 30
|
||||
|
||||
#ifndef SENSOR_BOARD_ROTATION_DEFAULT
|
||||
#define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG
|
||||
#endif
|
||||
|
||||
extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
|
||||
|
||||
class L3GD20 : public device::SPI
|
||||
@@ -216,6 +226,9 @@ private:
|
||||
math::LowPassFilter2p _gyro_filter_y;
|
||||
math::LowPassFilter2p _gyro_filter_z;
|
||||
|
||||
/* true if an L3G4200D is detected */
|
||||
bool _is_l3g4200d;
|
||||
|
||||
/**
|
||||
* Start automatic measurement.
|
||||
*/
|
||||
@@ -324,14 +337,15 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
|
||||
_gyro_topic(-1),
|
||||
_class_instance(-1),
|
||||
_current_rate(0),
|
||||
_orientation(SENSOR_BOARD_ROTATION_270_DEG),
|
||||
_orientation(SENSOR_BOARD_ROTATION_DEFAULT),
|
||||
_read(0),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read")),
|
||||
_reschedules(perf_alloc(PC_COUNT, "l3gd20_reschedules")),
|
||||
_errors(perf_alloc(PC_COUNT, "l3gd20_errors")),
|
||||
_gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
|
||||
_gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
|
||||
_gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ)
|
||||
_gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
|
||||
_is_l3g4200d(false)
|
||||
{
|
||||
// enable debug() calls
|
||||
_debug_enabled = true;
|
||||
@@ -413,14 +427,7 @@ L3GD20::probe()
|
||||
/* verify that the device is attached and functioning, accept L3GD20 and L3GD20H */
|
||||
if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
_orientation = SENSOR_BOARD_ROTATION_270_DEG;
|
||||
#elif CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
_orientation = SENSOR_BOARD_ROTATION_270_DEG;
|
||||
#else
|
||||
#error This driver needs a board selection, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
#endif
|
||||
|
||||
_orientation = SENSOR_BOARD_ROTATION_DEFAULT;
|
||||
success = true;
|
||||
}
|
||||
|
||||
@@ -430,6 +437,13 @@ L3GD20::probe()
|
||||
success = true;
|
||||
}
|
||||
|
||||
/* Detect the L3G4200D used on AeroCore */
|
||||
if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_L3G4200D) {
|
||||
_is_l3g4200d = true;
|
||||
_orientation = SENSOR_BOARD_ROTATION_DEFAULT;
|
||||
success = true;
|
||||
}
|
||||
|
||||
if (success)
|
||||
return OK;
|
||||
|
||||
@@ -502,6 +516,9 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
/* set default/max polling rate */
|
||||
case SENSOR_POLLRATE_MAX:
|
||||
case SENSOR_POLLRATE_DEFAULT:
|
||||
if (_is_l3g4200d) {
|
||||
return ioctl(filp, SENSORIOCSPOLLRATE, L3G4200D_DEFAULT_RATE);
|
||||
}
|
||||
return ioctl(filp, SENSORIOCSPOLLRATE, L3GD20_DEFAULT_RATE);
|
||||
|
||||
/* adjust to a legal polling interval in Hz */
|
||||
@@ -683,23 +700,26 @@ L3GD20::set_samplerate(unsigned frequency)
|
||||
uint8_t bits = REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
|
||||
|
||||
if (frequency == 0)
|
||||
frequency = 760;
|
||||
frequency = _is_l3g4200d ? 800 : 760;
|
||||
|
||||
/* use limits good for H or non-H models */
|
||||
/*
|
||||
* Use limits good for H or non-H models. Rates are slightly different
|
||||
* for L3G4200D part but register settings are the same.
|
||||
*/
|
||||
if (frequency <= 100) {
|
||||
_current_rate = 95;
|
||||
_current_rate = _is_l3g4200d ? 100 : 95;
|
||||
bits |= RATE_95HZ_LP_25HZ;
|
||||
|
||||
} else if (frequency <= 200) {
|
||||
_current_rate = 190;
|
||||
_current_rate = _is_l3g4200d ? 200 : 190;
|
||||
bits |= RATE_190HZ_LP_50HZ;
|
||||
|
||||
} else if (frequency <= 400) {
|
||||
_current_rate = 380;
|
||||
_current_rate = _is_l3g4200d ? 400 : 380;
|
||||
bits |= RATE_380HZ_LP_50HZ;
|
||||
|
||||
} else if (frequency <= 800) {
|
||||
_current_rate = 760;
|
||||
_current_rate = _is_l3g4200d ? 800 : 760;
|
||||
bits |= RATE_760HZ_LP_50HZ;
|
||||
} else {
|
||||
return -EINVAL;
|
||||
@@ -772,7 +792,7 @@ L3GD20::reset()
|
||||
* callback fast enough to not miss data. */
|
||||
write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
|
||||
|
||||
set_samplerate(0); // 760Hz
|
||||
set_samplerate(0); // 760Hz or 800Hz
|
||||
set_range(L3GD20_DEFAULT_RANGE_DPS);
|
||||
set_driver_lowpass_filter(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ);
|
||||
|
||||
@@ -971,7 +991,7 @@ start()
|
||||
errx(0, "already started");
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new L3GD20(1 /* SPI bus 1 */, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
|
||||
g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
|
||||
|
||||
if (g_dev == nullptr)
|
||||
goto fail;
|
||||
|
||||
@@ -880,7 +880,7 @@ LSM303D::mag_read(struct file *filp, char *buffer, size_t buflen)
|
||||
|
||||
/* manual measurement */
|
||||
_mag_reports->flush();
|
||||
measure();
|
||||
_mag->measure();
|
||||
|
||||
/* measurement will have generated a report, copy it out */
|
||||
if (_mag_reports->get(mrb))
|
||||
@@ -1793,7 +1793,7 @@ start()
|
||||
errx(0, "already started");
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new LSM303D(1 /* SPI dev 1 */, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
|
||||
g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
warnx("failed instantiating LSM303D obj");
|
||||
|
||||
@@ -92,8 +92,20 @@
|
||||
#define MOTOR_SPINUP_COUNTER 30
|
||||
#define ESC_UORB_PUBLISH_DELAY 500000
|
||||
|
||||
|
||||
|
||||
struct MotorData_t {
|
||||
unsigned int Version; // the version of the BL (0 = old)
|
||||
unsigned int SetPoint; // written by attitude controller
|
||||
unsigned int SetPointLowerBits; // for higher Resolution of new BLs
|
||||
float SetPoint_PX4; // Values from PX4
|
||||
unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
|
||||
unsigned int ReadMode; // select data to read
|
||||
unsigned short RawPwmValue; // length of PWM pulse
|
||||
// the following bytes must be exactly in that order!
|
||||
unsigned int Current; // in 0.1 A steps, read back from BL
|
||||
unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
|
||||
unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
|
||||
unsigned int RoundCount;
|
||||
};
|
||||
|
||||
class MK : public device::I2C
|
||||
{
|
||||
@@ -154,8 +166,10 @@ private:
|
||||
|
||||
actuator_controls_s _controls;
|
||||
|
||||
MotorData_t Motor[MAX_MOTORS];
|
||||
|
||||
static void task_main_trampoline(int argc, char *argv[]);
|
||||
void task_main() __attribute__((noreturn));
|
||||
void task_main();
|
||||
|
||||
static int control_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
@@ -195,24 +209,6 @@ const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
int addrTranslator[] = {0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
struct MotorData_t {
|
||||
unsigned int Version; // the version of the BL (0 = old)
|
||||
unsigned int SetPoint; // written by attitude controller
|
||||
unsigned int SetPointLowerBits; // for higher Resolution of new BLs
|
||||
float SetPoint_PX4; // Values from PX4
|
||||
unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
|
||||
unsigned int ReadMode; // select data to read
|
||||
unsigned short RawPwmValue; // length of PWM pulse
|
||||
// the following bytes must be exactly in that order!
|
||||
unsigned int Current; // in 0.1 A steps, read back from BL
|
||||
unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
|
||||
unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
|
||||
unsigned int RoundCount;
|
||||
};
|
||||
|
||||
MotorData_t Motor[MAX_MOTORS];
|
||||
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
|
||||
@@ -1380,7 +1380,6 @@ MPU6000_gyro::init()
|
||||
|
||||
_gyro_class_instance = register_class_devname(GYRO_DEVICE_PATH);
|
||||
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
@@ -526,6 +526,7 @@ void
|
||||
MS5611::cycle()
|
||||
{
|
||||
int ret;
|
||||
unsigned dummy;
|
||||
|
||||
/* collection phase? */
|
||||
if (_collect_phase) {
|
||||
@@ -542,6 +543,8 @@ MS5611::cycle()
|
||||
} else {
|
||||
//log("collection error %d", ret);
|
||||
}
|
||||
/* issue a reset command to the sensor */
|
||||
_interface->ioctl(IOCTL_RESET, dummy);
|
||||
/* reset the collection state machine and try again */
|
||||
start_cycle();
|
||||
return;
|
||||
@@ -573,6 +576,8 @@ MS5611::cycle()
|
||||
ret = measure();
|
||||
if (ret != OK) {
|
||||
//log("measure error %d", ret);
|
||||
/* issue a reset command to the sensor */
|
||||
_interface->ioctl(IOCTL_RESET, dummy);
|
||||
/* reset the collection state machine and try again */
|
||||
start_cycle();
|
||||
return;
|
||||
@@ -748,8 +753,8 @@ MS5611::print_info()
|
||||
printf("TEMP: %d\n", _TEMP);
|
||||
printf("SENS: %lld\n", _SENS);
|
||||
printf("OFF: %lld\n", _OFF);
|
||||
printf("P: %.3f\n", _P);
|
||||
printf("T: %.3f\n", _T);
|
||||
printf("P: %.3f\n", (double)_P);
|
||||
printf("T: %.3f\n", (double)_T);
|
||||
printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
|
||||
|
||||
printf("factory_setup %u\n", _prom.factory_setup);
|
||||
|
||||
@@ -117,7 +117,7 @@ private:
|
||||
device::Device *
|
||||
MS5611_spi_interface(ms5611::prom_u &prom_buf)
|
||||
{
|
||||
return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
|
||||
return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
|
||||
}
|
||||
|
||||
MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
|
||||
|
||||
@@ -0,0 +1,6 @@
|
||||
#
|
||||
# PCA8574 driver for RGB LED
|
||||
#
|
||||
|
||||
MODULE_COMMAND = pca8574
|
||||
SRCS = pca8574.cpp
|
||||
@@ -0,0 +1,554 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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 pca8574.cpp
|
||||
*
|
||||
* Driver for an 8 I/O controller (PC8574) connected via I2C.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <ctype.h>
|
||||
|
||||
#include <nuttx/wqueue.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include <drivers/drv_io_expander.h>
|
||||
|
||||
#define PCA8574_ONTIME 120
|
||||
#define PCA8574_OFFTIME 120
|
||||
#define PCA8574_DEVICE_PATH "/dev/pca8574"
|
||||
|
||||
#define ADDR 0x20 ///< I2C adress of PCA8574 (default, A0-A2 pulled to GND)
|
||||
|
||||
class PCA8574 : public device::I2C
|
||||
{
|
||||
public:
|
||||
PCA8574(int bus, int pca8574);
|
||||
virtual ~PCA8574();
|
||||
|
||||
|
||||
virtual int init();
|
||||
virtual int probe();
|
||||
virtual int info();
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
bool is_running() { return _running; }
|
||||
|
||||
private:
|
||||
work_s _work;
|
||||
|
||||
uint8_t _values_out;
|
||||
uint8_t _values_in;
|
||||
uint8_t _blinking;
|
||||
uint8_t _blink_phase;
|
||||
|
||||
enum IOX_MODE _mode;
|
||||
bool _running;
|
||||
int _led_interval;
|
||||
bool _should_run;
|
||||
bool _update_out;
|
||||
int _counter;
|
||||
|
||||
static void led_trampoline(void *arg);
|
||||
void led();
|
||||
|
||||
int send_led_enable(uint8_t arg);
|
||||
int send_led_values();
|
||||
|
||||
int get(uint8_t &vals);
|
||||
};
|
||||
|
||||
/* for now, we only support one PCA8574 */
|
||||
namespace
|
||||
{
|
||||
PCA8574 *g_pca8574;
|
||||
}
|
||||
|
||||
void pca8574_usage();
|
||||
|
||||
extern "C" __EXPORT int pca8574_main(int argc, char *argv[]);
|
||||
|
||||
PCA8574::PCA8574(int bus, int pca8574) :
|
||||
I2C("pca8574", PCA8574_DEVICE_PATH, bus, pca8574, 100000),
|
||||
_values_out(0),
|
||||
_values_in(0),
|
||||
_blinking(0),
|
||||
_blink_phase(0),
|
||||
_mode(IOX_MODE_OFF),
|
||||
_running(false),
|
||||
_led_interval(80),
|
||||
_should_run(false),
|
||||
_update_out(false),
|
||||
_counter(0)
|
||||
{
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
}
|
||||
|
||||
PCA8574::~PCA8574()
|
||||
{
|
||||
}
|
||||
|
||||
int
|
||||
PCA8574::init()
|
||||
{
|
||||
int ret;
|
||||
ret = I2C::init();
|
||||
|
||||
if (ret != OK) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
PCA8574::probe()
|
||||
{
|
||||
uint8_t val;
|
||||
return get(val);
|
||||
}
|
||||
|
||||
int
|
||||
PCA8574::info()
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
PCA8574::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = ENOTTY;
|
||||
|
||||
switch (cmd) {
|
||||
case IOX_SET_VALUE ...(IOX_SET_VALUE + 8): {
|
||||
// set the specified on / off state
|
||||
uint8_t position = (1 << (cmd - IOX_SET_VALUE));
|
||||
uint8_t prev = _values_out;
|
||||
|
||||
if (arg) {
|
||||
_values_out |= position;
|
||||
|
||||
} else {
|
||||
_values_out &= ~(position);
|
||||
}
|
||||
|
||||
if (_values_out != prev) {
|
||||
if (_values_out) {
|
||||
_mode = IOX_MODE_ON;
|
||||
}
|
||||
send_led_values();
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
case IOX_SET_MASK:
|
||||
send_led_enable(arg);
|
||||
return OK;
|
||||
|
||||
case IOX_GET_MASK: {
|
||||
uint8_t val;
|
||||
ret = get(val);
|
||||
|
||||
if (ret == OK) {
|
||||
return val;
|
||||
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
case IOX_SET_MODE:
|
||||
|
||||
if (_mode != (IOX_MODE)arg) {
|
||||
|
||||
switch ((IOX_MODE)arg) {
|
||||
case IOX_MODE_OFF:
|
||||
_values_out = 0xFF;
|
||||
break;
|
||||
|
||||
case IOX_MODE_ON:
|
||||
_values_out = 0;
|
||||
break;
|
||||
|
||||
case IOX_MODE_TEST_OUT:
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
_mode = (IOX_MODE)arg;
|
||||
send_led_values();
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
||||
default:
|
||||
// see if the parent class can make any use of it
|
||||
ret = CDev::ioctl(filp, cmd, arg);
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
PCA8574::led_trampoline(void *arg)
|
||||
{
|
||||
PCA8574 *rgbl = reinterpret_cast<PCA8574 *>(arg);
|
||||
|
||||
rgbl->led();
|
||||
}
|
||||
|
||||
/**
|
||||
* Main loop function
|
||||
*/
|
||||
void
|
||||
PCA8574::led()
|
||||
{
|
||||
if (_mode == IOX_MODE_TEST_OUT) {
|
||||
|
||||
// we count only seven states
|
||||
_counter &= 0xF;
|
||||
_counter++;
|
||||
|
||||
for (int i = 0; i < 8; i++) {
|
||||
if (i < _counter) {
|
||||
_values_out |= (1 << i);
|
||||
|
||||
} else {
|
||||
_values_out &= ~(1 << i);
|
||||
}
|
||||
}
|
||||
|
||||
_update_out = true;
|
||||
_should_run = true;
|
||||
} else if (_mode == IOX_MODE_OFF) {
|
||||
_update_out = true;
|
||||
_should_run = false;
|
||||
} else {
|
||||
|
||||
// Any of the normal modes
|
||||
if (_blinking > 0) {
|
||||
/* we need to be running to blink */
|
||||
_should_run = true;
|
||||
} else {
|
||||
_should_run = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (_update_out) {
|
||||
uint8_t msg;
|
||||
|
||||
if (_blinking) {
|
||||
msg = (_values_out & _blinking & _blink_phase);
|
||||
|
||||
// wipe out all positions that are marked as blinking
|
||||
msg &= ~(_blinking);
|
||||
|
||||
// fill blink positions
|
||||
msg |= ((_blink_phase) ? _blinking : 0);
|
||||
|
||||
_blink_phase = !_blink_phase;
|
||||
} else {
|
||||
msg = _values_out;
|
||||
}
|
||||
|
||||
int ret = transfer(&msg, sizeof(msg), nullptr, 0);
|
||||
|
||||
if (!ret) {
|
||||
_update_out = false;
|
||||
}
|
||||
}
|
||||
|
||||
// check if any activity remains, else stp
|
||||
if (!_should_run) {
|
||||
_running = false;
|
||||
return;
|
||||
}
|
||||
|
||||
// re-queue ourselves to run again later
|
||||
_running = true;
|
||||
work_queue(LPWORK, &_work, (worker_t)&PCA8574::led_trampoline, this, _led_interval);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sent ENABLE flag to LED driver
|
||||
*/
|
||||
int
|
||||
PCA8574::send_led_enable(uint8_t arg)
|
||||
{
|
||||
|
||||
int ret = transfer(&arg, sizeof(arg), nullptr, 0);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* Send 8 outputs
|
||||
*/
|
||||
int
|
||||
PCA8574::send_led_values()
|
||||
{
|
||||
_update_out = true;
|
||||
|
||||
// if not active, kick it
|
||||
if (!_running) {
|
||||
_running = true;
|
||||
work_queue(LPWORK, &_work, (worker_t)&PCA8574::led_trampoline, this, 1);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
PCA8574::get(uint8_t &vals)
|
||||
{
|
||||
uint8_t result;
|
||||
int ret;
|
||||
|
||||
ret = transfer(nullptr, 0, &result, 1);
|
||||
|
||||
if (ret == OK) {
|
||||
_values_in = result;
|
||||
vals = result;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
pca8574_usage()
|
||||
{
|
||||
warnx("missing command: try 'start', 'test', 'info', 'off', 'stop', 'val 0 1'");
|
||||
warnx("options:");
|
||||
warnx(" -b i2cbus (%d)", PX4_I2C_BUS_LED);
|
||||
warnx(" -a addr (0x%x)", ADDR);
|
||||
}
|
||||
|
||||
int
|
||||
pca8574_main(int argc, char *argv[])
|
||||
{
|
||||
int i2cdevice = -1;
|
||||
int pca8574adr = ADDR; // 7bit
|
||||
|
||||
int ch;
|
||||
|
||||
// jump over start/off/etc and look at options first
|
||||
while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
|
||||
switch (ch) {
|
||||
case 'a':
|
||||
pca8574adr = strtol(optarg, NULL, 0);
|
||||
break;
|
||||
|
||||
case 'b':
|
||||
i2cdevice = strtol(optarg, NULL, 0);
|
||||
break;
|
||||
|
||||
default:
|
||||
pca8574_usage();
|
||||
exit(0);
|
||||
}
|
||||
}
|
||||
|
||||
if (optind >= argc) {
|
||||
pca8574_usage();
|
||||
exit(1);
|
||||
}
|
||||
|
||||
const char *verb = argv[optind];
|
||||
|
||||
int fd;
|
||||
int ret;
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
if (g_pca8574 != nullptr) {
|
||||
errx(1, "already started");
|
||||
}
|
||||
|
||||
if (i2cdevice == -1) {
|
||||
// try the external bus first
|
||||
i2cdevice = PX4_I2C_BUS_EXPANSION;
|
||||
g_pca8574 = new PCA8574(PX4_I2C_BUS_EXPANSION, pca8574adr);
|
||||
|
||||
if (g_pca8574 != nullptr && OK != g_pca8574->init()) {
|
||||
delete g_pca8574;
|
||||
g_pca8574 = nullptr;
|
||||
}
|
||||
|
||||
if (g_pca8574 == nullptr) {
|
||||
// fall back to default bus
|
||||
if (PX4_I2C_BUS_LED == PX4_I2C_BUS_EXPANSION) {
|
||||
errx(1, "init failed");
|
||||
}
|
||||
|
||||
i2cdevice = PX4_I2C_BUS_LED;
|
||||
}
|
||||
}
|
||||
|
||||
if (g_pca8574 == nullptr) {
|
||||
g_pca8574 = new PCA8574(i2cdevice, pca8574adr);
|
||||
|
||||
if (g_pca8574 == nullptr) {
|
||||
errx(1, "new failed");
|
||||
}
|
||||
|
||||
if (OK != g_pca8574->init()) {
|
||||
delete g_pca8574;
|
||||
g_pca8574 = nullptr;
|
||||
errx(1, "init failed");
|
||||
}
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
// need the driver past this point
|
||||
if (g_pca8574 == nullptr) {
|
||||
warnx("not started, run pca8574 start");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "test")) {
|
||||
fd = open(PCA8574_DEVICE_PATH, 0);
|
||||
|
||||
if (fd == -1) {
|
||||
errx(1, "Unable to open " PCA8574_DEVICE_PATH);
|
||||
}
|
||||
|
||||
ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_TEST_OUT);
|
||||
|
||||
close(fd);
|
||||
exit(ret);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "info")) {
|
||||
g_pca8574->info();
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "off")) {
|
||||
fd = open(PCA8574_DEVICE_PATH, 0);
|
||||
|
||||
if (fd < 0) {
|
||||
errx(1, "Unable to open " PCA8574_DEVICE_PATH);
|
||||
}
|
||||
|
||||
ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_OFF);
|
||||
close(fd);
|
||||
exit(ret);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
fd = open(PCA8574_DEVICE_PATH, 0);
|
||||
|
||||
if (fd == -1) {
|
||||
errx(1, "Unable to open " PCA8574_DEVICE_PATH);
|
||||
}
|
||||
|
||||
ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_OFF);
|
||||
close(fd);
|
||||
|
||||
// wait until we're not running any more
|
||||
for (unsigned i = 0; i < 15; i++) {
|
||||
if (!g_pca8574->is_running()) {
|
||||
break;
|
||||
}
|
||||
|
||||
usleep(50000);
|
||||
printf(".");
|
||||
fflush(stdout);
|
||||
}
|
||||
printf("\n");
|
||||
fflush(stdout);
|
||||
|
||||
if (!g_pca8574->is_running()) {
|
||||
delete g_pca8574;
|
||||
g_pca8574 = nullptr;
|
||||
exit(0);
|
||||
} else {
|
||||
warnx("stop failed.");
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "val")) {
|
||||
if (argc < 4) {
|
||||
errx(1, "Usage: pca8574 val <channel> <0 or 1>");
|
||||
}
|
||||
|
||||
fd = open(PCA8574_DEVICE_PATH, 0);
|
||||
|
||||
if (fd == -1) {
|
||||
errx(1, "Unable to open " PCA8574_DEVICE_PATH);
|
||||
}
|
||||
|
||||
unsigned channel = strtol(argv[2], NULL, 0);
|
||||
unsigned val = strtol(argv[3], NULL, 0);
|
||||
|
||||
if (channel < 8) {
|
||||
ret = ioctl(fd, (IOX_SET_VALUE + channel), val);
|
||||
} else {
|
||||
ret = -1;
|
||||
}
|
||||
close(fd);
|
||||
exit(ret);
|
||||
}
|
||||
|
||||
pca8574_usage();
|
||||
exit(0);
|
||||
}
|
||||
+250
-112
@@ -92,6 +92,7 @@ public:
|
||||
MODE_2PWM,
|
||||
MODE_4PWM,
|
||||
MODE_6PWM,
|
||||
MODE_8PWM,
|
||||
};
|
||||
PX4FMU();
|
||||
virtual ~PX4FMU();
|
||||
@@ -113,6 +114,9 @@ private:
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
static const unsigned _max_actuators = 6;
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
static const unsigned _max_actuators = 8;
|
||||
#endif
|
||||
|
||||
Mode _mode;
|
||||
unsigned _pwm_default_rate;
|
||||
@@ -120,19 +124,25 @@ private:
|
||||
uint32_t _pwm_alt_rate_channels;
|
||||
unsigned _current_update_rate;
|
||||
int _task;
|
||||
int _t_actuators;
|
||||
int _t_actuator_armed;
|
||||
orb_advert_t _t_outputs;
|
||||
int _armed_sub;
|
||||
orb_advert_t _outputs_pub;
|
||||
actuator_armed_s _armed;
|
||||
unsigned _num_outputs;
|
||||
bool _primary_pwm_device;
|
||||
|
||||
volatile bool _task_should_exit;
|
||||
bool _armed;
|
||||
bool _servo_armed;
|
||||
bool _pwm_on;
|
||||
|
||||
MixerGroup *_mixers;
|
||||
|
||||
actuator_controls_s _controls;
|
||||
uint32_t _groups_required;
|
||||
uint32_t _groups_subscribed;
|
||||
int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS];
|
||||
actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS];
|
||||
orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS];
|
||||
pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS];
|
||||
unsigned _poll_fds_num;
|
||||
|
||||
pwm_limit_t _pwm_limit;
|
||||
uint16_t _failsafe_pwm[_max_actuators];
|
||||
@@ -143,13 +153,13 @@ private:
|
||||
unsigned _num_disarmed_set;
|
||||
|
||||
static void task_main_trampoline(int argc, char *argv[]);
|
||||
void task_main() __attribute__((noreturn));
|
||||
void task_main();
|
||||
|
||||
static int control_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
uint8_t control_index,
|
||||
float &input);
|
||||
|
||||
void subscribe();
|
||||
int set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_rate);
|
||||
int pwm_ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
@@ -197,6 +207,20 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
|
||||
{GPIO_VDD_5V_HIPOWER_OC, 0, 0},
|
||||
{GPIO_VDD_5V_PERIPH_OC, 0, 0},
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
/* AeroCore breaks out User GPIOs on J11 */
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
|
||||
{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0},
|
||||
{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0},
|
||||
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0},
|
||||
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0},
|
||||
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0},
|
||||
{GPIO_GPIO8_INPUT, GPIO_GPIO8_OUTPUT, 0},
|
||||
{GPIO_GPIO9_INPUT, GPIO_GPIO9_OUTPUT, 0},
|
||||
{GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0},
|
||||
{GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0},
|
||||
#endif
|
||||
};
|
||||
|
||||
const unsigned PX4FMU::_ngpio = sizeof(PX4FMU::_gpio_tab) / sizeof(PX4FMU::_gpio_tab[0]);
|
||||
@@ -216,15 +240,18 @@ PX4FMU::PX4FMU() :
|
||||
_pwm_alt_rate_channels(0),
|
||||
_current_update_rate(0),
|
||||
_task(-1),
|
||||
_t_actuators(-1),
|
||||
_t_actuator_armed(-1),
|
||||
_t_outputs(0),
|
||||
_control_subs({-1}),
|
||||
_poll_fds_num(0),
|
||||
_armed_sub(-1),
|
||||
_outputs_pub(-1),
|
||||
_num_outputs(0),
|
||||
_primary_pwm_device(false),
|
||||
_task_should_exit(false),
|
||||
_armed(false),
|
||||
_servo_armed(false),
|
||||
_pwm_on(false),
|
||||
_mixers(nullptr),
|
||||
_groups_required(0),
|
||||
_groups_subscribed(0),
|
||||
_failsafe_pwm({0}),
|
||||
_disarmed_pwm({0}),
|
||||
_num_failsafe_set(0),
|
||||
@@ -235,6 +262,14 @@ PX4FMU::PX4FMU() :
|
||||
_max_pwm[i] = PWM_DEFAULT_MAX;
|
||||
}
|
||||
|
||||
_control_topics[0] = ORB_ID(actuator_controls_0);
|
||||
_control_topics[1] = ORB_ID(actuator_controls_1);
|
||||
_control_topics[2] = ORB_ID(actuator_controls_2);
|
||||
_control_topics[3] = ORB_ID(actuator_controls_3);
|
||||
|
||||
memset(_controls, 0, sizeof(_controls));
|
||||
memset(_poll_fds, 0, sizeof(_poll_fds));
|
||||
|
||||
_debug_enabled = true;
|
||||
}
|
||||
|
||||
@@ -365,6 +400,20 @@ PX4FMU::set_mode(Mode mode)
|
||||
|
||||
break;
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case MODE_8PWM: // AeroCore PWMs as 8 PWM outs
|
||||
debug("MODE_8PWM");
|
||||
/* default output rates */
|
||||
_pwm_default_rate = 50;
|
||||
_pwm_alt_rate = 50;
|
||||
_pwm_alt_rate_channels = 0;
|
||||
|
||||
/* XXX magic numbers */
|
||||
up_pwm_servo_init(0xff);
|
||||
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MODE_NONE:
|
||||
debug("MODE_NONE");
|
||||
|
||||
@@ -447,33 +496,43 @@ PX4FMU::set_pwm_alt_channels(uint32_t channels)
|
||||
return set_pwm_rate(channels, _pwm_default_rate, _pwm_alt_rate);
|
||||
}
|
||||
|
||||
void
|
||||
PX4FMU::subscribe()
|
||||
{
|
||||
/* subscribe/unsubscribe to required actuator control groups */
|
||||
uint32_t sub_groups = _groups_required & ~_groups_subscribed;
|
||||
uint32_t unsub_groups = _groups_subscribed & ~_groups_required;
|
||||
_poll_fds_num = 0;
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||
if (sub_groups & (1 << i)) {
|
||||
warnx("subscribe to actuator_controls_%d", i);
|
||||
_control_subs[i] = orb_subscribe(_control_topics[i]);
|
||||
}
|
||||
if (unsub_groups & (1 << i)) {
|
||||
warnx("unsubscribe from actuator_controls_%d", i);
|
||||
::close(_control_subs[i]);
|
||||
_control_subs[i] = -1;
|
||||
}
|
||||
|
||||
if (_control_subs[i] > 0) {
|
||||
_poll_fds[_poll_fds_num].fd = _control_subs[i];
|
||||
_poll_fds[_poll_fds_num].events = POLLIN;
|
||||
_poll_fds_num++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
PX4FMU::task_main()
|
||||
{
|
||||
/*
|
||||
* Subscribe to the appropriate PWM output topic based on whether we are the
|
||||
* primary PWM output or not.
|
||||
*/
|
||||
_t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
|
||||
ORB_ID(actuator_controls_1));
|
||||
/* force a reset of the update rate */
|
||||
_current_update_rate = 0;
|
||||
|
||||
_t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
|
||||
orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
|
||||
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
|
||||
|
||||
/* advertise the mixed control outputs */
|
||||
actuator_outputs_s outputs;
|
||||
memset(&outputs, 0, sizeof(outputs));
|
||||
/* advertise the mixed control outputs */
|
||||
_t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
|
||||
&outputs);
|
||||
|
||||
pollfd fds[2];
|
||||
fds[0].fd = _t_actuators;
|
||||
fds[0].events = POLLIN;
|
||||
fds[1].fd = _t_actuator_armed;
|
||||
fds[1].events = POLLIN;
|
||||
|
||||
#ifdef HRT_PPM_CHANNEL
|
||||
// rc input, published to ORB
|
||||
@@ -491,6 +550,12 @@ PX4FMU::task_main()
|
||||
|
||||
/* loop until killed */
|
||||
while (!_task_should_exit) {
|
||||
if (_groups_subscribed != _groups_required) {
|
||||
subscribe();
|
||||
_groups_subscribed = _groups_required;
|
||||
/* force setting update rate */
|
||||
_current_update_rate = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* Adjust actuator topic update rate to keep up with
|
||||
@@ -515,20 +580,23 @@ PX4FMU::task_main()
|
||||
}
|
||||
|
||||
debug("adjusted actuator update interval to %ums", update_rate_in_ms);
|
||||
orb_set_interval(_t_actuators, update_rate_in_ms);
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||
if (_control_subs[i] > 0) {
|
||||
orb_set_interval(_control_subs[i], update_rate_in_ms);
|
||||
}
|
||||
}
|
||||
|
||||
// set to current max rate, even if we are actually checking slower/faster
|
||||
_current_update_rate = max_rate;
|
||||
}
|
||||
|
||||
/* sleep waiting for data, stopping to check for PPM
|
||||
* input at 100Hz */
|
||||
int ret = ::poll(&fds[0], 2, CONTROL_INPUT_DROP_LIMIT_MS);
|
||||
* input at 50Hz */
|
||||
int ret = ::poll(_poll_fds, _poll_fds_num, CONTROL_INPUT_DROP_LIMIT_MS);
|
||||
|
||||
/* this would be bad... */
|
||||
if (ret < 0) {
|
||||
log("poll error %d", errno);
|
||||
usleep(1000000);
|
||||
continue;
|
||||
|
||||
} else if (ret == 0) {
|
||||
@@ -537,89 +605,100 @@ PX4FMU::task_main()
|
||||
|
||||
} else {
|
||||
|
||||
/* do we have a control update? */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
|
||||
/* get controls - must always do this to avoid spinning */
|
||||
orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1), _t_actuators, &_controls);
|
||||
|
||||
/* can we mix? */
|
||||
if (_mixers != nullptr) {
|
||||
|
||||
unsigned num_outputs;
|
||||
|
||||
switch (_mode) {
|
||||
case MODE_2PWM:
|
||||
num_outputs = 2;
|
||||
break;
|
||||
|
||||
case MODE_4PWM:
|
||||
num_outputs = 4;
|
||||
break;
|
||||
|
||||
case MODE_6PWM:
|
||||
num_outputs = 6;
|
||||
break;
|
||||
|
||||
default:
|
||||
num_outputs = 0;
|
||||
break;
|
||||
/* get controls for required topics */
|
||||
unsigned poll_id = 0;
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||
if (_control_subs[i] > 0) {
|
||||
if (_poll_fds[poll_id].revents & POLLIN) {
|
||||
orb_copy(_control_topics[i], _control_subs[i], &_controls[i]);
|
||||
}
|
||||
|
||||
/* do mixing */
|
||||
outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
|
||||
outputs.timestamp = hrt_absolute_time();
|
||||
|
||||
/* iterate actuators */
|
||||
for (unsigned i = 0; i < num_outputs; i++) {
|
||||
/* last resort: catch NaN, INF and out-of-band errors */
|
||||
if (i >= outputs.noutputs ||
|
||||
!isfinite(outputs.output[i]) ||
|
||||
outputs.output[i] < -1.0f ||
|
||||
outputs.output[i] > 1.0f) {
|
||||
/*
|
||||
* Value is NaN, INF or out of band - set to the minimum value.
|
||||
* This will be clearly visible on the servo status and will limit the risk of accidentally
|
||||
* spinning motors. It would be deadly in flight.
|
||||
*/
|
||||
outputs.output[i] = -1.0f;
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t pwm_limited[num_outputs];
|
||||
|
||||
pwm_limit_calc(_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
|
||||
|
||||
/* output to the servos */
|
||||
for (unsigned i = 0; i < num_outputs; i++) {
|
||||
up_pwm_servo_set(i, pwm_limited[i]);
|
||||
}
|
||||
|
||||
/* and publish for anyone that cares to see */
|
||||
orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs);
|
||||
poll_id++;
|
||||
}
|
||||
}
|
||||
|
||||
/* how about an arming update? */
|
||||
if (fds[1].revents & POLLIN) {
|
||||
actuator_armed_s aa;
|
||||
/* can we mix? */
|
||||
if (_mixers != nullptr) {
|
||||
|
||||
/* get new value */
|
||||
orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
|
||||
unsigned num_outputs;
|
||||
|
||||
/* update the armed status and check that we're not locked down */
|
||||
bool set_armed = aa.armed && !aa.lockdown;
|
||||
switch (_mode) {
|
||||
case MODE_2PWM:
|
||||
num_outputs = 2;
|
||||
break;
|
||||
|
||||
if (_armed != set_armed)
|
||||
_armed = set_armed;
|
||||
case MODE_4PWM:
|
||||
num_outputs = 4;
|
||||
break;
|
||||
|
||||
/* update PWM status if armed or if disarmed PWM values are set */
|
||||
bool pwm_on = (aa.armed || _num_disarmed_set > 0);
|
||||
case MODE_6PWM:
|
||||
num_outputs = 6;
|
||||
break;
|
||||
|
||||
if (_pwm_on != pwm_on) {
|
||||
_pwm_on = pwm_on;
|
||||
up_pwm_servo_arm(pwm_on);
|
||||
case MODE_8PWM:
|
||||
num_outputs = 8;
|
||||
break;
|
||||
default:
|
||||
num_outputs = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
/* do mixing */
|
||||
outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
|
||||
outputs.timestamp = hrt_absolute_time();
|
||||
|
||||
/* iterate actuators */
|
||||
for (unsigned i = 0; i < num_outputs; i++) {
|
||||
/* last resort: catch NaN and INF */
|
||||
if ((i >= outputs.noutputs) ||
|
||||
!isfinite(outputs.output[i])) {
|
||||
/*
|
||||
* Value is NaN, INF or out of band - set to the minimum value.
|
||||
* This will be clearly visible on the servo status and will limit the risk of accidentally
|
||||
* spinning motors. It would be deadly in flight.
|
||||
*/
|
||||
outputs.output[i] = -1.0f;
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t pwm_limited[num_outputs];
|
||||
|
||||
/* the PWM limit call takes care of out of band errors and constrains */
|
||||
pwm_limit_calc(_servo_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
|
||||
|
||||
/* output to the servos */
|
||||
for (unsigned i = 0; i < num_outputs; i++) {
|
||||
up_pwm_servo_set(i, pwm_limited[i]);
|
||||
}
|
||||
|
||||
/* publish mixed control outputs */
|
||||
if (_outputs_pub < 0) {
|
||||
_outputs_pub = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), &outputs);
|
||||
} else {
|
||||
|
||||
orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _outputs_pub, &outputs);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* check arming state */
|
||||
bool updated = false;
|
||||
orb_check(_armed_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed);
|
||||
|
||||
/* update the armed status and check that we're not locked down */
|
||||
bool set_armed = _armed.armed && !_armed.lockdown;
|
||||
|
||||
if (_servo_armed != set_armed)
|
||||
_servo_armed = set_armed;
|
||||
|
||||
/* update PWM status if armed or if disarmed PWM values are set */
|
||||
bool pwm_on = (_armed.armed || _num_disarmed_set > 0);
|
||||
|
||||
if (_pwm_on != pwm_on) {
|
||||
_pwm_on = pwm_on;
|
||||
up_pwm_servo_arm(pwm_on);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -661,8 +740,13 @@ PX4FMU::task_main()
|
||||
|
||||
}
|
||||
|
||||
::close(_t_actuators);
|
||||
::close(_t_actuator_armed);
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||
if (_control_subs > 0) {
|
||||
::close(_control_subs[i]);
|
||||
_control_subs[i] = -1;
|
||||
}
|
||||
}
|
||||
::close(_armed_sub);
|
||||
|
||||
/* make sure servos are off */
|
||||
up_pwm_servo_deinit();
|
||||
@@ -684,7 +768,7 @@ PX4FMU::control_callback(uintptr_t handle,
|
||||
{
|
||||
const actuator_controls_s *controls = (actuator_controls_s *)handle;
|
||||
|
||||
input = controls->control[control_index];
|
||||
input = controls[control_group].control[control_index];
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -707,6 +791,9 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
|
||||
case MODE_2PWM:
|
||||
case MODE_4PWM:
|
||||
case MODE_6PWM:
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case MODE_8PWM:
|
||||
#endif
|
||||
ret = pwm_ioctl(filp, cmd, arg);
|
||||
break;
|
||||
|
||||
@@ -936,6 +1023,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case PWM_SERVO_SET(7):
|
||||
case PWM_SERVO_SET(6):
|
||||
if (_mode < MODE_8PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
case PWM_SERVO_SET(5):
|
||||
case PWM_SERVO_SET(4):
|
||||
if (_mode < MODE_6PWM) {
|
||||
@@ -963,6 +1059,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
|
||||
break;
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case PWM_SERVO_GET(7):
|
||||
case PWM_SERVO_GET(6):
|
||||
if (_mode < MODE_8PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
case PWM_SERVO_GET(5):
|
||||
case PWM_SERVO_GET(4):
|
||||
if (_mode < MODE_6PWM) {
|
||||
@@ -990,12 +1095,22 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
case PWM_SERVO_GET_RATEGROUP(3):
|
||||
case PWM_SERVO_GET_RATEGROUP(4):
|
||||
case PWM_SERVO_GET_RATEGROUP(5):
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case PWM_SERVO_GET_RATEGROUP(6):
|
||||
case PWM_SERVO_GET_RATEGROUP(7):
|
||||
#endif
|
||||
*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0));
|
||||
break;
|
||||
|
||||
case PWM_SERVO_GET_COUNT:
|
||||
case MIXERIOCGETOUTPUTCOUNT:
|
||||
switch (_mode) {
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case MODE_8PWM:
|
||||
*(unsigned *)arg = 8;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MODE_6PWM:
|
||||
*(unsigned *)arg = 6;
|
||||
break;
|
||||
@@ -1041,6 +1156,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
set_mode(MODE_6PWM);
|
||||
break;
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
case 8:
|
||||
set_mode(MODE_8PWM);
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
ret = -EINVAL;
|
||||
@@ -1053,6 +1173,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
if (_mixers != nullptr) {
|
||||
delete _mixers;
|
||||
_mixers = nullptr;
|
||||
_groups_required = 0;
|
||||
}
|
||||
|
||||
break;
|
||||
@@ -1061,18 +1182,20 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
mixer_simple_s *mixinfo = (mixer_simple_s *)arg;
|
||||
|
||||
SimpleMixer *mixer = new SimpleMixer(control_callback,
|
||||
(uintptr_t)&_controls, mixinfo);
|
||||
(uintptr_t)_controls, mixinfo);
|
||||
|
||||
if (mixer->check()) {
|
||||
delete mixer;
|
||||
_groups_required = 0;
|
||||
ret = -EINVAL;
|
||||
|
||||
} else {
|
||||
if (_mixers == nullptr)
|
||||
_mixers = new MixerGroup(control_callback,
|
||||
(uintptr_t)&_controls);
|
||||
(uintptr_t)_controls);
|
||||
|
||||
_mixers->add_mixer(mixer);
|
||||
_mixers->groups_required(_groups_required);
|
||||
}
|
||||
|
||||
break;
|
||||
@@ -1083,9 +1206,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
unsigned buflen = strnlen(buf, 1024);
|
||||
|
||||
if (_mixers == nullptr)
|
||||
_mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
|
||||
_mixers = new MixerGroup(control_callback, (uintptr_t)_controls);
|
||||
|
||||
if (_mixers == nullptr) {
|
||||
_groups_required = 0;
|
||||
ret = -ENOMEM;
|
||||
|
||||
} else {
|
||||
@@ -1096,7 +1220,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
debug("mixer load failed with %d", ret);
|
||||
delete _mixers;
|
||||
_mixers = nullptr;
|
||||
_groups_required = 0;
|
||||
ret = -EINVAL;
|
||||
} else {
|
||||
|
||||
_mixers->groups_required(_groups_required);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1123,10 +1251,17 @@ PX4FMU::write(file *filp, const char *buffer, size_t len)
|
||||
unsigned count = len / 2;
|
||||
uint16_t values[6];
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
if (count > 8) {
|
||||
// we have at most 8 outputs
|
||||
count = 8;
|
||||
}
|
||||
#else
|
||||
if (count > 6) {
|
||||
// we have at most 6 outputs
|
||||
count = 6;
|
||||
}
|
||||
#endif
|
||||
|
||||
// allow for misaligned values
|
||||
memcpy(values, buffer, count * 2);
|
||||
@@ -1400,6 +1535,9 @@ fmu_new_mode(PortMode new_mode)
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
servo_mode = PX4FMU::MODE_6PWM;
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
servo_mode = PX4FMU::MODE_8PWM;
|
||||
#endif
|
||||
break;
|
||||
|
||||
@@ -1718,7 +1856,7 @@ fmu_main(int argc, char *argv[])
|
||||
fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb);
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
fprintf(stderr, " mode_gpio, mode_pwm, test, sensor_reset [milliseconds]\n");
|
||||
#endif
|
||||
exit(1);
|
||||
|
||||
@@ -4,3 +4,5 @@
|
||||
|
||||
MODULE_COMMAND = fmu
|
||||
SRCS = fmu.cpp
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
@@ -44,3 +44,5 @@ SRCS = px4io.cpp \
|
||||
|
||||
# XXX prune to just get UART registers
|
||||
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
+66
-19
@@ -529,6 +529,11 @@ PX4IO::~PX4IO()
|
||||
if (_interface != nullptr)
|
||||
delete _interface;
|
||||
|
||||
/* deallocate perfs */
|
||||
perf_free(_perf_update);
|
||||
perf_free(_perf_write);
|
||||
perf_free(_perf_chan_count);
|
||||
|
||||
g_dev = nullptr;
|
||||
}
|
||||
|
||||
@@ -576,8 +581,10 @@ PX4IO::init()
|
||||
ASSERT(_task == -1);
|
||||
|
||||
sys_restart_param = param_find("SYS_RESTART_TYPE");
|
||||
/* Indicate restart type is unknown */
|
||||
param_set(sys_restart_param, &sys_restart_val);
|
||||
if (sys_restart_param != PARAM_INVALID) {
|
||||
/* Indicate restart type is unknown */
|
||||
param_set(sys_restart_param, &sys_restart_val);
|
||||
}
|
||||
|
||||
/* do regular cdev init */
|
||||
ret = CDev::init();
|
||||
@@ -683,6 +690,25 @@ PX4IO::init()
|
||||
|
||||
/* send command to arm system via command API */
|
||||
vehicle_command_s cmd;
|
||||
/* send this to itself */
|
||||
param_t sys_id_param = param_find("MAV_SYS_ID");
|
||||
param_t comp_id_param = param_find("MAV_COMP_ID");
|
||||
|
||||
int32_t sys_id;
|
||||
int32_t comp_id;
|
||||
|
||||
if (param_get(sys_id_param, &sys_id)) {
|
||||
errx(1, "PRM SYSID");
|
||||
}
|
||||
|
||||
if (param_get(comp_id_param, &comp_id)) {
|
||||
errx(1, "PRM CMPID");
|
||||
}
|
||||
|
||||
cmd.target_system = sys_id;
|
||||
cmd.target_component = comp_id;
|
||||
cmd.source_system = sys_id;
|
||||
cmd.source_component = comp_id;
|
||||
/* request arming */
|
||||
cmd.param1 = 1.0f;
|
||||
cmd.param2 = 0;
|
||||
@@ -692,10 +718,7 @@ PX4IO::init()
|
||||
cmd.param6 = 0;
|
||||
cmd.param7 = 0;
|
||||
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
|
||||
// cmd.target_system = status.system_id;
|
||||
// cmd.target_component = status.component_id;
|
||||
// cmd.source_system = status.system_id;
|
||||
// cmd.source_component = status.component_id;
|
||||
|
||||
/* ask to confirm command */
|
||||
cmd.confirmation = 1;
|
||||
|
||||
@@ -773,7 +796,12 @@ PX4IO::init()
|
||||
}
|
||||
|
||||
/* start the IO interface task */
|
||||
_task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr);
|
||||
_task = task_spawn_cmd("px4io",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_ACTUATOR_OUTPUTS,
|
||||
2000,
|
||||
(main_t)&PX4IO::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
if (_task < 0) {
|
||||
debug("task start failed: %d", errno);
|
||||
@@ -968,13 +996,17 @@ PX4IO::task_main()
|
||||
int32_t failsafe_param_val;
|
||||
param_t failsafe_param = param_find("RC_FAILS_THR");
|
||||
|
||||
if (failsafe_param > 0) {
|
||||
if (failsafe_param != PARAM_INVALID) {
|
||||
|
||||
param_get(failsafe_param, &failsafe_param_val);
|
||||
uint16_t failsafe_thr = failsafe_param_val;
|
||||
pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
|
||||
if (pret != OK) {
|
||||
log("failsafe upload failed");
|
||||
|
||||
if (failsafe_param_val > 0) {
|
||||
|
||||
uint16_t failsafe_thr = failsafe_param_val;
|
||||
pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
|
||||
if (pret != OK) {
|
||||
log("failsafe upload failed, FS: %d us", (int)failsafe_thr);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1432,7 +1464,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
|
||||
/* we don't have the status bits, so input_source has to be set elsewhere */
|
||||
input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
|
||||
|
||||
static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
|
||||
const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
|
||||
uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
|
||||
|
||||
/*
|
||||
@@ -1440,8 +1472,6 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
|
||||
*
|
||||
* This should be the common case (9 channel R/C control being a reasonable upper bound).
|
||||
*/
|
||||
input_rc.timestamp_publication = hrt_absolute_time();
|
||||
|
||||
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, ®s[0], prolog + 9);
|
||||
|
||||
if (ret != OK)
|
||||
@@ -1453,23 +1483,38 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
|
||||
*/
|
||||
channel_count = regs[PX4IO_P_RAW_RC_COUNT];
|
||||
|
||||
if (channel_count != _rc_chan_count)
|
||||
/* limit the channel count */
|
||||
if (channel_count > RC_INPUT_MAX_CHANNELS) {
|
||||
channel_count = RC_INPUT_MAX_CHANNELS;
|
||||
}
|
||||
|
||||
/* count channel count changes to identify signal integrity issues */
|
||||
if (channel_count != _rc_chan_count) {
|
||||
perf_count(_perf_chan_count);
|
||||
}
|
||||
|
||||
_rc_chan_count = channel_count;
|
||||
|
||||
input_rc.timestamp_publication = hrt_absolute_time();
|
||||
|
||||
input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA];
|
||||
input_rc.rssi = regs[PX4IO_P_RAW_RC_NRSSI];
|
||||
input_rc.rc_failsafe = (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
|
||||
input_rc.rc_lost = !(regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_OK);
|
||||
input_rc.rc_lost_frame_count = regs[PX4IO_P_RAW_LOST_FRAME_COUNT];
|
||||
input_rc.rc_total_frame_count = regs[PX4IO_P_RAW_FRAME_COUNT];
|
||||
input_rc.channel_count = channel_count;
|
||||
|
||||
/* rc_lost has to be set before the call to this function */
|
||||
if (!input_rc.rc_lost && !input_rc.rc_failsafe)
|
||||
if (!input_rc.rc_lost && !input_rc.rc_failsafe) {
|
||||
_rc_last_valid = input_rc.timestamp_publication;
|
||||
}
|
||||
|
||||
input_rc.timestamp_last_signal = _rc_last_valid;
|
||||
|
||||
/* FIELDS NOT SET HERE */
|
||||
/* input_rc.input_source is set after this call XXX we might want to mirror the flags in the RC struct */
|
||||
|
||||
if (channel_count > 9) {
|
||||
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, ®s[prolog + 9], channel_count - 9);
|
||||
|
||||
@@ -1477,8 +1522,10 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
|
||||
return ret;
|
||||
}
|
||||
|
||||
input_rc.channel_count = channel_count;
|
||||
memcpy(input_rc.values, ®s[prolog], channel_count * 2);
|
||||
/* last thing set are the actual channel values as 16 bit values */
|
||||
for (unsigned i = 0; i < channel_count; i++) {
|
||||
input_rc.values[i] = regs[prolog + i];
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
@@ -639,7 +639,7 @@ PX4IO_serial::_do_interrupt()
|
||||
if (_rx_dma_status == _dma_status_waiting) {
|
||||
|
||||
/* verify that the received packet is complete */
|
||||
unsigned length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
|
||||
int length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
|
||||
if ((length < 1) || (length < PKT_SIZE(_dma_buffer))) {
|
||||
perf_count(_pc_badidle);
|
||||
|
||||
|
||||
@@ -254,9 +254,6 @@ SF0X::~SF0X()
|
||||
int
|
||||
SF0X::init()
|
||||
{
|
||||
int ret = ERROR;
|
||||
unsigned i = 0;
|
||||
|
||||
/* do regular cdev init */
|
||||
if (CDev::init() != OK) {
|
||||
goto out;
|
||||
@@ -594,7 +591,7 @@ SF0X::collect()
|
||||
valid = false;
|
||||
|
||||
/* wipe out partially read content from last cycle(s), check for dot */
|
||||
for (int i = 0; i < (lend - 2); i++) {
|
||||
for (unsigned i = 0; i < (lend - 2); i++) {
|
||||
if (_linebuf[i] == '\n') {
|
||||
char buf[sizeof(_linebuf)];
|
||||
memcpy(buf, &_linebuf[i+1], (lend + 1) - (i + 1));
|
||||
@@ -795,7 +792,7 @@ const int ERROR = -1;
|
||||
|
||||
SF0X *g_dev;
|
||||
|
||||
void start();
|
||||
void start(const char *port);
|
||||
void stop();
|
||||
void test();
|
||||
void reset();
|
||||
|
||||
@@ -145,7 +145,7 @@ private:
|
||||
|
||||
ADC::ADC(uint32_t channels) :
|
||||
CDev("adc", ADC_DEVICE_PATH),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "ADC samples")),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
|
||||
_channel_count(0),
|
||||
_samples(nullptr),
|
||||
_to_system_power(0)
|
||||
@@ -419,6 +419,10 @@ adc_main(int argc, char *argv[])
|
||||
g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
|
||||
(1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
|
||||
#endif
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
/* XXX this hardcodes the default channel set for AeroCore - should be configurable */
|
||||
g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
|
||||
#endif
|
||||
|
||||
if (g_adc == nullptr)
|
||||
errx(1, "couldn't allocate the ADC driver");
|
||||
|
||||
@@ -94,7 +94,7 @@
|
||||
#elif HRT_TIMER == 3
|
||||
# define HRT_TIMER_BASE STM32_TIM3_BASE
|
||||
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
|
||||
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM3EN
|
||||
# define HRT_TIMER_POWER_BIT RCC_APB1ENR_TIM3EN
|
||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIM3
|
||||
# define HRT_TIMER_CLOCK STM32_APB1_TIM3_CLKIN
|
||||
# if CONFIG_STM32_TIM3
|
||||
@@ -141,7 +141,7 @@
|
||||
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
|
||||
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
|
||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
|
||||
# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
|
||||
# define HRT_TIMER_CLOCK STM32_APB2_TIM10_CLKIN
|
||||
# if CONFIG_STM32_TIM10
|
||||
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
|
||||
# endif
|
||||
@@ -150,7 +150,7 @@
|
||||
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
|
||||
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
|
||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
|
||||
# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
|
||||
# define HRT_TIMER_CLOCK STM32_APB2_TIM11_CLKIN
|
||||
# if CONFIG_STM32_TIM11
|
||||
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
|
||||
# endif
|
||||
@@ -354,6 +354,9 @@ __EXPORT uint16_t ppm_frame_length = 0;
|
||||
__EXPORT unsigned ppm_decoded_channels = 0;
|
||||
__EXPORT uint64_t ppm_last_valid_decode = 0;
|
||||
|
||||
#define PPM_DEBUG 0
|
||||
|
||||
#if PPM_DEBUG
|
||||
/* PPM edge history */
|
||||
__EXPORT uint16_t ppm_edge_history[32];
|
||||
unsigned ppm_edge_next;
|
||||
@@ -361,6 +364,7 @@ unsigned ppm_edge_next;
|
||||
/* PPM pulse history */
|
||||
__EXPORT uint16_t ppm_pulse_history[32];
|
||||
unsigned ppm_pulse_next;
|
||||
#endif
|
||||
|
||||
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
|
||||
|
||||
@@ -455,10 +459,12 @@ hrt_ppm_decode(uint32_t status)
|
||||
/* how long since the last edge? - this handles counter wrapping implicitely. */
|
||||
width = count - ppm.last_edge;
|
||||
|
||||
#if PPM_DEBUG
|
||||
ppm_edge_history[ppm_edge_next++] = width;
|
||||
|
||||
if (ppm_edge_next >= 32)
|
||||
ppm_edge_next = 0;
|
||||
#endif
|
||||
|
||||
/*
|
||||
* if this looks like a start pulse, then push the last set of values
|
||||
@@ -546,10 +552,12 @@ hrt_ppm_decode(uint32_t status)
|
||||
interval = count - ppm.last_mark;
|
||||
ppm.last_mark = count;
|
||||
|
||||
#if PPM_DEBUG
|
||||
ppm_pulse_history[ppm_pulse_next++] = interval;
|
||||
|
||||
if (ppm_pulse_next >= 32)
|
||||
ppm_pulse_next = 0;
|
||||
#endif
|
||||
|
||||
/* if the mark-mark timing is out of bounds, abandon the frame */
|
||||
if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
|
||||
|
||||
@@ -39,3 +39,5 @@ MODULE_COMMAND = ex_fixedwing_control
|
||||
|
||||
SRCS = main.c \
|
||||
params.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
@@ -1,613 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 flow_position_control.c
|
||||
*
|
||||
* Optical flow position controller
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <termios.h>
|
||||
#include <time.h>
|
||||
#include <math.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/vehicle_local_position.h>
|
||||
#include <uORB/topics/vehicle_bodyframe_speed_setpoint.h>
|
||||
#include <uORB/topics/filtered_bottom_flow.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <poll.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
#include "flow_position_control_params.h"
|
||||
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
__EXPORT int flow_position_control_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of position controller.
|
||||
*/
|
||||
static int flow_position_control_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_spawn_cmd().
|
||||
*/
|
||||
int flow_position_control_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start"))
|
||||
{
|
||||
if (thread_running)
|
||||
{
|
||||
printf("flow position control already running\n");
|
||||
/* this is not an error */
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn_cmd("flow_position_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 6,
|
||||
4096,
|
||||
flow_position_control_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop"))
|
||||
{
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status"))
|
||||
{
|
||||
if (thread_running)
|
||||
printf("\tflow position control app is running\n");
|
||||
else
|
||||
printf("\tflow position control app not started\n");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
static int
|
||||
flow_position_control_thread_main(int argc, char *argv[])
|
||||
{
|
||||
/* welcome user */
|
||||
thread_running = true;
|
||||
static int mavlink_fd;
|
||||
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
mavlink_log_info(mavlink_fd, "[fpc] started");
|
||||
|
||||
uint32_t counter = 0;
|
||||
const float time_scale = powf(10.0f,-6.0f);
|
||||
|
||||
/* structures */
|
||||
struct actuator_armed_s armed;
|
||||
memset(&armed, 0, sizeof(armed));
|
||||
struct vehicle_control_mode_s control_mode;
|
||||
memset(&control_mode, 0, sizeof(control_mode));
|
||||
struct vehicle_attitude_s att;
|
||||
memset(&att, 0, sizeof(att));
|
||||
struct manual_control_setpoint_s manual;
|
||||
memset(&manual, 0, sizeof(manual));
|
||||
struct filtered_bottom_flow_s filtered_flow;
|
||||
memset(&filtered_flow, 0, sizeof(filtered_flow));
|
||||
struct vehicle_local_position_s local_pos;
|
||||
memset(&local_pos, 0, sizeof(local_pos));
|
||||
struct vehicle_bodyframe_speed_setpoint_s speed_sp;
|
||||
memset(&speed_sp, 0, sizeof(speed_sp));
|
||||
|
||||
/* subscribe to attitude, motor setpoints and system state */
|
||||
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
|
||||
int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
|
||||
int manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
int filtered_bottom_flow_sub = orb_subscribe(ORB_ID(filtered_bottom_flow));
|
||||
int vehicle_local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
|
||||
|
||||
orb_advert_t speed_sp_pub;
|
||||
bool speed_setpoint_adverted = false;
|
||||
|
||||
/* parameters init*/
|
||||
struct flow_position_control_params params;
|
||||
struct flow_position_control_param_handles param_handles;
|
||||
parameters_init(¶m_handles);
|
||||
parameters_update(¶m_handles, ¶ms);
|
||||
|
||||
/* init flow sum setpoint */
|
||||
float flow_sp_sumx = 0.0f;
|
||||
float flow_sp_sumy = 0.0f;
|
||||
|
||||
/* init yaw setpoint */
|
||||
float yaw_sp = 0.0f;
|
||||
|
||||
/* init height setpoint */
|
||||
float height_sp = params.height_min;
|
||||
|
||||
/* height controller states */
|
||||
bool start_phase = true;
|
||||
bool landing_initialized = false;
|
||||
float landing_thrust_start = 0.0f;
|
||||
|
||||
/* states */
|
||||
float integrated_h_error = 0.0f;
|
||||
float last_local_pos_z = 0.0f;
|
||||
bool update_flow_sp_sumx = false;
|
||||
bool update_flow_sp_sumy = false;
|
||||
uint64_t last_time = 0.0f;
|
||||
float dt = 0.0f; // s
|
||||
|
||||
|
||||
/* register the perf counter */
|
||||
perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "flow_position_control_runtime");
|
||||
perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "flow_position_control_interval");
|
||||
perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "flow_position_control_err");
|
||||
|
||||
static bool sensors_ready = false;
|
||||
static bool status_changed = false;
|
||||
|
||||
while (!thread_should_exit)
|
||||
{
|
||||
/* wait for first attitude msg to be sure all data are available */
|
||||
if (sensors_ready)
|
||||
{
|
||||
/* polling */
|
||||
struct pollfd fds[2] = {
|
||||
{ .fd = filtered_bottom_flow_sub, .events = POLLIN }, // positions from estimator
|
||||
{ .fd = parameter_update_sub, .events = POLLIN }
|
||||
|
||||
};
|
||||
|
||||
/* wait for a position update, check for exit condition every 500 ms */
|
||||
int ret = poll(fds, 2, 500);
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
/* poll error, count it in perf */
|
||||
perf_count(mc_err_perf);
|
||||
}
|
||||
else if (ret == 0)
|
||||
{
|
||||
/* no return value, ignore */
|
||||
// printf("[flow position control] no filtered flow updates\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
/* parameter update available? */
|
||||
if (fds[1].revents & POLLIN)
|
||||
{
|
||||
/* read from param to clear updated flag */
|
||||
struct parameter_update_s update;
|
||||
orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
|
||||
|
||||
parameters_update(¶m_handles, ¶ms);
|
||||
mavlink_log_info(mavlink_fd,"[fpc] parameters updated.");
|
||||
}
|
||||
|
||||
/* only run controller if position/speed changed */
|
||||
if (fds[0].revents & POLLIN)
|
||||
{
|
||||
perf_begin(mc_loop_perf);
|
||||
|
||||
/* get a local copy of the vehicle state */
|
||||
orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
|
||||
/* get a local copy of manual setpoint */
|
||||
orb_copy(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, &manual);
|
||||
/* get a local copy of attitude */
|
||||
orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
|
||||
/* get a local copy of filtered bottom flow */
|
||||
orb_copy(ORB_ID(filtered_bottom_flow), filtered_bottom_flow_sub, &filtered_flow);
|
||||
/* get a local copy of local position */
|
||||
orb_copy(ORB_ID(vehicle_local_position), vehicle_local_position_sub, &local_pos);
|
||||
/* get a local copy of control mode */
|
||||
orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
|
||||
|
||||
if (control_mode.flag_control_velocity_enabled)
|
||||
{
|
||||
float manual_pitch = manual.pitch / params.rc_scale_pitch; // 0 to 1
|
||||
float manual_roll = manual.roll / params.rc_scale_roll; // 0 to 1
|
||||
float manual_yaw = manual.yaw / params.rc_scale_yaw; // -1 to 1
|
||||
|
||||
if(status_changed == false)
|
||||
mavlink_log_info(mavlink_fd,"[fpc] flow POSITION control engaged");
|
||||
|
||||
status_changed = true;
|
||||
|
||||
/* calc dt */
|
||||
if(last_time == 0)
|
||||
{
|
||||
last_time = hrt_absolute_time();
|
||||
continue;
|
||||
}
|
||||
dt = ((float) (hrt_absolute_time() - last_time)) * time_scale;
|
||||
last_time = hrt_absolute_time();
|
||||
|
||||
/* update flow sum setpoint */
|
||||
if (update_flow_sp_sumx)
|
||||
{
|
||||
flow_sp_sumx = filtered_flow.sumx;
|
||||
update_flow_sp_sumx = false;
|
||||
}
|
||||
if (update_flow_sp_sumy)
|
||||
{
|
||||
flow_sp_sumy = filtered_flow.sumy;
|
||||
update_flow_sp_sumy = false;
|
||||
}
|
||||
|
||||
/* calc new bodyframe speed setpoints */
|
||||
float speed_body_x = (flow_sp_sumx - filtered_flow.sumx) * params.pos_p - filtered_flow.vx * params.pos_d;
|
||||
float speed_body_y = (flow_sp_sumy - filtered_flow.sumy) * params.pos_p - filtered_flow.vy * params.pos_d;
|
||||
float speed_limit_height_factor = height_sp; // the settings are for 1 meter
|
||||
|
||||
/* overwrite with rc input if there is any */
|
||||
if(isfinite(manual_pitch) && isfinite(manual_roll))
|
||||
{
|
||||
if(fabsf(manual_pitch) > params.manual_threshold)
|
||||
{
|
||||
speed_body_x = -manual_pitch * params.limit_speed_x * speed_limit_height_factor;
|
||||
update_flow_sp_sumx = true;
|
||||
}
|
||||
|
||||
if(fabsf(manual_roll) > params.manual_threshold)
|
||||
{
|
||||
speed_body_y = manual_roll * params.limit_speed_y * speed_limit_height_factor;
|
||||
update_flow_sp_sumy = true;
|
||||
}
|
||||
}
|
||||
|
||||
/* limit speed setpoints */
|
||||
if((speed_body_x <= params.limit_speed_x * speed_limit_height_factor) &&
|
||||
(speed_body_x >= -params.limit_speed_x * speed_limit_height_factor))
|
||||
{
|
||||
speed_sp.vx = speed_body_x;
|
||||
}
|
||||
else
|
||||
{
|
||||
if(speed_body_x > params.limit_speed_x * speed_limit_height_factor)
|
||||
speed_sp.vx = params.limit_speed_x * speed_limit_height_factor;
|
||||
if(speed_body_x < -params.limit_speed_x * speed_limit_height_factor)
|
||||
speed_sp.vx = -params.limit_speed_x * speed_limit_height_factor;
|
||||
}
|
||||
|
||||
if((speed_body_y <= params.limit_speed_y * speed_limit_height_factor) &&
|
||||
(speed_body_y >= -params.limit_speed_y * speed_limit_height_factor))
|
||||
{
|
||||
speed_sp.vy = speed_body_y;
|
||||
}
|
||||
else
|
||||
{
|
||||
if(speed_body_y > params.limit_speed_y * speed_limit_height_factor)
|
||||
speed_sp.vy = params.limit_speed_y * speed_limit_height_factor;
|
||||
if(speed_body_y < -params.limit_speed_y * speed_limit_height_factor)
|
||||
speed_sp.vy = -params.limit_speed_y * speed_limit_height_factor;
|
||||
}
|
||||
|
||||
/* manual yaw change */
|
||||
if(isfinite(manual_yaw) && isfinite(manual.throttle))
|
||||
{
|
||||
if(fabsf(manual_yaw) > params.manual_threshold && manual.throttle > 0.2f)
|
||||
{
|
||||
yaw_sp += manual_yaw * params.limit_yaw_step;
|
||||
|
||||
/* modulo for rotation -pi +pi */
|
||||
if(yaw_sp < -M_PI_F)
|
||||
yaw_sp = yaw_sp + M_TWOPI_F;
|
||||
else if(yaw_sp > M_PI_F)
|
||||
yaw_sp = yaw_sp - M_TWOPI_F;
|
||||
}
|
||||
}
|
||||
|
||||
/* forward yaw setpoint */
|
||||
speed_sp.yaw_sp = yaw_sp;
|
||||
|
||||
|
||||
/* manual height control
|
||||
* 0-20%: thrust linear down
|
||||
* 20%-40%: down
|
||||
* 40%-60%: stabilize altitude
|
||||
* 60-100%: up
|
||||
*/
|
||||
float thrust_control = 0.0f;
|
||||
|
||||
if (isfinite(manual.throttle))
|
||||
{
|
||||
if (start_phase)
|
||||
{
|
||||
/* control start thrust with stick input */
|
||||
if (manual.throttle < 0.4f)
|
||||
{
|
||||
/* first 40% for up to feedforward */
|
||||
thrust_control = manual.throttle / 0.4f * params.thrust_feedforward;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* second 60% for up to feedforward + 10% */
|
||||
thrust_control = (manual.throttle - 0.4f) / 0.6f * 0.1f + params.thrust_feedforward;
|
||||
}
|
||||
|
||||
/* exit start phase if setpoint is reached */
|
||||
if (height_sp < -local_pos.z && thrust_control > params.limit_thrust_lower)
|
||||
{
|
||||
start_phase = false;
|
||||
/* switch to stabilize */
|
||||
thrust_control = params.thrust_feedforward;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (manual.throttle < 0.2f)
|
||||
{
|
||||
/* landing initialization */
|
||||
if (!landing_initialized)
|
||||
{
|
||||
/* consider last thrust control to avoid steps */
|
||||
landing_thrust_start = speed_sp.thrust_sp;
|
||||
landing_initialized = true;
|
||||
}
|
||||
|
||||
/* set current height as setpoint to avoid steps */
|
||||
if (-local_pos.z > params.height_min)
|
||||
height_sp = -local_pos.z;
|
||||
else
|
||||
height_sp = params.height_min;
|
||||
|
||||
/* lower 20% stick range controls thrust down */
|
||||
thrust_control = manual.throttle / 0.2f * landing_thrust_start;
|
||||
|
||||
/* assume ground position here */
|
||||
if (thrust_control < 0.1f)
|
||||
{
|
||||
/* reset integral if on ground */
|
||||
integrated_h_error = 0.0f;
|
||||
/* switch to start phase */
|
||||
start_phase = true;
|
||||
/* reset height setpoint */
|
||||
height_sp = params.height_min;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* stabilized mode */
|
||||
landing_initialized = false;
|
||||
|
||||
/* calc new thrust with PID */
|
||||
float height_error = (local_pos.z - (-height_sp));
|
||||
|
||||
/* update height setpoint if needed*/
|
||||
if (manual.throttle < 0.4f)
|
||||
{
|
||||
/* down */
|
||||
if (height_sp > params.height_min + params.height_rate &&
|
||||
fabsf(height_error) < params.limit_height_error)
|
||||
height_sp -= params.height_rate * dt;
|
||||
}
|
||||
|
||||
if (manual.throttle > 0.6f)
|
||||
{
|
||||
/* up */
|
||||
if (height_sp < params.height_max &&
|
||||
fabsf(height_error) < params.limit_height_error)
|
||||
height_sp += params.height_rate * dt;
|
||||
}
|
||||
|
||||
/* instead of speed limitation, limit height error (downwards) */
|
||||
if(height_error > params.limit_height_error)
|
||||
height_error = params.limit_height_error;
|
||||
else if(height_error < -params.limit_height_error)
|
||||
height_error = -params.limit_height_error;
|
||||
|
||||
integrated_h_error = integrated_h_error + height_error;
|
||||
float integrated_thrust_addition = integrated_h_error * params.height_i;
|
||||
|
||||
if(integrated_thrust_addition > params.limit_thrust_int)
|
||||
integrated_thrust_addition = params.limit_thrust_int;
|
||||
if(integrated_thrust_addition < -params.limit_thrust_int)
|
||||
integrated_thrust_addition = -params.limit_thrust_int;
|
||||
|
||||
float height_speed = last_local_pos_z - local_pos.z;
|
||||
float thrust_diff = height_error * params.height_p - height_speed * params.height_d;
|
||||
|
||||
thrust_control = params.thrust_feedforward + thrust_diff + integrated_thrust_addition;
|
||||
|
||||
/* add attitude component
|
||||
* F = Fz / (cos(pitch)*cos(roll)) -> can be found in rotM
|
||||
*/
|
||||
// // TODO problem with attitude
|
||||
// if (att.R_valid && att.R[2][2] > 0)
|
||||
// thrust_control = thrust_control / att.R[2][2];
|
||||
|
||||
/* set thrust lower limit */
|
||||
if(thrust_control < params.limit_thrust_lower)
|
||||
thrust_control = params.limit_thrust_lower;
|
||||
}
|
||||
}
|
||||
|
||||
/* set thrust upper limit */
|
||||
if(thrust_control > params.limit_thrust_upper)
|
||||
thrust_control = params.limit_thrust_upper;
|
||||
}
|
||||
/* store actual height for speed estimation */
|
||||
last_local_pos_z = local_pos.z;
|
||||
|
||||
speed_sp.thrust_sp = thrust_control; //manual.throttle;
|
||||
speed_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* publish new speed setpoint */
|
||||
if(isfinite(speed_sp.vx) && isfinite(speed_sp.vy) && isfinite(speed_sp.yaw_sp) && isfinite(speed_sp.thrust_sp))
|
||||
{
|
||||
|
||||
if(speed_setpoint_adverted)
|
||||
{
|
||||
orb_publish(ORB_ID(vehicle_bodyframe_speed_setpoint), speed_sp_pub, &speed_sp);
|
||||
}
|
||||
else
|
||||
{
|
||||
speed_sp_pub = orb_advertise(ORB_ID(vehicle_bodyframe_speed_setpoint), &speed_sp);
|
||||
speed_setpoint_adverted = true;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
warnx("NaN in flow position controller!");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* in manual or stabilized state just reset speed and flow sum setpoint */
|
||||
//mavlink_log_info(mavlink_fd,"[fpc] reset speed sp, flow_sp_sumx,y (%f,%f)",filtered_flow.sumx, filtered_flow.sumy);
|
||||
if(status_changed == true)
|
||||
mavlink_log_info(mavlink_fd,"[fpc] flow POSITION controller disengaged.");
|
||||
|
||||
status_changed = false;
|
||||
speed_sp.vx = 0.0f;
|
||||
speed_sp.vy = 0.0f;
|
||||
flow_sp_sumx = filtered_flow.sumx;
|
||||
flow_sp_sumy = filtered_flow.sumy;
|
||||
if(isfinite(att.yaw))
|
||||
{
|
||||
yaw_sp = att.yaw;
|
||||
speed_sp.yaw_sp = att.yaw;
|
||||
}
|
||||
if(isfinite(manual.throttle))
|
||||
speed_sp.thrust_sp = manual.throttle;
|
||||
}
|
||||
/* measure in what intervals the controller runs */
|
||||
perf_count(mc_interval_perf);
|
||||
perf_end(mc_loop_perf);
|
||||
}
|
||||
}
|
||||
|
||||
counter++;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* sensors not ready waiting for first attitude msg */
|
||||
|
||||
/* polling */
|
||||
struct pollfd fds[1] = {
|
||||
{ .fd = vehicle_attitude_sub, .events = POLLIN },
|
||||
};
|
||||
|
||||
/* wait for a flow msg, check for exit condition every 5 s */
|
||||
int ret = poll(fds, 1, 5000);
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
/* poll error, count it in perf */
|
||||
perf_count(mc_err_perf);
|
||||
}
|
||||
else if (ret == 0)
|
||||
{
|
||||
/* no return value, ignore */
|
||||
mavlink_log_info(mavlink_fd,"[fpc] no attitude received.\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
if (fds[0].revents & POLLIN)
|
||||
{
|
||||
sensors_ready = true;
|
||||
mavlink_log_info(mavlink_fd,"[fpc] initialized.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
mavlink_log_info(mavlink_fd,"[fpc] ending now...\n");
|
||||
|
||||
thread_running = false;
|
||||
|
||||
close(parameter_update_sub);
|
||||
close(vehicle_attitude_sub);
|
||||
close(vehicle_local_position_sub);
|
||||
close(armed_sub);
|
||||
close(control_mode_sub);
|
||||
close(manual_control_setpoint_sub);
|
||||
close(speed_sp_pub);
|
||||
|
||||
perf_print_counter(mc_loop_perf);
|
||||
perf_free(mc_loop_perf);
|
||||
|
||||
fflush(stdout);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -1,124 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 flow_position_control_params.c
|
||||
*/
|
||||
|
||||
#include "flow_position_control_params.h"
|
||||
|
||||
/* controller parameters */
|
||||
|
||||
// Position control P gain
|
||||
PARAM_DEFINE_FLOAT(FPC_POS_P, 3.0f);
|
||||
// Position control D / damping gain
|
||||
PARAM_DEFINE_FLOAT(FPC_POS_D, 0.0f);
|
||||
// Altitude control P gain
|
||||
PARAM_DEFINE_FLOAT(FPC_H_P, 0.15f);
|
||||
// Altitude control I (integrator) gain
|
||||
PARAM_DEFINE_FLOAT(FPC_H_I, 0.00001f);
|
||||
// Altitude control D gain
|
||||
PARAM_DEFINE_FLOAT(FPC_H_D, 0.8f);
|
||||
// Altitude control rate limiter
|
||||
PARAM_DEFINE_FLOAT(FPC_H_RATE, 0.1f);
|
||||
// Altitude control minimum altitude
|
||||
PARAM_DEFINE_FLOAT(FPC_H_MIN, 0.5f);
|
||||
// Altitude control maximum altitude (higher than 1.5m is untested)
|
||||
PARAM_DEFINE_FLOAT(FPC_H_MAX, 1.5f);
|
||||
// Altitude control feed forward throttle - adjust to the
|
||||
// throttle position (0..1) where the copter hovers in manual flight
|
||||
PARAM_DEFINE_FLOAT(FPC_T_FFWD, 0.7f); // adjust this before flight
|
||||
PARAM_DEFINE_FLOAT(FPC_L_S_X, 1.2f);
|
||||
PARAM_DEFINE_FLOAT(FPC_L_S_Y, 1.2f);
|
||||
PARAM_DEFINE_FLOAT(FPC_L_H_ERR, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(FPC_L_TH_I, 0.05f);
|
||||
PARAM_DEFINE_FLOAT(FPC_L_TH_U, 0.8f);
|
||||
PARAM_DEFINE_FLOAT(FPC_L_TH_L, 0.6f);
|
||||
PARAM_DEFINE_FLOAT(FPC_L_YAW_STEP, 0.03f);
|
||||
PARAM_DEFINE_FLOAT(FPC_MAN_THR, 0.1f);
|
||||
|
||||
|
||||
int parameters_init(struct flow_position_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->pos_p = param_find("FPC_POS_P");
|
||||
h->pos_d = param_find("FPC_POS_D");
|
||||
h->height_p = param_find("FPC_H_P");
|
||||
h->height_i = param_find("FPC_H_I");
|
||||
h->height_d = param_find("FPC_H_D");
|
||||
h->height_rate = param_find("FPC_H_RATE");
|
||||
h->height_min = param_find("FPC_H_MIN");
|
||||
h->height_max = param_find("FPC_H_MAX");
|
||||
h->thrust_feedforward = param_find("FPC_T_FFWD");
|
||||
h->limit_speed_x = param_find("FPC_L_S_X");
|
||||
h->limit_speed_y = param_find("FPC_L_S_Y");
|
||||
h->limit_height_error = param_find("FPC_L_H_ERR");
|
||||
h->limit_thrust_int = param_find("FPC_L_TH_I");
|
||||
h->limit_thrust_upper = param_find("FPC_L_TH_U");
|
||||
h->limit_thrust_lower = param_find("FPC_L_TH_L");
|
||||
h->limit_yaw_step = param_find("FPC_L_YAW_STEP");
|
||||
h->manual_threshold = param_find("FPC_MAN_THR");
|
||||
h->rc_scale_pitch = param_find("RC_SCALE_PITCH");
|
||||
h->rc_scale_roll = param_find("RC_SCALE_ROLL");
|
||||
h->rc_scale_yaw = param_find("RC_SCALE_YAW");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int parameters_update(const struct flow_position_control_param_handles *h, struct flow_position_control_params *p)
|
||||
{
|
||||
param_get(h->pos_p, &(p->pos_p));
|
||||
param_get(h->pos_d, &(p->pos_d));
|
||||
param_get(h->height_p, &(p->height_p));
|
||||
param_get(h->height_i, &(p->height_i));
|
||||
param_get(h->height_d, &(p->height_d));
|
||||
param_get(h->height_rate, &(p->height_rate));
|
||||
param_get(h->height_min, &(p->height_min));
|
||||
param_get(h->height_max, &(p->height_max));
|
||||
param_get(h->thrust_feedforward, &(p->thrust_feedforward));
|
||||
param_get(h->limit_speed_x, &(p->limit_speed_x));
|
||||
param_get(h->limit_speed_y, &(p->limit_speed_y));
|
||||
param_get(h->limit_height_error, &(p->limit_height_error));
|
||||
param_get(h->limit_thrust_int, &(p->limit_thrust_int));
|
||||
param_get(h->limit_thrust_upper, &(p->limit_thrust_upper));
|
||||
param_get(h->limit_thrust_lower, &(p->limit_thrust_lower));
|
||||
param_get(h->limit_yaw_step, &(p->limit_yaw_step));
|
||||
param_get(h->manual_threshold, &(p->manual_threshold));
|
||||
param_get(h->rc_scale_pitch, &(p->rc_scale_pitch));
|
||||
param_get(h->rc_scale_roll, &(p->rc_scale_roll));
|
||||
param_get(h->rc_scale_yaw, &(p->rc_scale_yaw));
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -1,100 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 flow_position_control_params.h
|
||||
*
|
||||
* Parameters for position controller
|
||||
*/
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
struct flow_position_control_params {
|
||||
float pos_p;
|
||||
float pos_d;
|
||||
float height_p;
|
||||
float height_i;
|
||||
float height_d;
|
||||
float height_rate;
|
||||
float height_min;
|
||||
float height_max;
|
||||
float thrust_feedforward;
|
||||
float limit_speed_x;
|
||||
float limit_speed_y;
|
||||
float limit_height_error;
|
||||
float limit_thrust_int;
|
||||
float limit_thrust_upper;
|
||||
float limit_thrust_lower;
|
||||
float limit_yaw_step;
|
||||
float manual_threshold;
|
||||
float rc_scale_pitch;
|
||||
float rc_scale_roll;
|
||||
float rc_scale_yaw;
|
||||
};
|
||||
|
||||
struct flow_position_control_param_handles {
|
||||
param_t pos_p;
|
||||
param_t pos_d;
|
||||
param_t height_p;
|
||||
param_t height_i;
|
||||
param_t height_d;
|
||||
param_t height_rate;
|
||||
param_t height_min;
|
||||
param_t height_max;
|
||||
param_t thrust_feedforward;
|
||||
param_t limit_speed_x;
|
||||
param_t limit_speed_y;
|
||||
param_t limit_height_error;
|
||||
param_t limit_thrust_int;
|
||||
param_t limit_thrust_upper;
|
||||
param_t limit_thrust_lower;
|
||||
param_t limit_yaw_step;
|
||||
param_t manual_threshold;
|
||||
param_t rc_scale_pitch;
|
||||
param_t rc_scale_roll;
|
||||
param_t rc_scale_yaw;
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialize all parameter handles and values
|
||||
*
|
||||
*/
|
||||
int parameters_init(struct flow_position_control_param_handles *h);
|
||||
|
||||
/**
|
||||
* Update all parameters
|
||||
*
|
||||
*/
|
||||
int parameters_update(const struct flow_position_control_param_handles *h, struct flow_position_control_params *p);
|
||||
@@ -1,41 +0,0 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Build multirotor position control
|
||||
#
|
||||
|
||||
MODULE_COMMAND = flow_position_control
|
||||
|
||||
SRCS = flow_position_control_main.c \
|
||||
flow_position_control_params.c
|
||||
@@ -65,6 +65,7 @@
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
#include <uORB/topics/filtered_bottom_flow.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include "flow_position_estimator_params.h"
|
||||
@@ -109,9 +110,9 @@ int flow_position_estimator_main(int argc, char *argv[])
|
||||
|
||||
thread_should_exit = false;
|
||||
daemon_task = task_spawn_cmd("flow_position_estimator",
|
||||
SCHED_RR,
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
4096,
|
||||
4000,
|
||||
flow_position_estimator_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
|
||||
@@ -38,3 +38,5 @@
|
||||
MODULE_COMMAND = px4_daemon_app
|
||||
|
||||
SRCS = px4_daemon_app.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
@@ -98,7 +98,7 @@ int px4_daemon_app_main(int argc, char *argv[])
|
||||
daemon_task = task_spawn_cmd("daemon",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
4096,
|
||||
2000,
|
||||
px4_daemon_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
|
||||
@@ -37,4 +37,6 @@
|
||||
|
||||
MODULE_COMMAND = px4_mavlink_debug
|
||||
|
||||
SRCS = px4_mavlink_debug.c
|
||||
SRCS = px4_mavlink_debug.c
|
||||
|
||||
MODULE_STACKSIZE = 2000
|
||||
|
||||
@@ -63,11 +63,22 @@ ECL_PitchController::ECL_PitchController() :
|
||||
_rate_setpoint(0.0f),
|
||||
_bodyrate_setpoint(0.0f)
|
||||
{
|
||||
perf_alloc(PC_COUNT, "fw att control pitch nonfinite input");
|
||||
}
|
||||
|
||||
ECL_PitchController::~ECL_PitchController()
|
||||
{
|
||||
perf_free(_nonfinite_input_perf);
|
||||
}
|
||||
|
||||
float ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed)
|
||||
{
|
||||
|
||||
/* Do not calculate control signal with bad inputs */
|
||||
if (!(isfinite(pitch_setpoint) && isfinite(roll) && isfinite(pitch) && isfinite(airspeed))) {
|
||||
perf_count(_nonfinite_input_perf);
|
||||
warnx("not controlling pitch");
|
||||
return _rate_setpoint;
|
||||
}
|
||||
|
||||
/* flying inverted (wings upside down) ? */
|
||||
bool inverted = false;
|
||||
@@ -123,6 +134,14 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
|
||||
float yaw_rate_setpoint,
|
||||
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
|
||||
{
|
||||
/* Do not calculate control signal with bad inputs */
|
||||
if (!(isfinite(roll) && isfinite(pitch) && isfinite(pitch_rate) && isfinite(yaw_rate) &&
|
||||
isfinite(yaw_rate_setpoint) && isfinite(airspeed_min) &&
|
||||
isfinite(airspeed_max) && isfinite(scaler))) {
|
||||
perf_count(_nonfinite_input_perf);
|
||||
return math::constrain(_last_output, -1.0f, 1.0f);
|
||||
}
|
||||
|
||||
/* get the usual dt estimate */
|
||||
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
|
||||
_last_run = ecl_absolute_time();
|
||||
|
||||
@@ -51,12 +51,15 @@
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
class __EXPORT ECL_PitchController //XXX: create controller superclass
|
||||
{
|
||||
public:
|
||||
ECL_PitchController();
|
||||
|
||||
~ECL_PitchController();
|
||||
|
||||
float control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed);
|
||||
|
||||
|
||||
@@ -126,6 +129,7 @@ private:
|
||||
float _rate_error;
|
||||
float _rate_setpoint;
|
||||
float _bodyrate_setpoint;
|
||||
perf_counter_t _nonfinite_input_perf;
|
||||
};
|
||||
|
||||
#endif // ECL_PITCH_CONTROLLER_H
|
||||
|
||||
@@ -61,10 +61,21 @@ ECL_RollController::ECL_RollController() :
|
||||
_rate_setpoint(0.0f),
|
||||
_bodyrate_setpoint(0.0f)
|
||||
{
|
||||
perf_alloc(PC_COUNT, "fw att control roll nonfinite input");
|
||||
}
|
||||
|
||||
ECL_RollController::~ECL_RollController()
|
||||
{
|
||||
perf_free(_nonfinite_input_perf);
|
||||
}
|
||||
|
||||
float ECL_RollController::control_attitude(float roll_setpoint, float roll)
|
||||
{
|
||||
/* Do not calculate control signal with bad inputs */
|
||||
if (!(isfinite(roll_setpoint) && isfinite(roll))) {
|
||||
perf_count(_nonfinite_input_perf);
|
||||
return _rate_setpoint;
|
||||
}
|
||||
|
||||
/* Calculate error */
|
||||
float roll_error = roll_setpoint - roll;
|
||||
@@ -86,6 +97,14 @@ float ECL_RollController::control_bodyrate(float pitch,
|
||||
float yaw_rate_setpoint,
|
||||
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
|
||||
{
|
||||
/* Do not calculate control signal with bad inputs */
|
||||
if (!(isfinite(pitch) && isfinite(roll_rate) && isfinite(yaw_rate) && isfinite(yaw_rate_setpoint) &&
|
||||
isfinite(airspeed_min) && isfinite(airspeed_max) &&
|
||||
isfinite(scaler))) {
|
||||
perf_count(_nonfinite_input_perf);
|
||||
return math::constrain(_last_output, -1.0f, 1.0f);
|
||||
}
|
||||
|
||||
/* get the usual dt estimate */
|
||||
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
|
||||
_last_run = ecl_absolute_time();
|
||||
@@ -122,8 +141,8 @@ float ECL_RollController::control_bodyrate(float pitch,
|
||||
float id = _rate_error * dt;
|
||||
|
||||
/*
|
||||
* anti-windup: do not allow integrator to increase if actuator is at limit
|
||||
*/
|
||||
* anti-windup: do not allow integrator to increase if actuator is at limit
|
||||
*/
|
||||
if (_last_output < -1.0f) {
|
||||
/* only allow motion to center: increase value */
|
||||
id = math::max(id, 0.0f);
|
||||
|
||||
@@ -51,12 +51,15 @@
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
class __EXPORT ECL_RollController //XXX: create controller superclass
|
||||
{
|
||||
public:
|
||||
ECL_RollController();
|
||||
|
||||
~ECL_RollController();
|
||||
|
||||
float control_attitude(float roll_setpoint, float roll);
|
||||
|
||||
float control_bodyrate(float pitch,
|
||||
@@ -117,6 +120,7 @@ private:
|
||||
float _rate_error;
|
||||
float _rate_setpoint;
|
||||
float _bodyrate_setpoint;
|
||||
perf_counter_t _nonfinite_input_perf;
|
||||
};
|
||||
|
||||
#endif // ECL_ROLL_CONTROLLER_H
|
||||
|
||||
@@ -60,12 +60,25 @@ ECL_YawController::ECL_YawController() :
|
||||
_bodyrate_setpoint(0.0f),
|
||||
_coordinated_min_speed(1.0f)
|
||||
{
|
||||
perf_alloc(PC_COUNT, "fw att control yaw nonfinite input");
|
||||
}
|
||||
|
||||
ECL_YawController::~ECL_YawController()
|
||||
{
|
||||
perf_free(_nonfinite_input_perf);
|
||||
}
|
||||
|
||||
float ECL_YawController::control_attitude(float roll, float pitch,
|
||||
float speed_body_u, float speed_body_v, float speed_body_w,
|
||||
float roll_rate_setpoint, float pitch_rate_setpoint)
|
||||
{
|
||||
/* Do not calculate control signal with bad inputs */
|
||||
if (!(isfinite(roll) && isfinite(pitch) && isfinite(speed_body_u) && isfinite(speed_body_v) &&
|
||||
isfinite(speed_body_w) && isfinite(roll_rate_setpoint) &&
|
||||
isfinite(pitch_rate_setpoint))) {
|
||||
perf_count(_nonfinite_input_perf);
|
||||
return _rate_setpoint;
|
||||
}
|
||||
// static int counter = 0;
|
||||
/* Calculate desired yaw rate from coordinated turn constraint / (no side forces) */
|
||||
_rate_setpoint = 0.0f;
|
||||
@@ -103,6 +116,13 @@ float ECL_YawController::control_bodyrate(float roll, float pitch,
|
||||
float pitch_rate_setpoint,
|
||||
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
|
||||
{
|
||||
/* Do not calculate control signal with bad inputs */
|
||||
if (!(isfinite(roll) && isfinite(pitch) && isfinite(pitch_rate) && isfinite(yaw_rate) &&
|
||||
isfinite(pitch_rate_setpoint) && isfinite(airspeed_min) &&
|
||||
isfinite(airspeed_max) && isfinite(scaler))) {
|
||||
perf_count(_nonfinite_input_perf);
|
||||
return math::constrain(_last_output, -1.0f, 1.0f);
|
||||
}
|
||||
/* get the usual dt estimate */
|
||||
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
|
||||
_last_run = ecl_absolute_time();
|
||||
|
||||
@@ -50,12 +50,15 @@
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
class __EXPORT ECL_YawController //XXX: create controller superclass
|
||||
{
|
||||
public:
|
||||
ECL_YawController();
|
||||
|
||||
~ECL_YawController();
|
||||
|
||||
float control_attitude(float roll, float pitch,
|
||||
float speed_body_u, float speed_body_v, float speed_body_w,
|
||||
float roll_rate_setpoint, float pitch_rate_setpoint);
|
||||
@@ -118,6 +121,7 @@ private:
|
||||
float _rate_setpoint;
|
||||
float _bodyrate_setpoint;
|
||||
float _coordinated_min_speed;
|
||||
perf_counter_t _nonfinite_input_perf;
|
||||
|
||||
};
|
||||
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user