forked from Archive/PX4-Autopilot
Merged origin/master into pubsub_cleanup
This commit is contained in:
commit
773f70a9df
|
@ -599,7 +599,7 @@ RECURSIVE = YES
|
|||
# excluded from the INPUT source files. This way you can easily exclude a
|
||||
# subdirectory from a directory tree whose root is specified with the INPUT tag.
|
||||
|
||||
EXCLUDE = ../src/modules/mathlib/CMSIS \
|
||||
EXCLUDE = ../src/lib/mathlib/CMSIS \
|
||||
../src/modules/attitude_estimator_ekf/codegen
|
||||
|
||||
# The EXCLUDE_SYMLINKS tag can be used select whether or not files or
|
||||
|
|
|
@ -1,14 +1,13 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HILStar / X-Plane
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting.."
|
||||
echo "HIL Rascal 110 starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
|
@ -40,48 +39,7 @@ then
|
|||
param save
|
||||
fi
|
||||
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
# Tell MAVLink that this link is "fast"
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
|
||||
fw_pos_control_l1 start
|
||||
fw_att_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
||||
|
|
|
@ -1,74 +1,31 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] Team Blacksheep Discovery Quad"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
# Team Blacksheep Discovery Quadcopter
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.006
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.17
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 5.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.17
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.006
|
||||
param set MC_YAWPOS_P 0.5
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.2
|
||||
|
||||
param save
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_w
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load the mixer for a quad with wide arms
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1100
|
||||
pwm max -c 1234 -p 1900
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
|
|
|
@ -1,73 +1,53 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] 3DR Iris Quad"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
# 3DR Iris Quadcopter
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.13
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 9.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.13
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 0.5
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.8
|
||||
param set MPC_THR_MIN 0.2
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
param set BAT_V_SCALING 0.00989
|
||||
param set BAT_C_SCALING 0.0124
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_w
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.0098
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load the mixer for a quad with wide arms
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1050
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1000
|
||||
set PWM_MAX 2000
|
||||
|
|
|
@ -1,105 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
#
|
||||
|
||||
echo "[HIL] HILS quadrotor starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.0
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.05
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 3.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.1
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_P 0.05
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.5
|
||||
param set MPC_THR_MIN 0.1
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
# Tell MAVLink that this link is "fast"
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
|
||||
#
|
||||
# Start position estimator
|
||||
#
|
||||
position_estimator_inav start
|
||||
|
||||
#
|
||||
# Start attitude control
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start position control
|
||||
#
|
||||
multirotor_pos_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
|
|
@ -0,0 +1,46 @@
|
|||
#!nsh
|
||||
#
|
||||
# HIL Quadcopter X
|
||||
#
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.8
|
||||
param set MPC_THR_MIN 0.2
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
fi
|
||||
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_x
|
|
@ -1,14 +1,13 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HIL Rascal 110 (Flightgear)
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting in state-HIL mode.."
|
||||
echo "HIL Rascal 110 starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
|
@ -32,48 +31,15 @@ then
|
|||
param set FW_T_SINK_MAX 5.0
|
||||
param set FW_T_SINK_MIN 4.0
|
||||
param set FW_Y_ROLLFF 1.1
|
||||
param set FW_L1_PERIOD 16
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
# Tell MAVLink that this link is "fast"
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
|
||||
fw_pos_control_l1 start
|
||||
fw_att_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
||||
|
|
|
@ -1,105 +1,46 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HIL Quadcopter +
|
||||
#
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILS quadrotor + starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.0
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.05
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 3.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.1
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_P 0.05
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.5
|
||||
param set MPC_THR_MIN 0.1
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.8
|
||||
param set MPC_THR_MIN 0.2
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
fi
|
||||
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
# Tell MAVLink that this link is "fast"
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
||||
|
||||
#
|
||||
# Start position estimator
|
||||
#
|
||||
position_estimator_inav start
|
||||
|
||||
#
|
||||
# Start attitude control
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start position control
|
||||
#
|
||||
multirotor_pos_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_+
|
||||
|
|
|
@ -1,14 +1,13 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HIL Rascal 110 (Flightgear)
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting.."
|
||||
echo "HIL Rascal 110 starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
|
@ -40,59 +39,7 @@ then
|
|||
param save
|
||||
fi
|
||||
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
# Tell MAVLink that this link is "fast"
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
set MODE autostart
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_AERT.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_AERT.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_AERT.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_AERT.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
|
||||
fi
|
||||
|
||||
|
||||
fw_pos_control_l1 start
|
||||
fw_att_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo coaxial geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_octo_cox
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
|
@ -1,13 +1,15 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
# MPX EasyStar Plane
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
# Maintainers: ???
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 15
|
||||
|
@ -31,50 +33,7 @@ then
|
|||
param set FW_L1_PERIOD 16
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_RET.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_RET.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_RET.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_RET.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_RET
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on HK Bixler"
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set FW_P_D 0
|
||||
|
@ -35,46 +35,6 @@ then
|
|||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_AERT.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_AERT.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_AERT.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
|
@ -5,7 +5,7 @@ echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
|
|||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set FW_P_D 0
|
||||
|
@ -35,48 +35,6 @@ then
|
|||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
pwm disarmed -c 3 -p 1056
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_AERT.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_AERT.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_AETR.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AETR.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
|
@ -2,57 +2,39 @@
|
|||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
# TODO
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_AIRSPD_MIN 7
|
||||
param set FW_AIRSPD_TRIM 9
|
||||
param set FW_AIRSPD_MAX 14
|
||||
param set FW_L1_PERIOD 10
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 20
|
||||
param set FW_P_LIM_MAX 30
|
||||
param set FW_P_LIM_MIN -20
|
||||
param set FW_P_P 30
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 60
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.65
|
||||
param set FW_THR_MAX 0.7
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 2.0
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_Q
|
||||
|
|
|
@ -1,85 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set FW_AIRSPD_MIN 11.4
|
||||
param set FW_AIRSPD_TRIM 14
|
||||
param set FW_AIRSPD_MAX 22
|
||||
param set FW_L1_PERIOD 15
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 15
|
||||
param set FW_P_LIM_MAX 45
|
||||
param set FW_P_LIM_MIN -45
|
||||
param set FW_P_P 60
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 15
|
||||
param set FW_R_P 80
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.8
|
||||
param set FW_THR_LND_MAX 0
|
||||
param set FW_THR_MAX 1
|
||||
param set FW_THR_MIN 0.5
|
||||
param set FW_T_SINK_MAX 5.0
|
||||
param set FW_T_SINK_MIN 2.0
|
||||
param set FW_Y_ROLLFF 1.0
|
||||
param set RC_SCALE_ROLL 0.6
|
||||
param set RC_SCALE_PITCH 0.6
|
||||
param set TRIM_PITCH 0.1
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
|
@ -0,0 +1,44 @@
|
|||
#!nsh
|
||||
#
|
||||
# Phantom FPV Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_AIRSPD_MIN 11.4
|
||||
param set FW_AIRSPD_TRIM 14
|
||||
param set FW_AIRSPD_MAX 22
|
||||
param set FW_L1_PERIOD 15
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 15
|
||||
param set FW_P_LIM_MAX 45
|
||||
param set FW_P_LIM_MIN -45
|
||||
param set FW_P_P 60
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 15
|
||||
param set FW_R_P 80
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.8
|
||||
param set FW_THR_LND_MAX 0
|
||||
param set FW_THR_MAX 1
|
||||
param set FW_THR_MIN 0.5
|
||||
param set FW_T_SINK_MAX 5.0
|
||||
param set FW_T_SINK_MIN 2.0
|
||||
param set FW_Y_ROLLFF 1.0
|
||||
param set RC_SCALE_ROLL 0.6
|
||||
param set RC_SCALE_PITCH 0.6
|
||||
param set TRIM_PITCH 0.1
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_Q
|
|
@ -1,58 +1,43 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Skywalker X5"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
# Skywalker X5 Flying Wing
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
# TODO
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_AIRSPD_MIN 7
|
||||
param set FW_AIRSPD_TRIM 9
|
||||
param set FW_AIRSPD_MAX 14
|
||||
param set FW_L1_PERIOD 10
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 20
|
||||
param set FW_P_LIM_MAX 30
|
||||
param set FW_P_LIM_MIN -20
|
||||
param set FW_P_P 30
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 60
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.65
|
||||
param set FW_THR_MAX 0.7
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 2.0
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_X5
|
||||
|
|
|
@ -1,84 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on the Wing Wing (aka Z-84)"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set FW_AIRSPD_MIN 7
|
||||
param set FW_AIRSPD_TRIM 9
|
||||
param set FW_AIRSPD_MAX 14
|
||||
param set FW_L1_PERIOD 10
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 20
|
||||
param set FW_P_LIM_MAX 30
|
||||
param set FW_P_LIM_MIN -20
|
||||
param set FW_P_P 30
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 60
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.65
|
||||
param set FW_THR_MAX 0.7
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 2.0
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
|
@ -0,0 +1,43 @@
|
|||
#!nsh
|
||||
#
|
||||
# Wing Wing (aka Z-84) Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_AIRSPD_MIN 7
|
||||
param set FW_AIRSPD_TRIM 9
|
||||
param set FW_AIRSPD_MAX 14
|
||||
param set FW_L1_PERIOD 10
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 20
|
||||
param set FW_P_LIM_MAX 30
|
||||
param set FW_P_LIM_MIN -20
|
||||
param set FW_P_P 30
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 60
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.65
|
||||
param set FW_THR_MAX 0.7
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 2.0
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_Q
|
|
@ -0,0 +1,43 @@
|
|||
#!nsh
|
||||
#
|
||||
# FX-79 Buffalo Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_AIRSPD_MAX 20
|
||||
param set FW_AIRSPD_TRIM 12
|
||||
param set FW_AIRSPD_MIN 15
|
||||
param set FW_L1_PERIOD 12
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 15
|
||||
param set FW_P_LIM_MAX 50
|
||||
param set FW_P_LIM_MIN -50
|
||||
param set FW_P_P 60
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 1.1
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 80
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.75
|
||||
param set FW_THR_MAX 1
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5.0
|
||||
param set FW_T_SINK_MIN 4.0
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 1.1
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_FX79
|
|
@ -1,84 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on FX-79 Buffalo"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set FW_AIRSPD_MAX 20
|
||||
param set FW_AIRSPD_TRIM 12
|
||||
param set FW_AIRSPD_MIN 15
|
||||
param set FW_L1_PERIOD 12
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 15
|
||||
param set FW_P_LIM_MAX 50
|
||||
param set FW_P_LIM_MIN -50
|
||||
param set FW_P_P 60
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 1.1
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 80
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.75
|
||||
param set FW_THR_MAX 1
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5.0
|
||||
param set FW_T_SINK_MIN 4.0
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 1.1
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_FX79.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_FX79.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_FX79.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_FX79.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_FX79.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
|
@ -1,31 +1,31 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
# DJI Flame Wheel F330 Quadcopter
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.8
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.05
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
param set MPC_THR_MAX 0.8
|
||||
param set MPC_THR_MIN 0.2
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
|
@ -38,32 +38,14 @@ then
|
|||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_x
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
sh /etc/init.d/rc.mc_interface
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
||||
|
|
|
@ -1,74 +1,37 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on DJI F450"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
# DJI Flame Wheel F450 Quadcopter
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_x
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals (for DJI ESCs)
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1200
|
||||
pwm max -c 1234 -p 1800
|
||||
|
||||
#
|
||||
# Start common multirotor apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
||||
|
|
|
@ -0,0 +1,33 @@
|
|||
#!nsh
|
||||
#
|
||||
# HobbyKing X550 Quadcopter
|
||||
#
|
||||
# Maintainers: Todd Stellanova <tstellanova@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 5.5
|
||||
param set MC_ATT_I 0
|
||||
param set MC_ATT_D 0
|
||||
param set MC_ATTRATE_P 0.14
|
||||
param set MC_ATTRATE_I 0
|
||||
param set MC_ATTRATE_D 0.006
|
||||
param set MC_YAWPOS_P 0.6
|
||||
param set MC_YAWPOS_I 0
|
||||
param set MC_YAWPOS_D 0
|
||||
param set MC_YAWRATE_P 0.08
|
||||
param set MC_YAWRATE_I 0
|
||||
param set MC_YAWRATE_D 0
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_x
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
|
@ -1,51 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
# TODO
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 10 = ground rover
|
||||
#
|
||||
param set MAV_TYPE 10
|
||||
|
||||
#
|
||||
# Start MAVLink (depends on orb)
|
||||
#
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start and configure PX4IO interface
|
||||
#
|
||||
sh /etc/init.d/rc.io
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
roboclaw start /dev/ttyS2 128 1200
|
||||
segway start
|
|
@ -0,0 +1,37 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Quad + geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_+
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
|
@ -0,0 +1,37 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Hexa X geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_hexa_x
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
|
@ -1,76 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with or without IO"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set MC_ATTRATE_P 0.14
|
||||
param set MC_ATTRATE_I 0
|
||||
param set MC_ATTRATE_D 0.006
|
||||
param set MC_ATT_P 5.5
|
||||
param set MC_ATT_I 0
|
||||
param set MC_ATT_D 0
|
||||
param set MC_YAWPOS_D 0
|
||||
param set MC_YAWPOS_I 0
|
||||
param set MC_YAWPOS_P 0.6
|
||||
param set MC_YAWRATE_D 0
|
||||
param set MC_YAWRATE_I 0
|
||||
param set MC_YAWRATE_P 0.08
|
||||
param set RC_SCALE_PITCH 1
|
||||
param set RC_SCALE_ROLL 1
|
||||
param set RC_SCALE_YAW 3
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1100
|
||||
pwm max -c 1234 -p 1900
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
|
@ -0,0 +1,37 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Hexa + geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_hexa_+
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
|
@ -0,0 +1,37 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo X geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_octo_x
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
|
@ -1,51 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 init to log only
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Set PWM values for DJI ESCs
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
gps start
|
||||
|
||||
attitude_estimator_ekf start
|
||||
|
||||
position_estimator_inav start
|
||||
|
||||
if [ -d /fs/microsd ]
|
||||
then
|
||||
if [ $BOARD == fmuv1 ]
|
||||
then
|
||||
sdlog2 start -r 50 -e -b 16
|
||||
else
|
||||
sdlog2 start -r 200 -e -b 16
|
||||
fi
|
||||
fi
|
|
@ -0,0 +1,37 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo + geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.005
|
||||
|
||||
# TODO add default MPC parameters
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER FMU_octo_+
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
|
@ -1,9 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
cp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
|
||||
if cmp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
|
||||
then
|
||||
echo "CMP returned true"
|
||||
else
|
||||
echo "CMP returned false"
|
||||
fi
|
|
@ -0,0 +1,195 @@
|
|||
#
|
||||
# Check if auto-setup from one of the standard scripts is wanted
|
||||
# SYS_AUTOSTART = 0 means no autostart (default)
|
||||
#
|
||||
# AUTOSTART PARTITION:
|
||||
# 0 .. 999 Reserved (historical)
|
||||
# 1000 .. 1999 Simulation setups
|
||||
# 2000 .. 2999 Standard planes
|
||||
# 3000 .. 3999 Flying wing
|
||||
# 4000 .. 4999 Quad X
|
||||
# 5000 .. 5999 Quad +
|
||||
# 6000 .. 6999 Hexa X
|
||||
# 7000 .. 7999 Hexa +
|
||||
# 8000 .. 8999 Octo X
|
||||
# 9000 .. 9999 Octo +
|
||||
# 10000 .. 10999 Wide arm / H frame
|
||||
# 11000 .. 11999 Hexa Cox
|
||||
# 12000 .. 12999 Octo Cox
|
||||
|
||||
#
|
||||
# Simulation setups
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 1000
|
||||
then
|
||||
sh /etc/init.d/1000_rc_fw_easystar.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1001
|
||||
then
|
||||
sh /etc/init.d/1001_rc_quad_x.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1002
|
||||
then
|
||||
sh /etc/init.d/1002_rc_fw_state.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1003
|
||||
then
|
||||
sh /etc/init.d/1003_rc_quad_+.hil
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1004
|
||||
then
|
||||
sh /etc/init.d/1004_rc_fw_Rascal110.hil
|
||||
fi
|
||||
|
||||
#
|
||||
# Standard plane
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 2100 100
|
||||
then
|
||||
sh /etc/init.d/2100_mpx_easystar
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2101 101
|
||||
then
|
||||
sh /etc/init.d/2101_hk_bixler
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2102 102
|
||||
then
|
||||
sh /etc/init.d/2102_3dr_skywalker
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
#
|
||||
# Flying wing
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 3030 30
|
||||
then
|
||||
sh /etc/init.d/3030_io_camflyer
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3031 31
|
||||
then
|
||||
sh /etc/init.d/3031_phantom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3032 32
|
||||
then
|
||||
sh /etc/init.d/3032_skywalker_x5
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3033 33
|
||||
then
|
||||
sh /etc/init.d/3033_wingwing
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3034 34
|
||||
then
|
||||
sh /etc/init.d/3034_fx79
|
||||
fi
|
||||
|
||||
#
|
||||
# Quad X
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 4008 8
|
||||
then
|
||||
#sh /etc/init.d/4008_ardrone
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4009 9
|
||||
then
|
||||
#sh /etc/init.d/4009_ardrone_flow
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4010 10
|
||||
then
|
||||
sh /etc/init.d/4010_dji_f330
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4011 11
|
||||
then
|
||||
sh /etc/init.d/4011_dji_f450
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4012 12
|
||||
then
|
||||
sh /etc/init.d/4012_hk_x550
|
||||
fi
|
||||
|
||||
#
|
||||
# Quad +
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 5001
|
||||
then
|
||||
sh /etc/init.d/5001_quad_+_pwm
|
||||
fi
|
||||
|
||||
#
|
||||
# Hexa X
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 6001
|
||||
then
|
||||
sh /etc/init.d/6001_hexa_x_pwm
|
||||
fi
|
||||
|
||||
#
|
||||
# Hexa +
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 7001
|
||||
then
|
||||
sh /etc/init.d/7001_hexa_+_pwm
|
||||
fi
|
||||
|
||||
#
|
||||
# Octo X
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 8001
|
||||
then
|
||||
sh /etc/init.d/8001_octo_x_pwm
|
||||
fi
|
||||
|
||||
#
|
||||
# Octo +
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 9001
|
||||
then
|
||||
sh /etc/init.d/9001_octo_+_pwm
|
||||
fi
|
||||
|
||||
#
|
||||
# Wide arm / H frame
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 10015 15
|
||||
then
|
||||
sh /etc/init.d/10015_tbs_discovery
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10016 16
|
||||
then
|
||||
sh /etc/init.d/10016_3dr_iris
|
||||
fi
|
||||
|
||||
#
|
||||
# Octo Coaxial
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 12001
|
||||
then
|
||||
sh /etc/init.d/12001_octo_cox_pwm
|
||||
fi
|
|
@ -1,113 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.002
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.09
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 6.8
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Start the Mikrokopter ESC driver
|
||||
#
|
||||
if [ $MKBLCTRL_MODE == yes ]
|
||||
then
|
||||
if [ $MKBLCTRL_FRAME == x ]
|
||||
then
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing"
|
||||
mkblctrl -mkmode x
|
||||
else
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing"
|
||||
mkblctrl -mkmode +
|
||||
fi
|
||||
else
|
||||
if [ $MKBLCTRL_FRAME == x ]
|
||||
then
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame"
|
||||
else
|
||||
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame"
|
||||
fi
|
||||
mkblctrl
|
||||
fi
|
||||
|
||||
usleep 10000
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
if [ $MKBLCTRL_FRAME == x ]
|
||||
then
|
||||
mixer load /dev/mkblctrl /etc/mixers/FMU_quad_x.mix
|
||||
else
|
||||
mixer load /dev/mkblctrl /etc/mixers/FMU_quad_+.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,120 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.002
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.09
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 6.8
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
echo "RC script for PX4FMU + PX4IO + PPM-ESCs running"
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
usleep 10000
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
fmu mode_pwm
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
if [ $ESC_MAKER = afro ]
|
||||
then
|
||||
# Set PWM values for Afro ESCs
|
||||
pwm disarmed -c 1234 -p 1050
|
||||
pwm min -c 1234 -p 1080
|
||||
pwm max -c 1234 -p 1860
|
||||
else
|
||||
# Set PWM values for typical ESCs
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 980
|
||||
pwm max -c 1234 -p 1800
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
if [ $FRAME_GEOMETRY == x ]
|
||||
then
|
||||
echo "Frame geometry X"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
else
|
||||
if [ $FRAME_GEOMETRY == w ]
|
||||
then
|
||||
echo "Frame geometry W"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||
else
|
||||
echo "Frame geometry +"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -r 400 -c 1234
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
||||
|
||||
echo "Script end"
|
|
@ -1,34 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard everything needed for fixedwing except mixer, actuator output and mavlink
|
||||
#
|
||||
|
||||
#
|
||||
# Start the sensors and test them.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start logging (depends on sensors)
|
||||
#
|
||||
sh /etc/init.d/rc.logging
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
#
|
||||
fw_att_control start
|
||||
|
||||
#
|
||||
# Start the position controller
|
||||
#
|
||||
fw_pos_control_l1 start
|
|
@ -0,0 +1,19 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard apps for fixed wing
|
||||
#
|
||||
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
#
|
||||
fw_att_control start
|
||||
|
||||
#
|
||||
# Start the position controller
|
||||
#
|
||||
fw_pos_control_l1 start
|
|
@ -1,94 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Hex"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
|
||||
# 13 = hexarotor
|
||||
#
|
||||
param set MAV_TYPE 13
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Start and configure PX4IO interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# This is not possible on a hexa
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
mixer load /dev/pwm_output $MIXER
|
||||
|
||||
#
|
||||
# Set PWM output frequency to 400 Hz
|
||||
#
|
||||
pwm rate -a -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 123456 -p 900
|
||||
pwm min -c 123456 -p 1100
|
||||
pwm max -c 123456 -p 1900
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -0,0 +1,72 @@
|
|||
#!nsh
|
||||
#
|
||||
# Script to configure control interface
|
||||
#
|
||||
|
||||
if [ $MIXER != none ]
|
||||
then
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
set MIXERSD /fs/microsd/etc/mixers/$MIXER.mix
|
||||
|
||||
#Use the mixer file from the SD-card if it exists
|
||||
if [ -f $MIXERSD ]
|
||||
then
|
||||
set MIXER_FILE $MIXERSD
|
||||
else
|
||||
set MIXER_FILE /etc/mixers/$MIXER.mix
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == mkblctrl ]
|
||||
then
|
||||
set OUTPUT_DEV /dev/mkblctrl
|
||||
else
|
||||
set OUTPUT_DEV /dev/pwm_output
|
||||
fi
|
||||
|
||||
if mixer load $OUTPUT_DEV $MIXER_FILE
|
||||
then
|
||||
echo "[init] Mixer loaded: $MIXER_FILE"
|
||||
else
|
||||
echo "[init] Error loading mixer: $MIXER_FILE"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
else
|
||||
echo "[init] Mixer not defined"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
|
||||
then
|
||||
if [ $PWM_OUTPUTS != none ]
|
||||
then
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
if [ $PWM_RATE != none ]
|
||||
then
|
||||
echo "[init] Set PWM rate: $PWM_RATE"
|
||||
pwm rate -c $PWM_OUTPUTS -r $PWM_RATE
|
||||
fi
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM values
|
||||
#
|
||||
if [ $PWM_DISARMED != none ]
|
||||
then
|
||||
echo "[init] Set PWM disarmed: $PWM_DISARMED"
|
||||
pwm disarmed -c $PWM_OUTPUTS -p $PWM_DISARMED
|
||||
fi
|
||||
if [ $PWM_MIN != none ]
|
||||
then
|
||||
echo "[init] Set PWM min: $PWM_MIN"
|
||||
pwm min -c $PWM_OUTPUTS -p $PWM_MIN
|
||||
fi
|
||||
if [ $PWM_MAX != none ]
|
||||
then
|
||||
echo "[init] Set PWM max: $PWM_MAX"
|
||||
pwm max -c $PWM_OUTPUTS -p $PWM_MAX
|
||||
fi
|
||||
fi
|
||||
fi
|
|
@ -1,23 +1,21 @@
|
|||
#
|
||||
# Start PX4IO interface (depends on orb, commander)
|
||||
# Init PX4IO interface
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Disable px4io topic limiting
|
||||
#
|
||||
if [ $BOARD == fmuv1 ]
|
||||
then
|
||||
px4io limit 200
|
||||
else
|
||||
px4io limit 400
|
||||
fi
|
||||
else
|
||||
# SOS
|
||||
tone_alarm error
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
#
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Adjust PX4IO update rate limit
|
||||
#
|
||||
set PX4IO_LIMIT 400
|
||||
if hw_ver compare PX4FMU_V1
|
||||
then
|
||||
set PX4IO_LIMIT 200
|
||||
fi
|
||||
|
||||
echo "[init] Set PX4IO update rate limit: $PX4IO_LIMIT Hz"
|
||||
px4io limit $PX4IO_LIMIT
|
||||
|
|
|
@ -1,14 +1,14 @@
|
|||
#!nsh
|
||||
#
|
||||
# Initialise logging services.
|
||||
# Initialize logging services.
|
||||
#
|
||||
|
||||
if [ -d /fs/microsd ]
|
||||
then
|
||||
if [ $BOARD == fmuv1 ]
|
||||
if hw_ver compare PX4FMU_V1
|
||||
then
|
||||
sdlog2 start -r 50 -a -b 16
|
||||
sdlog2 start -r 50 -a -b 16 -t
|
||||
else
|
||||
sdlog2 start -r 200 -a -b 16
|
||||
sdlog2 start -r 200 -a -b 16 -t
|
||||
fi
|
||||
fi
|
||||
|
|
|
@ -0,0 +1,24 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard apps for multirotors
|
||||
#
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start position estimator
|
||||
#
|
||||
position_estimator_inav start
|
||||
|
||||
#
|
||||
# Start attitude control
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start position control
|
||||
#
|
||||
multirotor_pos_control start
|
|
@ -1,49 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# Script to set PWM min / max limits and mixer
|
||||
#
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
if [ $FRAME_GEOMETRY == x ]
|
||||
then
|
||||
echo "Frame geometry X"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
else
|
||||
if [ $FRAME_GEOMETRY == w ]
|
||||
then
|
||||
echo "Frame geometry W"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||
else
|
||||
echo "Frame geometry +"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $FRAME_COUNT == 4 ]
|
||||
then
|
||||
set OUTPUTS 1234
|
||||
param set MAV_TYPE 2
|
||||
else
|
||||
if [ $FRAME_COUNT == 6 ]
|
||||
then
|
||||
set OUTPUTS 123456
|
||||
param set MAV_TYPE 13
|
||||
else
|
||||
set OUTPUTS 12345678
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm rate -c $OUTPUTS -r $PWM_RATE
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals (for DJI ESCs)
|
||||
#
|
||||
pwm disarmed -c $OUTPUTS -p $PWM_DISARMED
|
||||
pwm min -c $OUTPUTS -p $PWM_MIN
|
||||
pwm max -c $OUTPUTS -p $PWM_MAX
|
|
@ -1,39 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard everything needed for multirotors except mixer, actuator output and mavlink
|
||||
#
|
||||
|
||||
#
|
||||
# Start the sensors and test them.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start logging (depends on sensors)
|
||||
#
|
||||
sh /etc/init.d/rc.logging
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start position estimator
|
||||
#
|
||||
position_estimator_inav start
|
||||
|
||||
#
|
||||
# Start attitude control
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start position control
|
||||
#
|
||||
multirotor_pos_control start
|
|
@ -1,94 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] Octorotor startup"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
|
||||
param set MC_ATTRATE_D 0.004
|
||||
param set MC_ATTRATE_I 0.0
|
||||
param set MC_ATTRATE_P 0.12
|
||||
param set MC_ATT_D 0.0
|
||||
param set MC_ATT_I 0.0
|
||||
param set MC_ATT_P 7.0
|
||||
param set MC_YAWPOS_D 0.0
|
||||
param set MC_YAWPOS_I 0.0
|
||||
param set MC_YAWPOS_P 2.0
|
||||
param set MC_YAWRATE_D 0.005
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set NAV_TAKEOFF_ALT 3.0
|
||||
param set MPC_TILT_MAX 0.5
|
||||
param set MPC_THR_MAX 0.7
|
||||
param set MPC_THR_MIN 0.3
|
||||
param set MPC_XY_D 0
|
||||
param set MPC_XY_P 0.5
|
||||
param set MPC_XY_VEL_D 0
|
||||
param set MPC_XY_VEL_I 0
|
||||
param set MPC_XY_VEL_MAX 3
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_Z_D 0
|
||||
param set MPC_Z_P 1
|
||||
param set MPC_Z_VEL_D 0
|
||||
param set MPC_Z_VEL_I 0.1
|
||||
param set MPC_Z_VEL_MAX 2
|
||||
param set MPC_Z_VEL_P 0.20
|
||||
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
|
||||
# 14 = octorotor
|
||||
#
|
||||
param set MAV_TYPE 14
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Start and configure PX4IO interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
# This is not possible on an octo
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer
|
||||
#
|
||||
mixer load /dev/pwm_output $MIXER
|
||||
|
||||
#
|
||||
# Set PWM output frequency to 400 Hz
|
||||
#
|
||||
pwm rate -a -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 12345678 -p 900
|
||||
pwm min -c 12345678 -p 1100
|
||||
pwm max -c 12345678 -p 1900
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -10,41 +10,42 @@
|
|||
ms5611 start
|
||||
adc start
|
||||
|
||||
# mag might be external
|
||||
# Mag might be external
|
||||
if hmc5883 start
|
||||
then
|
||||
echo "using HMC5883"
|
||||
echo "[init] Using HMC5883"
|
||||
fi
|
||||
|
||||
if mpu6000 start
|
||||
then
|
||||
echo "using MPU6000"
|
||||
echo "[init] Using MPU6000"
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
echo "using L3GD20(H)"
|
||||
echo "[init] Using L3GD20(H)"
|
||||
fi
|
||||
|
||||
if lsm303d start
|
||||
if hw_ver compare PX4FMU_V2
|
||||
then
|
||||
set BOARD fmuv2
|
||||
else
|
||||
set BOARD fmuv1
|
||||
if lsm303d start
|
||||
then
|
||||
echo "[init] Using LSM303D"
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start airspeed sensors
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "using MEAS airspeed sensor"
|
||||
echo "[init] Using MEAS airspeed sensor"
|
||||
else
|
||||
if ets_airspeed start
|
||||
then
|
||||
echo "using ETS airspeed sensor (bus 3)"
|
||||
echo "[init] Using ETS airspeed sensor (bus 3)"
|
||||
else
|
||||
if ets_airspeed start -b 1
|
||||
then
|
||||
echo "Using ETS airspeed sensor (bus 1)"
|
||||
echo "[init] Using ETS airspeed sensor (bus 1)"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
|
|
@ -1,13 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU standalone configuration.
|
||||
#
|
||||
|
||||
echo "[init] doing standalone PX4FMU startup..."
|
||||
|
||||
#
|
||||
# Start the ORB
|
||||
#
|
||||
uorb start
|
||||
|
||||
echo "[init] startup done"
|
|
@ -36,39 +36,6 @@ then
|
|||
echo "Commander started"
|
||||
fi
|
||||
|
||||
# Start px4io if present
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO driver started"
|
||||
else
|
||||
if fmu mode_serial
|
||||
then
|
||||
echo "FMU driver started"
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start sensors
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
# Start one of the estimators
|
||||
if attitude_estimator_ekf status
|
||||
then
|
||||
echo "multicopter att filter running"
|
||||
else
|
||||
if att_pos_estimator_ekf status
|
||||
then
|
||||
echo "fixedwing att filter running"
|
||||
else
|
||||
attitude_estimator_ekf start
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start GPS
|
||||
if gps start
|
||||
then
|
||||
echo "GPS started"
|
||||
fi
|
||||
|
||||
echo "MAVLink started, exiting shell.."
|
||||
|
||||
# Exit shell to make it available to MAVLink
|
||||
|
|
|
@ -8,39 +8,40 @@
|
|||
#
|
||||
set MODE autostart
|
||||
|
||||
set logfile /fs/microsd/bootlog.txt
|
||||
set RC_FILE /fs/microsd/etc/rc.txt
|
||||
set CONFIG_FILE /fs/microsd/etc/config.txt
|
||||
set EXTRAS_FILE /fs/microsd/etc/extras.txt
|
||||
|
||||
set TUNE_OUT_ERROR ML<<CP4CP4CP4CP4CP4
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
echo "[init] Looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
set LOG_FILE /fs/microsd/bootlog.txt
|
||||
echo "[init] microSD card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
set LOG_FILE /dev/null
|
||||
echo "[init] No microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
#
|
||||
# Look for an init script on the microSD card.
|
||||
# Disable autostart if the script found.
|
||||
#
|
||||
# To prevent automatic startup in the current flight mode,
|
||||
# the script should set MODE to some other value.
|
||||
#
|
||||
if [ -f /fs/microsd/etc/rc ]
|
||||
if [ -f $RC_FILE ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc"
|
||||
sh /fs/microsd/etc/rc
|
||||
fi
|
||||
# Also consider rc.txt files
|
||||
if [ -f /fs/microsd/etc/rc.txt ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc.txt"
|
||||
sh /fs/microsd/etc/rc.txt
|
||||
echo "[init] Executing init script: $RC_FILE"
|
||||
sh $RC_FILE
|
||||
set MODE custom
|
||||
else
|
||||
echo "[init] Init script not found: $RC_FILE"
|
||||
fi
|
||||
|
||||
# if this is an APM build then there will be a rc.APM script
|
||||
|
@ -52,20 +53,19 @@ then
|
|||
echo "[init] USB interface connected"
|
||||
fi
|
||||
|
||||
echo "Running rc.APM"
|
||||
echo "[init] Running rc.APM"
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APM
|
||||
fi
|
||||
|
||||
if [ $MODE == autostart ]
|
||||
then
|
||||
echo "[init] AUTOSTART mode"
|
||||
|
||||
#
|
||||
# Start terminal
|
||||
# Start CDC/ACM serial driver
|
||||
#
|
||||
if sercon
|
||||
then
|
||||
echo "USB connected"
|
||||
fi
|
||||
sercon
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
|
@ -73,27 +73,20 @@ then
|
|||
uorb start
|
||||
|
||||
#
|
||||
# Load microSD params
|
||||
# Load parameters
|
||||
#
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
if mtd start
|
||||
then
|
||||
param select /fs/mtd_params
|
||||
if param load /fs/mtd_params
|
||||
then
|
||||
else
|
||||
echo "FAILED LOADING PARAMS"
|
||||
fi
|
||||
set PARAM_FILE /fs/mtd_params
|
||||
fi
|
||||
|
||||
param select $PARAM_FILE
|
||||
if param load
|
||||
then
|
||||
echo "[init] Parameters loaded: $PARAM_FILE"
|
||||
else
|
||||
param select /fs/microsd/params
|
||||
if [ -f /fs/microsd/params ]
|
||||
then
|
||||
if param load /fs/microsd/params
|
||||
then
|
||||
echo "Parameters loaded"
|
||||
else
|
||||
echo "Parameter file corrupt - ignoring"
|
||||
fi
|
||||
fi
|
||||
echo "[init] ERROR: Parameters loading failed: $PARAM_FILE"
|
||||
fi
|
||||
|
||||
#
|
||||
|
@ -101,355 +94,418 @@ then
|
|||
#
|
||||
if rgbled start
|
||||
then
|
||||
echo "Using external RGB Led"
|
||||
echo "[init] Using external RGB Led"
|
||||
else
|
||||
if blinkm start
|
||||
then
|
||||
echo "[init] Using blinkm"
|
||||
blinkm systemstate
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Set default values
|
||||
#
|
||||
set HIL no
|
||||
set VEHICLE_TYPE none
|
||||
set MIXER none
|
||||
set USE_IO yes
|
||||
set OUTPUT_MODE none
|
||||
set PWM_OUTPUTS none
|
||||
set PWM_RATE none
|
||||
set PWM_DISARMED none
|
||||
set PWM_MIN none
|
||||
set PWM_MAX none
|
||||
set MKBLCTRL_MODE none
|
||||
set FMU_MODE pwm
|
||||
set MAV_TYPE none
|
||||
|
||||
#
|
||||
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
set DO_AUTOCONFIG yes
|
||||
else
|
||||
set DO_AUTOCONFIG no
|
||||
fi
|
||||
|
||||
#
|
||||
# Set parameters and env variables for selected AUTOSTART
|
||||
#
|
||||
if param compare SYS_AUTOSTART 0
|
||||
then
|
||||
echo "[init] Don't try to find autostart script"
|
||||
else
|
||||
sh /etc/init.d/rc.autostart
|
||||
fi
|
||||
|
||||
#
|
||||
# Override parameters from user configuration file
|
||||
#
|
||||
if [ -f $CONFIG_FILE ]
|
||||
then
|
||||
echo "[init] Reading config: $CONFIG_FILE"
|
||||
sh $CONFIG_FILE
|
||||
else
|
||||
echo "[init] Config file not found: $CONFIG_FILE"
|
||||
fi
|
||||
|
||||
#
|
||||
# If autoconfig parameter was set, reset it and save parameters
|
||||
#
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
set IO_PRESENT no
|
||||
|
||||
if [ $USE_IO == yes ]
|
||||
then
|
||||
#
|
||||
# Check if PX4IO present and update firmware if needed
|
||||
#
|
||||
if [ -f /etc/extras/px4io-v2_default.bin ]
|
||||
then
|
||||
set IO_FILE /etc/extras/px4io-v2_default.bin
|
||||
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
|
||||
if px4io checkcrc $IO_FILE
|
||||
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"
|
||||
echo "PX4IO update failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
else
|
||||
echo "[init] ERROR: PX4IO update failed"
|
||||
echo "PX4IO update failed" >> $LOG_FILE
|
||||
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
|
||||
#
|
||||
if [ $OUTPUT_MODE == none ]
|
||||
then
|
||||
if [ $USE_IO == yes ]
|
||||
then
|
||||
set OUTPUT_MODE io
|
||||
else
|
||||
set OUTPUT_MODE fmu
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == io -a $IO_PRESENT != yes ]
|
||||
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 hw_ver compare PX4FMU_V1
|
||||
then
|
||||
set FMU_MODE serial
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $HIL == yes ]
|
||||
then
|
||||
set OUTPUT_MODE hil
|
||||
if hw_ver compare PX4FMU_V1
|
||||
then
|
||||
set FMU_MODE serial
|
||||
fi
|
||||
else
|
||||
# Try to get an USB console if not in HIL mode
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the Commander (needs to be this early for in-air-restarts)
|
||||
#
|
||||
commander start
|
||||
|
||||
if param compare SYS_AUTOSTART 1000
|
||||
then
|
||||
sh /etc/init.d/1000_rc_fw_easystar.hil
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1001
|
||||
then
|
||||
sh /etc/init.d/1001_rc_quad.hil
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1002
|
||||
then
|
||||
sh /etc/init.d/1002_rc_fw_state.hil
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1003
|
||||
then
|
||||
sh /etc/init.d/1003_rc_quad_+.hil
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1004
|
||||
then
|
||||
sh /etc/init.d/1004_rc_fw_Rascal110.hil
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if [ $MODE != custom ]
|
||||
then
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
|
||||
#
|
||||
# Upgrade PX4IO firmware
|
||||
# Start primary output
|
||||
#
|
||||
|
||||
if [ -f /etc/extras/px4io-v2_default.bin ]
|
||||
then
|
||||
set io_file /etc/extras/px4io-v2_default.bin
|
||||
else
|
||||
set io_file /etc/extras/px4io-v1_default.bin
|
||||
fi
|
||||
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO OK"
|
||||
echo "PX4IO OK" >> $logfile
|
||||
fi
|
||||
set TTYS1_BUSY no
|
||||
|
||||
if px4io checkcrc $io_file
|
||||
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
|
||||
if [ $OUTPUT_MODE != none ]
|
||||
then
|
||||
echo "PX4IO CRC OK"
|
||||
echo "PX4IO CRC OK" >> $logfile
|
||||
else
|
||||
echo "PX4IO CRC failure"
|
||||
echo "PX4IO CRC failure" >> $logfile
|
||||
tone_alarm MBABGP
|
||||
if px4io forceupdate 14662 $io_file
|
||||
if [ $OUTPUT_MODE == io ]
|
||||
then
|
||||
usleep 500000
|
||||
echo "[init] Use PX4IO PWM as primary output"
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO restart OK"
|
||||
echo "PX4IO restart OK" >> $logfile
|
||||
tone_alarm MSPAA
|
||||
echo "[init] PX4IO started"
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
echo "PX4IO restart failed"
|
||||
echo "PX4IO restart failed" >> $logfile
|
||||
tone_alarm MNGGG
|
||||
sleep 10
|
||||
reboot
|
||||
echo "[init] ERROR: PX4IO start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
if [ $OUTPUT_MODE == fmu ]
|
||||
then
|
||||
echo "[init] Use FMU PWM as primary output"
|
||||
if fmu mode_$FMU_MODE
|
||||
then
|
||||
echo "[init] FMU mode_$FMU_MODE started"
|
||||
else
|
||||
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
|
||||
if hw_ver compare PX4FMU_V1
|
||||
then
|
||||
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
if [ $FMU_MODE == pwm_gpio ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
if [ $OUTPUT_MODE == mkblctrl ]
|
||||
then
|
||||
echo "[init] Use MKBLCTRL as primary output"
|
||||
set MKBLCTRL_ARG ""
|
||||
if [ $MKBLCTRL_MODE == x ]
|
||||
then
|
||||
set MKBLCTRL_ARG "-mkmode x"
|
||||
fi
|
||||
if [ $MKBLCTRL_MODE == + ]
|
||||
then
|
||||
set MKBLCTRL_ARG "-mkmode +"
|
||||
fi
|
||||
|
||||
if mkblctrl $MKBLCTRL_ARG
|
||||
then
|
||||
echo "[init] MKBLCTRL started"
|
||||
else
|
||||
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"
|
||||
if hil mode_pwm
|
||||
then
|
||||
echo "[init] HIL output started"
|
||||
else
|
||||
echo "[init] ERROR: HIL output start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start IO or FMU for RC PPM input if needed
|
||||
#
|
||||
if [ $IO_PRESENT == yes ]
|
||||
then
|
||||
if [ $OUTPUT_MODE != io ]
|
||||
then
|
||||
if px4io start
|
||||
then
|
||||
echo "[init] PX4IO started"
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
echo "[init] ERROR: PX4IO start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
else
|
||||
echo "PX4IO update failed"
|
||||
echo "PX4IO update failed" >> $logfile
|
||||
tone_alarm MNGGG
|
||||
if [ $OUTPUT_MODE != fmu ]
|
||||
then
|
||||
if fmu mode_$FMU_MODE
|
||||
then
|
||||
echo "[init] FMU mode_$FMU_MODE started"
|
||||
else
|
||||
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
|
||||
if hw_ver compare PX4FMU_V1
|
||||
then
|
||||
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
if [ $FMU_MODE == pwm_gpio ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# MAVLink
|
||||
#
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Check if auto-setup from one of the standard scripts is wanted
|
||||
# SYS_AUTOSTART = 0 means no autostart (default)
|
||||
#
|
||||
# AUTOSTART PARTITION:
|
||||
# 0 .. 999 Reserved (historical)
|
||||
# 1000 .. 1999 Simulation setups
|
||||
# 2000 .. 2999 Standard planes
|
||||
# 3000 .. 3999 Flying wing
|
||||
# 4000 .. 4999 Quad X
|
||||
# 5000 .. 5999 Quad +
|
||||
# 6000 .. 6999 Hexa X
|
||||
# 7000 .. 7999 Hexa +
|
||||
# 8000 .. 8999 Octo X
|
||||
# 9000 .. 9999 Octo +
|
||||
# 10000 .. 10999 Wide arm / H frame
|
||||
# 11000 .. 11999 Hexa Cox
|
||||
# 12000 .. 12999 Octo Cox
|
||||
|
||||
if param compare SYS_AUTOSTART 4008 8
|
||||
if [ $HIL == yes ]
|
||||
then
|
||||
sh /etc/init.d/4008_ardrone
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4009 9
|
||||
then
|
||||
sh /etc/init.d/4009_ardrone_flow
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4010 10
|
||||
then
|
||||
set FRAME_GEOMETRY x
|
||||
set FRAME_COUNT 4
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
||||
set PWM_DISARMED 900
|
||||
sh /etc/init.d/4010_dji_f330
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4011 11
|
||||
then
|
||||
sh /etc/init.d/4011_dji_f450
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4012
|
||||
then
|
||||
sh /etc/init.d/666_fmu_q_x550
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 6012 12
|
||||
then
|
||||
set MIXER /etc/mixers/FMU_hex_x.mix
|
||||
sh /etc/init.d/rc.hexa
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 7013 13
|
||||
then
|
||||
set MIXER /etc/mixers/FMU_hex_+.mix
|
||||
sh /etc/init.d/rc.hexa
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 8001
|
||||
then
|
||||
set MIXER /etc/mixers/FMU_octo_x.mix
|
||||
sh /etc/init.d/rc.octo
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 9001
|
||||
then
|
||||
set MIXER /etc/mixers/FMU_octo_+.mix
|
||||
sh /etc/init.d/rc.octo
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 12001
|
||||
then
|
||||
set MIXER /etc/mixers/FMU_octo_cox.mix
|
||||
sh /etc/init.d/rc.octo
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10015 15
|
||||
then
|
||||
sh /etc/init.d/10015_tbs_discovery
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10016 16
|
||||
then
|
||||
sh /etc/init.d/10016_3dr_iris
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame
|
||||
if param compare SYS_AUTOSTART 4017 17
|
||||
then
|
||||
set MKBLCTRL_MODE no
|
||||
set MKBLCTRL_FRAME x
|
||||
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame
|
||||
if param compare SYS_AUTOSTART 5018 18
|
||||
then
|
||||
set MKBLCTRL_MODE no
|
||||
set MKBLCTRL_FRAME +
|
||||
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing
|
||||
if param compare SYS_AUTOSTART 4019 19
|
||||
then
|
||||
set MKBLCTRL_MODE yes
|
||||
set MKBLCTRL_FRAME x
|
||||
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing
|
||||
if param compare SYS_AUTOSTART 5020 20
|
||||
then
|
||||
set MKBLCTRL_MODE yes
|
||||
set MKBLCTRL_FRAME +
|
||||
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
|
||||
if param compare SYS_AUTOSTART 4021 21
|
||||
then
|
||||
set FRAME_GEOMETRY x
|
||||
set ESC_MAKER afro
|
||||
sh /etc/init.d/rc.custom_io_esc
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
|
||||
if param compare SYS_AUTOSTART 10022 22
|
||||
then
|
||||
set FRAME_GEOMETRY w
|
||||
sh /etc/init.d/rc.custom_io_esc
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3030 30
|
||||
then
|
||||
sh /etc/init.d/3030_io_camflyer
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3031 31
|
||||
then
|
||||
sh /etc/init.d/3031_io_phantom
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3032 32
|
||||
then
|
||||
sh /etc/init.d/3032_skywalker_x5
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3033 33
|
||||
then
|
||||
sh /etc/init.d/3033_io_wingwing
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3034 34
|
||||
then
|
||||
sh /etc/init.d/3034_io_fx79
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 40
|
||||
then
|
||||
sh /etc/init.d/40_io_segway
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2100 100
|
||||
then
|
||||
sh /etc/init.d/2100_mpx_easystar
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2101 101
|
||||
then
|
||||
sh /etc/init.d/2101_hk_bixler
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2102 102
|
||||
then
|
||||
sh /etc/init.d/2102_3dr_skywalker
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 800
|
||||
then
|
||||
sh /etc/init.d/800_sdlogger
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# Start any custom extensions that might be missing
|
||||
if [ -f /fs/microsd/etc/rc.local ]
|
||||
then
|
||||
sh /fs/microsd/etc/rc.local
|
||||
fi
|
||||
|
||||
# If none of the autostart scripts triggered, get a minimal setup
|
||||
if [ $MODE == autostart ]
|
||||
then
|
||||
# Telemetry port is on both FMU boards ttyS1
|
||||
# but the AR.Drone motors can be get 'flashed'
|
||||
# if starting MAVLink on them - so do not
|
||||
# start it as default (default link: USB)
|
||||
|
||||
# Start commander
|
||||
commander start
|
||||
|
||||
# Start px4io if present
|
||||
if px4io detect
|
||||
sleep 1
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
usleep 5000
|
||||
else
|
||||
if [ $TTYS1_BUSY == yes ]
|
||||
then
|
||||
px4io start
|
||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
||||
mavlink start -d /dev/ttyS0
|
||||
usleep 5000
|
||||
|
||||
# Exit from nsh to free port for mavlink
|
||||
set EXIT_ON_END yes
|
||||
else
|
||||
if fmu mode_serial
|
||||
# Start MAVLink on default port: ttyS1
|
||||
mavlink start
|
||||
usleep 5000
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Sensors, Logging, GPS
|
||||
#
|
||||
echo "[init] Start sensors"
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
if [ $HIL == no ]
|
||||
then
|
||||
echo "[init] Start logging"
|
||||
sh /etc/init.d/rc.logging
|
||||
|
||||
echo "[init] Start GPS"
|
||||
gps start
|
||||
fi
|
||||
|
||||
#
|
||||
# Fixed wing setup
|
||||
#
|
||||
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
|
||||
sh /etc/init.d/rc.fw_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# Multicopters setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == mc ]
|
||||
then
|
||||
echo "[init] Vehicle type: MULTICOPTER"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
# Set default mixer for multicopter if not defined
|
||||
set MIXER quad_x
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
# Use MAV_TYPE = 2 (quadcopter) if not defined
|
||||
set MAV_TYPE 2
|
||||
|
||||
# Use mixer to detect vehicle type
|
||||
if [ $MIXER == FMU_hex_x -o $MIXER == FMU_hex_+ ]
|
||||
then
|
||||
echo "FMU driver (no PWM) started"
|
||||
param set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == FMU_octo_x -o $MIXER == FMU_octo_+ ]
|
||||
then
|
||||
param set MAV_TYPE 14
|
||||
fi
|
||||
if [ $MIXER == FMU_octo_cox ]
|
||||
then
|
||||
param set MAV_TYPE 14
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start sensors
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
# Start one of the estimators
|
||||
attitude_estimator_ekf start
|
||||
|
||||
# Start GPS
|
||||
gps start
|
||||
|
||||
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
# Start standard multicopter apps
|
||||
sh /etc/init.d/rc.mc_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# Generic setup (autostart ID not found)
|
||||
#
|
||||
if [ $VEHICLE_TYPE == none ]
|
||||
then
|
||||
echo "[init] Vehicle type: GENERIC"
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
fi
|
||||
|
||||
# Start any custom addons
|
||||
if [ -f $EXTRAS_FILE ]
|
||||
then
|
||||
echo "[init] Starting addons script: $EXTRAS_FILE"
|
||||
sh $EXTRAS_FILE
|
||||
else
|
||||
echo "[init] Addons script not found: $EXTRAS_FILE"
|
||||
fi
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
|
|
|
@ -25,13 +25,13 @@ for the elevons.
|
|||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -5000 -8000 0 -10000 10000
|
||||
S: 0 1 8000 8000 0 -10000 10000
|
||||
S: 0 0 -8000 -8000 0 -10000 10000
|
||||
S: 0 1 6000 6000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -8000 -5000 0 -10000 10000
|
||||
S: 0 1 -8000 -8000 0 -10000 10000
|
||||
S: 0 0 -8000 -8000 0 -10000 10000
|
||||
S: 0 1 -6000 -6000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
|
|
|
@ -1,2 +1,3 @@
|
|||
parameters.wiki
|
||||
parameters.xml
|
||||
parameters.xml
|
||||
cookies.txt
|
|
@ -1,10 +1,24 @@
|
|||
import output
|
||||
from xml.sax.saxutils import escape
|
||||
|
||||
class DokuWikiOutput(output.Output):
|
||||
def Generate(self, groups):
|
||||
result = ""
|
||||
pre_text = """<?xml version='1.0'?>
|
||||
<methodCall>
|
||||
<methodName>wiki.putPage</methodName>
|
||||
<params>
|
||||
<param>
|
||||
<value>
|
||||
<string>:firmware:parameters</string>
|
||||
</value>
|
||||
</param>
|
||||
<param>
|
||||
<value>
|
||||
<string>"""
|
||||
result = "====== Parameter Reference ======\nThis list is auto-generated every few minutes and contains the most recent parameter names and default values."
|
||||
for group in groups:
|
||||
result += "==== %s ====\n\n" % group.GetName()
|
||||
result += "|< 100% 20% 20% 10% 10% 10% 30%>|\n"
|
||||
result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n"
|
||||
for param in group.GetParams():
|
||||
code = param.GetFieldValue("code")
|
||||
|
@ -13,25 +27,36 @@ class DokuWikiOutput(output.Output):
|
|||
result += "| %s | %s " % (code, name)
|
||||
min_val = param.GetFieldValue("min")
|
||||
if min_val is not None:
|
||||
result += "| %s " % min_val
|
||||
result += " | %s " % min_val
|
||||
else:
|
||||
result += "|"
|
||||
result += " | "
|
||||
max_val = param.GetFieldValue("max")
|
||||
if max_val is not None:
|
||||
result += "| %s " % max_val
|
||||
result += " | %s " % max_val
|
||||
else:
|
||||
result += "|"
|
||||
result += " | "
|
||||
def_val = param.GetFieldValue("default")
|
||||
if def_val is not None:
|
||||
result += "| %s " % def_val
|
||||
else:
|
||||
result += "|"
|
||||
result += " | "
|
||||
long_desc = param.GetFieldValue("long_desc")
|
||||
if long_desc is not None:
|
||||
long_desc = long_desc.replace("\n", "")
|
||||
result += "| %s " % long_desc
|
||||
else:
|
||||
result += "|"
|
||||
result += "|\n"
|
||||
result += " | "
|
||||
result += " |\n"
|
||||
result += "\n"
|
||||
return result
|
||||
post_text = """</string>
|
||||
</value>
|
||||
</param>
|
||||
<param>
|
||||
<value>
|
||||
<name>sum</name>
|
||||
<string>Updated parameters automagically from code.</string>
|
||||
</value>
|
||||
</param>
|
||||
</params>
|
||||
</methodCall>"""
|
||||
return pre_text + escape(result) + post_text
|
||||
|
|
|
@ -0,0 +1,5 @@
|
|||
python px_process_params.py
|
||||
|
||||
rm cookies.txt
|
||||
curl --cookie cookies.txt --cookie-jar cookies.txt --user-agent Mozilla/4.0 --data "u=$XMLRPCUSER&p=$XMLRPCPASS" https://pixhawk.org/start?do=login
|
||||
curl -k --cookie cookies.txt -H "Content-Type: application/xml" -X POST --data-binary @parameters.wiki "https://pixhawk.org/lib/exe/xmlrpc.php"
|
|
@ -50,6 +50,9 @@
|
|||
# Currently only used for informational purposes.
|
||||
#
|
||||
|
||||
# for python2.7 compatibility
|
||||
from __future__ import print_function
|
||||
|
||||
import sys
|
||||
import argparse
|
||||
import binascii
|
||||
|
@ -154,6 +157,8 @@ class uploader(object):
|
|||
PROG_MULTI = b'\x27'
|
||||
READ_MULTI = b'\x28' # rev2 only
|
||||
GET_CRC = b'\x29' # rev3+
|
||||
GET_OTP = b'\x2a' # rev4+ , get a word from OTP area
|
||||
GET_SN = b'\x2b' # rev4+ , get a word from SN area
|
||||
REBOOT = b'\x30'
|
||||
|
||||
INFO_BL_REV = b'\x01' # bootloader protocol revision
|
||||
|
@ -175,6 +180,8 @@ class uploader(object):
|
|||
def __init__(self, portname, baudrate):
|
||||
# open the port, keep the default timeout short so we can poll quickly
|
||||
self.port = serial.Serial(portname, baudrate, timeout=0.5)
|
||||
self.otp = b''
|
||||
self.sn = b''
|
||||
|
||||
def close(self):
|
||||
if self.port is not None:
|
||||
|
@ -237,6 +244,22 @@ class uploader(object):
|
|||
self.__getSync()
|
||||
return value
|
||||
|
||||
# send the GET_OTP command and wait for an info parameter
|
||||
def __getOTP(self, param):
|
||||
t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array.
|
||||
self.__send(uploader.GET_OTP + t + uploader.EOC)
|
||||
value = self.__recv(4)
|
||||
self.__getSync()
|
||||
return value
|
||||
|
||||
# send the GET_OTP command and wait for an info parameter
|
||||
def __getSN(self, param):
|
||||
t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array.
|
||||
self.__send(uploader.GET_SN + t + uploader.EOC)
|
||||
value = self.__recv(4)
|
||||
self.__getSync()
|
||||
return value
|
||||
|
||||
# send the CHIP_ERASE command and wait for the bootloader to become ready
|
||||
def __erase(self):
|
||||
self.__send(uploader.CHIP_ERASE
|
||||
|
@ -353,6 +376,31 @@ class uploader(object):
|
|||
if self.fw_maxsize < fw.property('image_size'):
|
||||
raise RuntimeError("Firmware image is too large for this board")
|
||||
|
||||
# OTP added in v4:
|
||||
if self.bl_rev > 3:
|
||||
for byte in range(0,32*6,4):
|
||||
x = self.__getOTP(byte)
|
||||
self.otp = self.otp + x
|
||||
print(binascii.hexlify(x).decode('utf-8') + ' ', end='')
|
||||
# see src/modules/systemlib/otp.h in px4 code:
|
||||
self.otp_id = self.otp[0:4]
|
||||
self.otp_idtype = self.otp[4:5]
|
||||
self.otp_vid = self.otp[8:4:-1]
|
||||
self.otp_pid = self.otp[12:8:-1]
|
||||
self.otp_coa = self.otp[32:160]
|
||||
# show user:
|
||||
print("type: " + self.otp_id.decode('utf-8'))
|
||||
print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('utf-8'))
|
||||
print("vid: " + binascii.hexlify(self.otp_vid).decode('utf-8'))
|
||||
print("pid: "+ binascii.hexlify(self.otp_pid).decode('utf-8'))
|
||||
print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('utf-8'))
|
||||
print("sn: ", end='')
|
||||
for byte in range(0,12,4):
|
||||
x = self.__getSN(byte)
|
||||
x = x[::-1] # reverse the bytes
|
||||
self.sn = self.sn + x
|
||||
print(binascii.hexlify(x).decode('utf-8'), end='') # show user
|
||||
print('')
|
||||
print("erase...")
|
||||
self.__erase()
|
||||
|
||||
|
|
|
@ -10,11 +10,13 @@ LIBS=-lm
|
|||
#_DEPS = test.h
|
||||
#DEPS = $(patsubst %,$(IDIR)/%,$(_DEPS))
|
||||
|
||||
_OBJ = mixer_test.o test_mixer.o mixer_simple.o mixer_multirotor.o mixer.o mixer_group.o mixer_load.o
|
||||
_OBJ = mixer_test.o test_mixer.o mixer_simple.o mixer_multirotor.o \
|
||||
mixer.o mixer_group.o mixer_load.o test_conv.o pwm_limit.o hrt.o
|
||||
OBJ = $(patsubst %,$(ODIR)/%,$(_OBJ))
|
||||
|
||||
#$(DEPS)
|
||||
$(ODIR)/%.o: %.cpp
|
||||
mkdir -p obj
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/systemcmds/tests/%.cpp
|
||||
|
@ -26,6 +28,12 @@ $(ODIR)/%.o: ../../src/modules/systemlib/%.cpp
|
|||
$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.cpp
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/modules/systemlib/pwm_limit/%.cpp
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/modules/systemlib/pwm_limit/%.c
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.c
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
|
|
|
@ -0,0 +1,16 @@
|
|||
#include <sys/time.h>
|
||||
#include <inttypes.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <stdio.h>
|
||||
|
||||
hrt_abstime hrt_absolute_time() {
|
||||
struct timeval te;
|
||||
gettimeofday(&te, NULL); // get current time
|
||||
hrt_abstime us = static_cast<uint64_t>(te.tv_sec) * 1e6 + te.tv_usec; // caculate us
|
||||
return us;
|
||||
}
|
||||
|
||||
hrt_abstime hrt_elapsed_time(const volatile hrt_abstime *then) {
|
||||
// not thread safe
|
||||
return hrt_absolute_time() - *then;
|
||||
}
|
|
@ -9,4 +9,6 @@ int main(int argc, char *argv[]) {
|
|||
"../../ROMFS/px4fmu_common/mixers/FMU_quad_w.mix"};
|
||||
|
||||
test_mixer(3, args);
|
||||
|
||||
test_conv(1, args);
|
||||
}
|
|
@ -0,0 +1,133 @@
|
|||
/************************************************************************
|
||||
* include/queue.h
|
||||
*
|
||||
* Copyright (C) 2007-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 __INCLUDE_QUEUE_H
|
||||
#define __INCLUDE_QUEUE_H
|
||||
|
||||
#ifndef FAR
|
||||
#define FAR
|
||||
#endif
|
||||
|
||||
/************************************************************************
|
||||
* Included Files
|
||||
************************************************************************/
|
||||
|
||||
#include <sys/types.h>
|
||||
|
||||
/************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************/
|
||||
|
||||
#define sq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
|
||||
#define dq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
|
||||
|
||||
#define sq_next(p) ((p)->flink)
|
||||
#define dq_next(p) ((p)->flink)
|
||||
#define dq_prev(p) ((p)->blink)
|
||||
|
||||
#define sq_empty(q) ((q)->head == NULL)
|
||||
#define dq_empty(q) ((q)->head == NULL)
|
||||
|
||||
#define sq_peek(q) ((q)->head)
|
||||
#define dq_peek(q) ((q)->head)
|
||||
|
||||
/************************************************************************
|
||||
* Global Type Declarations
|
||||
************************************************************************/
|
||||
|
||||
struct sq_entry_s
|
||||
{
|
||||
FAR struct sq_entry_s *flink;
|
||||
};
|
||||
typedef struct sq_entry_s sq_entry_t;
|
||||
|
||||
struct dq_entry_s
|
||||
{
|
||||
FAR struct dq_entry_s *flink;
|
||||
FAR struct dq_entry_s *blink;
|
||||
};
|
||||
typedef struct dq_entry_s dq_entry_t;
|
||||
|
||||
struct sq_queue_s
|
||||
{
|
||||
FAR sq_entry_t *head;
|
||||
FAR sq_entry_t *tail;
|
||||
};
|
||||
typedef struct sq_queue_s sq_queue_t;
|
||||
|
||||
struct dq_queue_s
|
||||
{
|
||||
FAR dq_entry_t *head;
|
||||
FAR dq_entry_t *tail;
|
||||
};
|
||||
typedef struct dq_queue_s dq_queue_t;
|
||||
|
||||
/************************************************************************
|
||||
* Global Function Prototypes
|
||||
************************************************************************/
|
||||
|
||||
#ifdef __cplusplus
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
EXTERN void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue);
|
||||
EXTERN void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue);
|
||||
EXTERN void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue);
|
||||
EXTERN void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue);
|
||||
EXTERN void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node,
|
||||
sq_queue_t *queue);
|
||||
EXTERN void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node,
|
||||
dq_queue_t *queue);
|
||||
EXTERN void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node,
|
||||
dq_queue_t *queue);
|
||||
|
||||
EXTERN FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue);
|
||||
EXTERN void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue);
|
||||
EXTERN void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue);
|
||||
EXTERN FAR sq_entry_t *sq_remlast(sq_queue_t *queue);
|
||||
EXTERN FAR dq_entry_t *dq_remlast(dq_queue_t *queue);
|
||||
EXTERN FAR sq_entry_t *sq_remfirst(sq_queue_t *queue);
|
||||
EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue);
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __INCLUDE_QUEUE_H_ */
|
||||
|
|
@ -1,146 +0,0 @@
|
|||
#
|
||||
# Makefile for the px4fmu_default configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS.
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
|
||||
ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v1_default.bin
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/stm32/adc
|
||||
MODULES += drivers/stm32/tone_alarm
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/px4io
|
||||
MODULES += drivers/px4fmu
|
||||
MODULES += drivers/boards/px4fmu-v1
|
||||
MODULES += drivers/ardrone_interface
|
||||
MODULES += drivers/l3gd20
|
||||
MODULES += drivers/bma180
|
||||
MODULES += drivers/mpu6000
|
||||
MODULES += drivers/hmc5883
|
||||
MODULES += drivers/ms5611
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/blinkm
|
||||
MODULES += drivers/rgbled
|
||||
MODULES += drivers/roboclaw
|
||||
MODULES += drivers/airspeed
|
||||
MODULES += drivers/ets_airspeed
|
||||
MODULES += drivers/meas_airspeed
|
||||
MODULES += modules/sensors
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/eeprom
|
||||
MODULES += systemcmds/ramtron
|
||||
MODULES += systemcmds/bl_update
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/i2c
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/preflight_check
|
||||
MODULES += systemcmds/pwm
|
||||
MODULES += systemcmds/esc_calib
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/top
|
||||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
MODULES += modules/commander
|
||||
MODULES += modules/navigator
|
||||
MODULES += modules/mavlink
|
||||
MODULES += modules/mavlink_onboard
|
||||
MODULES += modules/gpio_led
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/att_pos_estimator_ekf
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
MODULES += modules/fixedwing_backside
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
MODULES += modules/sdlog2
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
#MODULES += modules/unit_test
|
||||
#MODULES += modules/commander/commander_tests
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/controllib
|
||||
MODULES += modules/uORB
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/ecl
|
||||
MODULES += lib/external_lgpl
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/conversion
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
#MODULES += examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/hello_sky
|
||||
#MODULES += examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/daemon
|
||||
#MODULES += examples/px4_daemon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/debug_values
|
||||
#MODULES += examples/px4_mavlink_debug
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
|
||||
#MODULES += examples/fixedwing_control
|
||||
|
||||
# Hardware test
|
||||
#MODULES += examples/hwtest
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
# In general, these should move to modules over time.
|
||||
#
|
||||
# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B
|
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef
|
||||
|
||||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, sercon, , 2048, sercon_main ) \
|
||||
$(call _B, serdis, , 2048, serdis_main ) \
|
||||
$(call _B, sysinfo, , 2048, sysinfo_main )
|
|
@ -42,8 +42,7 @@ MODULES += modules/sensors
|
|||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/eeprom
|
||||
MODULES += systemcmds/ramtron
|
||||
MODULES += systemcmds/mtd
|
||||
MODULES += systemcmds/bl_update
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/i2c
|
||||
|
@ -58,6 +57,7 @@ MODULES += systemcmds/top
|
|||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
MODULES += systemcmds/hw_ver
|
||||
|
||||
#
|
||||
# General system control
|
||||
|
|
|
@ -1,51 +0,0 @@
|
|||
#
|
||||
# Makefile for the px4fmu_default configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS.
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test
|
||||
ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v1_default.bin
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/stm32/adc
|
||||
MODULES += drivers/stm32/tone_alarm
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/boards/px4fmu-v1
|
||||
MODULES += drivers/px4io
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/nshterm
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/uORB
|
||||
LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
# In general, these should move to modules over time.
|
||||
#
|
||||
# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B
|
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef
|
||||
|
||||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, sercon, , 2048, sercon_main ) \
|
||||
$(call _B, serdis, , 2048, serdis_main )
|
|
@ -38,6 +38,8 @@ MODULES += drivers/ets_airspeed
|
|||
MODULES += drivers/meas_airspeed
|
||||
MODULES += drivers/frsky_telemetry
|
||||
MODULES += modules/sensors
|
||||
MODULES += drivers/mkblctrl
|
||||
|
||||
|
||||
# Needs to be burned to the ground and re-written; for now,
|
||||
# just don't build it.
|
||||
|
@ -46,7 +48,6 @@ MODULES += modules/sensors
|
|||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/ramtron
|
||||
MODULES += systemcmds/bl_update
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/mixer
|
||||
|
@ -61,6 +62,7 @@ MODULES += systemcmds/tests
|
|||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
MODULES += systemcmds/mtd
|
||||
MODULES += systemcmds/hw_ver
|
||||
|
||||
#
|
||||
# General system control
|
||||
|
|
|
@ -29,6 +29,7 @@ MODULES += systemcmds/reboot
|
|||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/nshterm
|
||||
MODULES += systemcmds/mtd
|
||||
MODULES += systemcmds/hw_ver
|
||||
|
||||
#
|
||||
# Library modules
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,287 @@
|
|||
// MESSAGE AHRS2 PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_AHRS2 178
|
||||
|
||||
typedef struct __mavlink_ahrs2_t
|
||||
{
|
||||
float roll; ///< Roll angle (rad)
|
||||
float pitch; ///< Pitch angle (rad)
|
||||
float yaw; ///< Yaw angle (rad)
|
||||
float altitude; ///< Altitude (MSL)
|
||||
int32_t lat; ///< Latitude in degrees * 1E7
|
||||
int32_t lng; ///< Longitude in degrees * 1E7
|
||||
} mavlink_ahrs2_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_AHRS2_LEN 24
|
||||
#define MAVLINK_MSG_ID_178_LEN 24
|
||||
|
||||
#define MAVLINK_MSG_ID_AHRS2_CRC 47
|
||||
#define MAVLINK_MSG_ID_178_CRC 47
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_AHRS2 { \
|
||||
"AHRS2", \
|
||||
6, \
|
||||
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs2_t, roll) }, \
|
||||
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs2_t, pitch) }, \
|
||||
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs2_t, yaw) }, \
|
||||
{ "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs2_t, altitude) }, \
|
||||
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs2_t, lat) }, \
|
||||
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs2_t, lng) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a ahrs2 message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param roll Roll angle (rad)
|
||||
* @param pitch Pitch angle (rad)
|
||||
* @param yaw Yaw angle (rad)
|
||||
* @param altitude Altitude (MSL)
|
||||
* @param lat Latitude in degrees * 1E7
|
||||
* @param lng Longitude in degrees * 1E7
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_ahrs2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_AHRS2_LEN];
|
||||
_mav_put_float(buf, 0, roll);
|
||||
_mav_put_float(buf, 4, pitch);
|
||||
_mav_put_float(buf, 8, yaw);
|
||||
_mav_put_float(buf, 12, altitude);
|
||||
_mav_put_int32_t(buf, 16, lat);
|
||||
_mav_put_int32_t(buf, 20, lng);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#else
|
||||
mavlink_ahrs2_t packet;
|
||||
packet.roll = roll;
|
||||
packet.pitch = pitch;
|
||||
packet.yaw = yaw;
|
||||
packet.altitude = altitude;
|
||||
packet.lat = lat;
|
||||
packet.lng = lng;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_AHRS2;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a ahrs2 message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param roll Roll angle (rad)
|
||||
* @param pitch Pitch angle (rad)
|
||||
* @param yaw Yaw angle (rad)
|
||||
* @param altitude Altitude (MSL)
|
||||
* @param lat Latitude in degrees * 1E7
|
||||
* @param lng Longitude in degrees * 1E7
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_ahrs2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
float roll,float pitch,float yaw,float altitude,int32_t lat,int32_t lng)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_AHRS2_LEN];
|
||||
_mav_put_float(buf, 0, roll);
|
||||
_mav_put_float(buf, 4, pitch);
|
||||
_mav_put_float(buf, 8, yaw);
|
||||
_mav_put_float(buf, 12, altitude);
|
||||
_mav_put_int32_t(buf, 16, lat);
|
||||
_mav_put_int32_t(buf, 20, lng);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#else
|
||||
mavlink_ahrs2_t packet;
|
||||
packet.roll = roll;
|
||||
packet.pitch = pitch;
|
||||
packet.yaw = yaw;
|
||||
packet.altitude = altitude;
|
||||
packet.lat = lat;
|
||||
packet.lng = lng;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_AHRS2;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a ahrs2 struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param ahrs2 C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_ahrs2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2)
|
||||
{
|
||||
return mavlink_msg_ahrs2_pack(system_id, component_id, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a ahrs2 struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param ahrs2 C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_ahrs2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2)
|
||||
{
|
||||
return mavlink_msg_ahrs2_pack_chan(system_id, component_id, chan, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a ahrs2 message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param roll Roll angle (rad)
|
||||
* @param pitch Pitch angle (rad)
|
||||
* @param yaw Yaw angle (rad)
|
||||
* @param altitude Altitude (MSL)
|
||||
* @param lat Latitude in degrees * 1E7
|
||||
* @param lng Longitude in degrees * 1E7
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_ahrs2_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_AHRS2_LEN];
|
||||
_mav_put_float(buf, 0, roll);
|
||||
_mav_put_float(buf, 4, pitch);
|
||||
_mav_put_float(buf, 8, yaw);
|
||||
_mav_put_float(buf, 12, altitude);
|
||||
_mav_put_int32_t(buf, 16, lat);
|
||||
_mav_put_int32_t(buf, 20, lng);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_ahrs2_t packet;
|
||||
packet.roll = roll;
|
||||
packet.pitch = pitch;
|
||||
packet.yaw = yaw;
|
||||
packet.altitude = altitude;
|
||||
packet.lat = lat;
|
||||
packet.lng = lng;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)&packet, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)&packet, MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE AHRS2 UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field roll from ahrs2 message
|
||||
*
|
||||
* @return Roll angle (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_ahrs2_get_roll(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field pitch from ahrs2 message
|
||||
*
|
||||
* @return Pitch angle (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_ahrs2_get_pitch(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field yaw from ahrs2 message
|
||||
*
|
||||
* @return Yaw angle (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_ahrs2_get_yaw(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field altitude from ahrs2 message
|
||||
*
|
||||
* @return Altitude (MSL)
|
||||
*/
|
||||
static inline float mavlink_msg_ahrs2_get_altitude(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field lat from ahrs2 message
|
||||
*
|
||||
* @return Latitude in degrees * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_ahrs2_get_lat(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field lng from ahrs2 message
|
||||
*
|
||||
* @return Longitude in degrees * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_ahrs2_get_lng(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a ahrs2 message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param ahrs2 C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_ahrs2_decode(const mavlink_message_t* msg, mavlink_ahrs2_t* ahrs2)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
ahrs2->roll = mavlink_msg_ahrs2_get_roll(msg);
|
||||
ahrs2->pitch = mavlink_msg_ahrs2_get_pitch(msg);
|
||||
ahrs2->yaw = mavlink_msg_ahrs2_get_yaw(msg);
|
||||
ahrs2->altitude = mavlink_msg_ahrs2_get_altitude(msg);
|
||||
ahrs2->lat = mavlink_msg_ahrs2_get_lat(msg);
|
||||
ahrs2->lng = mavlink_msg_ahrs2_get_lng(msg);
|
||||
#else
|
||||
memcpy(ahrs2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AHRS2_LEN);
|
||||
#endif
|
||||
}
|
|
@ -1398,6 +1398,59 @@ static void mavlink_test_rally_fetch_point(uint8_t system_id, uint8_t component_
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_ahrs2(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_ahrs2_t packet_in = {
|
||||
17.0,
|
||||
}45.0,
|
||||
}73.0,
|
||||
}101.0,
|
||||
}963498296,
|
||||
}963498504,
|
||||
};
|
||||
mavlink_ahrs2_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.roll = packet_in.roll;
|
||||
packet1.pitch = packet_in.pitch;
|
||||
packet1.yaw = packet_in.yaw;
|
||||
packet1.altitude = packet_in.altitude;
|
||||
packet1.lat = packet_in.lat;
|
||||
packet1.lng = packet_in.lng;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_ahrs2_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_ahrs2_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_ahrs2_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.altitude , packet1.lat , packet1.lng );
|
||||
mavlink_msg_ahrs2_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_ahrs2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.altitude , packet1.lat , packet1.lng );
|
||||
mavlink_msg_ahrs2_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_ahrs2_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_ahrs2_send(MAVLINK_COMM_1 , packet1.roll , packet1.pitch , packet1.yaw , packet1.altitude , packet1.lat , packet1.lng );
|
||||
mavlink_msg_ahrs2_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
|
||||
|
@ -1426,6 +1479,7 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
|
|||
mavlink_test_airspeed_autocal(system_id, component_id, last_msg);
|
||||
mavlink_test_rally_point(system_id, component_id, last_msg);
|
||||
mavlink_test_rally_fetch_point(system_id, component_id, last_msg);
|
||||
mavlink_test_ahrs2(system_id, component_id, last_msg);
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
|
|
@ -5,8 +5,8 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Mon Dec 16 08:56:32 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Feb 4 15:27:33 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
#endif // MAVLINK_VERSION_H
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -5,8 +5,8 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Mon Dec 16 09:03:20 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Feb 4 15:27:43 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
#endif // MAVLINK_VERSION_H
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -1,23 +1,23 @@
|
|||
// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 193
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130
|
||||
|
||||
typedef struct __mavlink_data_transmission_handshake_t
|
||||
{
|
||||
uint32_t size; ///< total data size in bytes (set on ACK only)
|
||||
uint16_t width; ///< Width of a matrix or image
|
||||
uint16_t height; ///< Height of a matrix or image
|
||||
uint16_t packets; ///< number of packets beeing sent (set on ACK only)
|
||||
uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
|
||||
uint8_t packets; ///< number of packets beeing sent (set on ACK only)
|
||||
uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
|
||||
uint8_t jpg_quality; ///< JPEG quality out of [1,100]
|
||||
} mavlink_data_transmission_handshake_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 12
|
||||
#define MAVLINK_MSG_ID_193_LEN 12
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13
|
||||
#define MAVLINK_MSG_ID_130_LEN 13
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 23
|
||||
#define MAVLINK_MSG_ID_193_CRC 23
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29
|
||||
#define MAVLINK_MSG_ID_130_CRC 29
|
||||
|
||||
|
||||
|
||||
|
@ -27,10 +27,10 @@ typedef struct __mavlink_data_transmission_handshake_t
|
|||
{ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
|
||||
{ "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \
|
||||
{ "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \
|
||||
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, type) }, \
|
||||
{ "packets", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
|
||||
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
|
||||
{ "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
|
||||
{ "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
|
||||
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
|
||||
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
|
||||
{ "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
@ -51,17 +51,17 @@ typedef struct __mavlink_data_transmission_handshake_t
|
|||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
|
||||
uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
|
||||
_mav_put_uint32_t(buf, 0, size);
|
||||
_mav_put_uint16_t(buf, 4, width);
|
||||
_mav_put_uint16_t(buf, 6, height);
|
||||
_mav_put_uint8_t(buf, 8, type);
|
||||
_mav_put_uint8_t(buf, 9, packets);
|
||||
_mav_put_uint8_t(buf, 10, payload);
|
||||
_mav_put_uint8_t(buf, 11, jpg_quality);
|
||||
_mav_put_uint16_t(buf, 8, packets);
|
||||
_mav_put_uint8_t(buf, 10, type);
|
||||
_mav_put_uint8_t(buf, 11, payload);
|
||||
_mav_put_uint8_t(buf, 12, jpg_quality);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#else
|
||||
|
@ -69,8 +69,8 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst
|
|||
packet.size = size;
|
||||
packet.width = width;
|
||||
packet.height = height;
|
||||
packet.type = type;
|
||||
packet.packets = packets;
|
||||
packet.type = type;
|
||||
packet.payload = payload;
|
||||
packet.jpg_quality = jpg_quality;
|
||||
|
||||
|
@ -102,17 +102,17 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint8_t packets,uint8_t payload,uint8_t jpg_quality)
|
||||
uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
|
||||
_mav_put_uint32_t(buf, 0, size);
|
||||
_mav_put_uint16_t(buf, 4, width);
|
||||
_mav_put_uint16_t(buf, 6, height);
|
||||
_mav_put_uint8_t(buf, 8, type);
|
||||
_mav_put_uint8_t(buf, 9, packets);
|
||||
_mav_put_uint8_t(buf, 10, payload);
|
||||
_mav_put_uint8_t(buf, 11, jpg_quality);
|
||||
_mav_put_uint16_t(buf, 8, packets);
|
||||
_mav_put_uint8_t(buf, 10, type);
|
||||
_mav_put_uint8_t(buf, 11, payload);
|
||||
_mav_put_uint8_t(buf, 12, jpg_quality);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#else
|
||||
|
@ -120,8 +120,8 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t
|
|||
packet.size = size;
|
||||
packet.width = width;
|
||||
packet.height = height;
|
||||
packet.type = type;
|
||||
packet.packets = packets;
|
||||
packet.type = type;
|
||||
packet.payload = payload;
|
||||
packet.jpg_quality = jpg_quality;
|
||||
|
||||
|
@ -177,17 +177,17 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8
|
|||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
|
||||
static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
|
||||
_mav_put_uint32_t(buf, 0, size);
|
||||
_mav_put_uint16_t(buf, 4, width);
|
||||
_mav_put_uint16_t(buf, 6, height);
|
||||
_mav_put_uint8_t(buf, 8, type);
|
||||
_mav_put_uint8_t(buf, 9, packets);
|
||||
_mav_put_uint8_t(buf, 10, payload);
|
||||
_mav_put_uint8_t(buf, 11, jpg_quality);
|
||||
_mav_put_uint16_t(buf, 8, packets);
|
||||
_mav_put_uint8_t(buf, 10, type);
|
||||
_mav_put_uint8_t(buf, 11, payload);
|
||||
_mav_put_uint8_t(buf, 12, jpg_quality);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
|
||||
|
@ -199,8 +199,8 @@ static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_
|
|||
packet.size = size;
|
||||
packet.width = width;
|
||||
packet.height = height;
|
||||
packet.type = type;
|
||||
packet.packets = packets;
|
||||
packet.type = type;
|
||||
packet.payload = payload;
|
||||
packet.jpg_quality = jpg_quality;
|
||||
|
||||
|
@ -224,7 +224,7 @@ static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_
|
|||
*/
|
||||
static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 8);
|
||||
return _MAV_RETURN_uint8_t(msg, 10);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -262,9 +262,9 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const
|
|||
*
|
||||
* @return number of packets beeing sent (set on ACK only)
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
|
||||
static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 9);
|
||||
return _MAV_RETURN_uint16_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -274,7 +274,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const
|
|||
*/
|
||||
static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 10);
|
||||
return _MAV_RETURN_uint8_t(msg, 11);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -284,7 +284,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const
|
|||
*/
|
||||
static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 11);
|
||||
return _MAV_RETURN_uint8_t(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -299,8 +299,8 @@ static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_
|
|||
data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg);
|
||||
data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg);
|
||||
data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg);
|
||||
data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
|
||||
data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg);
|
||||
data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
|
||||
data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg);
|
||||
data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg);
|
||||
#else
|
|
@ -1,6 +1,6 @@
|
|||
// MESSAGE ENCAPSULATED_DATA PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 194
|
||||
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131
|
||||
|
||||
typedef struct __mavlink_encapsulated_data_t
|
||||
{
|
||||
|
@ -9,10 +9,10 @@ typedef struct __mavlink_encapsulated_data_t
|
|||
} mavlink_encapsulated_data_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255
|
||||
#define MAVLINK_MSG_ID_194_LEN 255
|
||||
#define MAVLINK_MSG_ID_131_LEN 255
|
||||
|
||||
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223
|
||||
#define MAVLINK_MSG_ID_194_CRC 223
|
||||
#define MAVLINK_MSG_ID_131_CRC 223
|
||||
|
||||
#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253
|
||||
|
|
@ -0,0 +1,419 @@
|
|||
// MESSAGE GPS2_RAW PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RAW 124
|
||||
|
||||
typedef struct __mavlink_gps2_raw_t
|
||||
{
|
||||
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
int32_t lat; ///< Latitude (WGS84), in degrees * 1E7
|
||||
int32_t lon; ///< Longitude (WGS84), in degrees * 1E7
|
||||
int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up)
|
||||
uint32_t dgps_age; ///< Age of DGPS info
|
||||
uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
|
||||
uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
|
||||
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
|
||||
uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255
|
||||
uint8_t dgps_numch; ///< Number of DGPS satellites
|
||||
} mavlink_gps2_raw_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
|
||||
#define MAVLINK_MSG_ID_124_LEN 35
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
|
||||
#define MAVLINK_MSG_ID_124_CRC 87
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
|
||||
"GPS2_RAW", \
|
||||
12, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
|
||||
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
|
||||
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
|
||||
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
|
||||
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
|
||||
{ "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
|
||||
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
|
||||
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
|
||||
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
|
||||
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
|
||||
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
|
||||
{ "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a gps2_raw message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
|
||||
* @param lat Latitude (WGS84), in degrees * 1E7
|
||||
* @param lon Longitude (WGS84), in degrees * 1E7
|
||||
* @param alt Altitude (WGS84), in meters * 1000 (positive for up)
|
||||
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
|
||||
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
|
||||
* @param satellites_visible Number of satellites visible. If unknown, set to 255
|
||||
* @param dgps_numch Number of DGPS satellites
|
||||
* @param dgps_age Age of DGPS info
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_int32_t(buf, 8, lat);
|
||||
_mav_put_int32_t(buf, 12, lon);
|
||||
_mav_put_int32_t(buf, 16, alt);
|
||||
_mav_put_uint32_t(buf, 20, dgps_age);
|
||||
_mav_put_uint16_t(buf, 24, eph);
|
||||
_mav_put_uint16_t(buf, 26, epv);
|
||||
_mav_put_uint16_t(buf, 28, vel);
|
||||
_mav_put_uint16_t(buf, 30, cog);
|
||||
_mav_put_uint8_t(buf, 32, fix_type);
|
||||
_mav_put_uint8_t(buf, 33, satellites_visible);
|
||||
_mav_put_uint8_t(buf, 34, dgps_numch);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#else
|
||||
mavlink_gps2_raw_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.lat = lat;
|
||||
packet.lon = lon;
|
||||
packet.alt = alt;
|
||||
packet.dgps_age = dgps_age;
|
||||
packet.eph = eph;
|
||||
packet.epv = epv;
|
||||
packet.vel = vel;
|
||||
packet.cog = cog;
|
||||
packet.fix_type = fix_type;
|
||||
packet.satellites_visible = satellites_visible;
|
||||
packet.dgps_numch = dgps_numch;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a gps2_raw message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
|
||||
* @param lat Latitude (WGS84), in degrees * 1E7
|
||||
* @param lon Longitude (WGS84), in degrees * 1E7
|
||||
* @param alt Altitude (WGS84), in meters * 1000 (positive for up)
|
||||
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
|
||||
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
|
||||
* @param satellites_visible Number of satellites visible. If unknown, set to 255
|
||||
* @param dgps_numch Number of DGPS satellites
|
||||
* @param dgps_age Age of DGPS info
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,uint8_t dgps_numch,uint32_t dgps_age)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_int32_t(buf, 8, lat);
|
||||
_mav_put_int32_t(buf, 12, lon);
|
||||
_mav_put_int32_t(buf, 16, alt);
|
||||
_mav_put_uint32_t(buf, 20, dgps_age);
|
||||
_mav_put_uint16_t(buf, 24, eph);
|
||||
_mav_put_uint16_t(buf, 26, epv);
|
||||
_mav_put_uint16_t(buf, 28, vel);
|
||||
_mav_put_uint16_t(buf, 30, cog);
|
||||
_mav_put_uint8_t(buf, 32, fix_type);
|
||||
_mav_put_uint8_t(buf, 33, satellites_visible);
|
||||
_mav_put_uint8_t(buf, 34, dgps_numch);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#else
|
||||
mavlink_gps2_raw_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.lat = lat;
|
||||
packet.lon = lon;
|
||||
packet.alt = alt;
|
||||
packet.dgps_age = dgps_age;
|
||||
packet.eph = eph;
|
||||
packet.epv = epv;
|
||||
packet.vel = vel;
|
||||
packet.cog = cog;
|
||||
packet.fix_type = fix_type;
|
||||
packet.satellites_visible = satellites_visible;
|
||||
packet.dgps_numch = dgps_numch;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a gps2_raw struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param gps2_raw C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
|
||||
{
|
||||
return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a gps2_raw struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param gps2_raw C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
|
||||
{
|
||||
return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a gps2_raw message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
|
||||
* @param lat Latitude (WGS84), in degrees * 1E7
|
||||
* @param lon Longitude (WGS84), in degrees * 1E7
|
||||
* @param alt Altitude (WGS84), in meters * 1000 (positive for up)
|
||||
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
|
||||
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
|
||||
* @param satellites_visible Number of satellites visible. If unknown, set to 255
|
||||
* @param dgps_numch Number of DGPS satellites
|
||||
* @param dgps_age Age of DGPS info
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_int32_t(buf, 8, lat);
|
||||
_mav_put_int32_t(buf, 12, lon);
|
||||
_mav_put_int32_t(buf, 16, alt);
|
||||
_mav_put_uint32_t(buf, 20, dgps_age);
|
||||
_mav_put_uint16_t(buf, 24, eph);
|
||||
_mav_put_uint16_t(buf, 26, epv);
|
||||
_mav_put_uint16_t(buf, 28, vel);
|
||||
_mav_put_uint16_t(buf, 30, cog);
|
||||
_mav_put_uint8_t(buf, 32, fix_type);
|
||||
_mav_put_uint8_t(buf, 33, satellites_visible);
|
||||
_mav_put_uint8_t(buf, 34, dgps_numch);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps2_raw_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.lat = lat;
|
||||
packet.lon = lon;
|
||||
packet.alt = alt;
|
||||
packet.dgps_age = dgps_age;
|
||||
packet.eph = eph;
|
||||
packet.epv = epv;
|
||||
packet.vel = vel;
|
||||
packet.cog = cog;
|
||||
packet.fix_type = fix_type;
|
||||
packet.satellites_visible = satellites_visible;
|
||||
packet.dgps_numch = dgps_numch;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE GPS2_RAW UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field time_usec from gps2_raw message
|
||||
*
|
||||
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint64_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field fix_type from gps2_raw message
|
||||
*
|
||||
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field lat from gps2_raw message
|
||||
*
|
||||
* @return Latitude (WGS84), in degrees * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field lon from gps2_raw message
|
||||
*
|
||||
* @return Longitude (WGS84), in degrees * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field alt from gps2_raw message
|
||||
*
|
||||
* @return Altitude (WGS84), in meters * 1000 (positive for up)
|
||||
*/
|
||||
static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field eph from gps2_raw message
|
||||
*
|
||||
* @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint16_t(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field epv from gps2_raw message
|
||||
*
|
||||
* @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint16_t(msg, 26);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vel from gps2_raw message
|
||||
*
|
||||
* @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint16_t(msg, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field cog from gps2_raw message
|
||||
*
|
||||
* @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint16_t(msg, 30);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field satellites_visible from gps2_raw message
|
||||
*
|
||||
* @return Number of satellites visible. If unknown, set to 255
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 33);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field dgps_numch from gps2_raw message
|
||||
*
|
||||
* @return Number of DGPS satellites
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 34);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field dgps_age from gps2_raw message
|
||||
*
|
||||
* @return Age of DGPS info
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a gps2_raw message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param gps2_raw C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg);
|
||||
gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg);
|
||||
gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg);
|
||||
gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg);
|
||||
gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg);
|
||||
gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg);
|
||||
gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg);
|
||||
gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg);
|
||||
gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg);
|
||||
gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg);
|
||||
gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg);
|
||||
gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg);
|
||||
#else
|
||||
memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
}
|
|
@ -0,0 +1,237 @@
|
|||
// MESSAGE GPS_INJECT_DATA PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123
|
||||
|
||||
typedef struct __mavlink_gps_inject_data_t
|
||||
{
|
||||
uint8_t target_system; ///< System ID
|
||||
uint8_t target_component; ///< Component ID
|
||||
uint8_t len; ///< data length
|
||||
uint8_t data[110]; ///< raw data (110 is enough for 12 satellites of RTCMv2)
|
||||
} mavlink_gps_inject_data_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113
|
||||
#define MAVLINK_MSG_ID_123_LEN 113
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250
|
||||
#define MAVLINK_MSG_ID_123_CRC 250
|
||||
|
||||
#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \
|
||||
"GPS_INJECT_DATA", \
|
||||
4, \
|
||||
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \
|
||||
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \
|
||||
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a gps_inject_data message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param len data length
|
||||
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN];
|
||||
_mav_put_uint8_t(buf, 0, target_system);
|
||||
_mav_put_uint8_t(buf, 1, target_component);
|
||||
_mav_put_uint8_t(buf, 2, len);
|
||||
_mav_put_uint8_t_array(buf, 3, data, 110);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#else
|
||||
mavlink_gps_inject_data_t packet;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
packet.len = len;
|
||||
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a gps_inject_data message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param len data length
|
||||
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN];
|
||||
_mav_put_uint8_t(buf, 0, target_system);
|
||||
_mav_put_uint8_t(buf, 1, target_component);
|
||||
_mav_put_uint8_t(buf, 2, len);
|
||||
_mav_put_uint8_t_array(buf, 3, data, 110);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#else
|
||||
mavlink_gps_inject_data_t packet;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
packet.len = len;
|
||||
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a gps_inject_data struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param gps_inject_data C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data)
|
||||
{
|
||||
return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a gps_inject_data struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param gps_inject_data C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data)
|
||||
{
|
||||
return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a gps_inject_data message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param len data length
|
||||
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN];
|
||||
_mav_put_uint8_t(buf, 0, target_system);
|
||||
_mav_put_uint8_t(buf, 1, target_component);
|
||||
_mav_put_uint8_t(buf, 2, len);
|
||||
_mav_put_uint8_t_array(buf, 3, data, 110);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps_inject_data_t packet;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
packet.len = len;
|
||||
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE GPS_INJECT_DATA UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from gps_inject_data message
|
||||
*
|
||||
* @return System ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field target_component from gps_inject_data message
|
||||
*
|
||||
* @return Component ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field len from gps_inject_data message
|
||||
*
|
||||
* @return data length
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 2);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field data from gps_inject_data message
|
||||
*
|
||||
* @return raw data (110 is enough for 12 satellites of RTCMv2)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t_array(msg, data, 110, 3);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a gps_inject_data message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param gps_inject_data C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg);
|
||||
gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg);
|
||||
gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg);
|
||||
mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data);
|
||||
#else
|
||||
memcpy(gps_inject_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
}
|
|
@ -4839,6 +4839,220 @@ static void mavlink_test_log_request_end(uint8_t system_id, uint8_t component_id
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gps_inject_data(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gps_inject_data_t packet_in = {
|
||||
5,
|
||||
}72,
|
||||
}139,
|
||||
}{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59 },
|
||||
};
|
||||
mavlink_gps_inject_data_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
packet1.len = packet_in.len;
|
||||
|
||||
mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*110);
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps_inject_data_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gps_inject_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps_inject_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data );
|
||||
mavlink_msg_gps_inject_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data );
|
||||
mavlink_msg_gps_inject_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gps_inject_data_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps_inject_data_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.len , packet1.data );
|
||||
mavlink_msg_gps_inject_data_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gps2_raw(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gps2_raw_t packet_in = {
|
||||
93372036854775807ULL,
|
||||
}963497880,
|
||||
}963498088,
|
||||
}963498296,
|
||||
}963498504,
|
||||
}18483,
|
||||
}18587,
|
||||
}18691,
|
||||
}18795,
|
||||
}101,
|
||||
}168,
|
||||
}235,
|
||||
};
|
||||
mavlink_gps2_raw_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.time_usec = packet_in.time_usec;
|
||||
packet1.lat = packet_in.lat;
|
||||
packet1.lon = packet_in.lon;
|
||||
packet1.alt = packet_in.alt;
|
||||
packet1.dgps_age = packet_in.dgps_age;
|
||||
packet1.eph = packet_in.eph;
|
||||
packet1.epv = packet_in.epv;
|
||||
packet1.vel = packet_in.vel;
|
||||
packet1.cog = packet_in.cog;
|
||||
packet1.fix_type = packet_in.fix_type;
|
||||
packet1.satellites_visible = packet_in.satellites_visible;
|
||||
packet1.dgps_numch = packet_in.dgps_numch;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps2_raw_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gps2_raw_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps2_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age );
|
||||
mavlink_msg_gps2_raw_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps2_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age );
|
||||
mavlink_msg_gps2_raw_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gps2_raw_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gps2_raw_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age );
|
||||
mavlink_msg_gps2_raw_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_data_transmission_handshake(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_data_transmission_handshake_t packet_in = {
|
||||
963497464,
|
||||
}17443,
|
||||
}17547,
|
||||
}17651,
|
||||
}163,
|
||||
}230,
|
||||
}41,
|
||||
};
|
||||
mavlink_data_transmission_handshake_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.size = packet_in.size;
|
||||
packet1.width = packet_in.width;
|
||||
packet1.height = packet_in.height;
|
||||
packet1.packets = packet_in.packets;
|
||||
packet1.type = packet_in.type;
|
||||
packet1.payload = packet_in.payload;
|
||||
packet1.jpg_quality = packet_in.jpg_quality;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_pack(system_id, component_id, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality );
|
||||
mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality );
|
||||
mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_data_transmission_handshake_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_send(MAVLINK_COMM_1 , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality );
|
||||
mavlink_msg_data_transmission_handshake_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_encapsulated_data(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_encapsulated_data_t packet_in = {
|
||||
17235,
|
||||
}{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135 },
|
||||
};
|
||||
mavlink_encapsulated_data_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.seqnr = packet_in.seqnr;
|
||||
|
||||
mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*253);
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_encapsulated_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_pack(system_id, component_id, &msg , packet1.seqnr , packet1.data );
|
||||
mavlink_msg_encapsulated_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seqnr , packet1.data );
|
||||
mavlink_msg_encapsulated_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_encapsulated_data_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_send(MAVLINK_COMM_1 , packet1.seqnr , packet1.data );
|
||||
mavlink_msg_encapsulated_data_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
|
@ -5393,6 +5607,10 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
|
|||
mavlink_test_log_data(system_id, component_id, last_msg);
|
||||
mavlink_test_log_erase(system_id, component_id, last_msg);
|
||||
mavlink_test_log_request_end(system_id, component_id, last_msg);
|
||||
mavlink_test_gps_inject_data(system_id, component_id, last_msg);
|
||||
mavlink_test_gps2_raw(system_id, component_id, last_msg);
|
||||
mavlink_test_data_transmission_handshake(system_id, component_id, last_msg);
|
||||
mavlink_test_encapsulated_data(system_id, component_id, last_msg);
|
||||
mavlink_test_battery_status(system_id, component_id, last_msg);
|
||||
mavlink_test_setpoint_8dof(system_id, component_id, last_msg);
|
||||
mavlink_test_setpoint_6dof(system_id, component_id, last_msg);
|
||||
|
|
|
@ -5,8 +5,8 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Mon Dec 16 08:59:18 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Feb 4 15:28:29 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
#endif // MAVLINK_VERSION_H
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -5,8 +5,8 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Mon Dec 16 08:57:49 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Feb 4 15:28:04 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
#endif // MAVLINK_VERSION_H
|
||||
|
|
|
@ -48,7 +48,7 @@ typedef struct __mavlink_system {
|
|||
uint8_t type; ///< Unused, can be used by user to store the system's type
|
||||
uint8_t state; ///< Unused, can be used by user to store the system's state
|
||||
uint8_t mode; ///< Unused, can be used by user to store the system's mode
|
||||
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
||||
uint32_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
||||
} mavlink_system_t;
|
||||
|
||||
typedef struct __mavlink_message {
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -853,106 +853,6 @@ static void mavlink_test_point_of_interest_connection(uint8_t system_id, uint8_t
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_data_transmission_handshake(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_data_transmission_handshake_t packet_in = {
|
||||
963497464,
|
||||
}17443,
|
||||
}17547,
|
||||
}29,
|
||||
}96,
|
||||
}163,
|
||||
}230,
|
||||
};
|
||||
mavlink_data_transmission_handshake_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.size = packet_in.size;
|
||||
packet1.width = packet_in.width;
|
||||
packet1.height = packet_in.height;
|
||||
packet1.type = packet_in.type;
|
||||
packet1.packets = packet_in.packets;
|
||||
packet1.payload = packet_in.payload;
|
||||
packet1.jpg_quality = packet_in.jpg_quality;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_pack(system_id, component_id, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality );
|
||||
mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality );
|
||||
mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_data_transmission_handshake_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_data_transmission_handshake_send(MAVLINK_COMM_1 , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality );
|
||||
mavlink_msg_data_transmission_handshake_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_encapsulated_data(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_encapsulated_data_t packet_in = {
|
||||
17235,
|
||||
}{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135 },
|
||||
};
|
||||
mavlink_encapsulated_data_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.seqnr = packet_in.seqnr;
|
||||
|
||||
mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*253);
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_encapsulated_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_pack(system_id, component_id, &msg , packet1.seqnr , packet1.data );
|
||||
mavlink_msg_encapsulated_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seqnr , packet1.data );
|
||||
mavlink_msg_encapsulated_data_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_encapsulated_data_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_encapsulated_data_send(MAVLINK_COMM_1 , packet1.seqnr , packet1.data );
|
||||
mavlink_msg_encapsulated_data_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_brief_feature(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
|
@ -1086,8 +986,6 @@ static void mavlink_test_pixhawk(uint8_t system_id, uint8_t component_id, mavlin
|
|||
mavlink_test_pattern_detected(system_id, component_id, last_msg);
|
||||
mavlink_test_point_of_interest(system_id, component_id, last_msg);
|
||||
mavlink_test_point_of_interest_connection(system_id, component_id, last_msg);
|
||||
mavlink_test_data_transmission_handshake(system_id, component_id, last_msg);
|
||||
mavlink_test_encapsulated_data(system_id, component_id, last_msg);
|
||||
mavlink_test_brief_feature(system_id, component_id, last_msg);
|
||||
mavlink_test_attitude_control(system_id, component_id, last_msg);
|
||||
}
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Mon Dec 16 08:58:02 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Feb 4 15:28:16 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -31,8 +31,8 @@ static void mavlink_test_obs_position(uint8_t system_id, uint8_t component_id, m
|
|||
uint16_t i;
|
||||
mavlink_obs_position_t packet_in = {
|
||||
963497464,
|
||||
963497672,
|
||||
963497880,
|
||||
}963497672,
|
||||
}963497880,
|
||||
};
|
||||
mavlink_obs_position_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
@ -207,8 +207,8 @@ static void mavlink_test_obs_air_velocity(uint8_t system_id, uint8_t component_i
|
|||
uint16_t i;
|
||||
mavlink_obs_air_velocity_t packet_in = {
|
||||
17.0,
|
||||
45.0,
|
||||
73.0,
|
||||
}45.0,
|
||||
}73.0,
|
||||
};
|
||||
mavlink_obs_air_velocity_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
@ -254,7 +254,7 @@ static void mavlink_test_obs_bias(uint8_t system_id, uint8_t component_id, mavli
|
|||
uint16_t i;
|
||||
mavlink_obs_bias_t packet_in = {
|
||||
{ 17.0, 18.0, 19.0 },
|
||||
{ 101.0, 102.0, 103.0 },
|
||||
}{ 101.0, 102.0, 103.0 },
|
||||
};
|
||||
mavlink_obs_bias_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
@ -428,7 +428,7 @@ static void mavlink_test_llc_out(uint8_t system_id, uint8_t component_id, mavlin
|
|||
uint16_t i;
|
||||
mavlink_llc_out_t packet_in = {
|
||||
{ 17235, 17236, 17237, 17238 },
|
||||
{ 17651, 17652 },
|
||||
}{ 17651, 17652 },
|
||||
};
|
||||
mavlink_llc_out_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
@ -473,8 +473,8 @@ static void mavlink_test_pm_elec(uint8_t system_id, uint8_t component_id, mavlin
|
|||
uint16_t i;
|
||||
mavlink_pm_elec_t packet_in = {
|
||||
17.0,
|
||||
45.0,
|
||||
{ 73.0, 74.0, 75.0 },
|
||||
}45.0,
|
||||
}{ 73.0, 74.0, 75.0 },
|
||||
};
|
||||
mavlink_pm_elec_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
@ -520,9 +520,9 @@ static void mavlink_test_sys_stat(uint8_t system_id, uint8_t component_id, mavli
|
|||
uint16_t i;
|
||||
mavlink_sys_stat_t packet_in = {
|
||||
5,
|
||||
72,
|
||||
139,
|
||||
206,
|
||||
}72,
|
||||
}139,
|
||||
}206,
|
||||
};
|
||||
mavlink_sys_stat_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
@ -569,7 +569,7 @@ static void mavlink_test_cmd_airspeed_chng(uint8_t system_id, uint8_t component_
|
|||
uint16_t i;
|
||||
mavlink_cmd_airspeed_chng_t packet_in = {
|
||||
17.0,
|
||||
17,
|
||||
}17,
|
||||
};
|
||||
mavlink_cmd_airspeed_chng_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
@ -614,7 +614,7 @@ static void mavlink_test_cmd_airspeed_ack(uint8_t system_id, uint8_t component_i
|
|||
uint16_t i;
|
||||
mavlink_cmd_airspeed_ack_t packet_in = {
|
||||
17.0,
|
||||
17,
|
||||
}17,
|
||||
};
|
||||
mavlink_cmd_airspeed_ack_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
|
|
|
@ -5,8 +5,8 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Tue Sep 10 23:50:02 2013"
|
||||
#define MAVLINK_BUILD_DATE "Tue Feb 4 15:28:27 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
#endif // MAVLINK_VERSION_H
|
||||
|
|
|
@ -246,14 +246,14 @@
|
|||
*
|
||||
* There are sensors on SPI1, and SPI3 is connected to the microSD slot.
|
||||
*/
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
|
||||
#define GPIO_SPI1_MISO (GPIO_SPI1_MISO_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
|
||||
|
||||
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
|
||||
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
|
||||
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
|
||||
#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2
|
||||
#define GPIO_SPI3_MISO (GPIO_SPI3_MISO_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI3_MOSI (GPIO_SPI3_MOSI_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI3_SCK (GPIO_SPI3_SCK_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI3_NSS (GPIO_SPI3_NSS_2|GPIO_SPEED_50MHz)
|
||||
|
||||
/* SPI DMA configuration for SPI3 (microSD) */
|
||||
#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1
|
||||
|
|
|
@ -260,13 +260,13 @@
|
|||
*
|
||||
* There are sensors on SPI1, and SPI2 is connected to the FRAM.
|
||||
*/
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
|
||||
#define GPIO_SPI1_MISO (GPIO_SPI1_MISO_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
|
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
|
||||
#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
|
|
|
@ -92,7 +92,7 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) :
|
|||
_comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors"))
|
||||
{
|
||||
// enable debug() calls
|
||||
_debug_enabled = true;
|
||||
_debug_enabled = false;
|
||||
|
||||
// work_cancel in the dtor will explode if we don't do this...
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
|
|
|
@ -75,7 +75,7 @@ __BEGIN_DECLS
|
|||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
|
||||
|
||||
/* External interrupts */
|
||||
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN0)
|
||||
|
@ -87,7 +87,7 @@ __BEGIN_DECLS
|
|||
#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_MAG_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN4)
|
||||
#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
|
||||
|
||||
/* SPI1 off */
|
||||
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5)
|
||||
|
@ -98,7 +98,7 @@ __BEGIN_DECLS
|
|||
#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN13)
|
||||
#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTD|GPIO_PIN7)
|
||||
#define GPIO_SPI_CS_MPU (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2)
|
||||
|
||||
/* SPI chip selects */
|
||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
|
||||
|
|
|
@ -58,11 +58,11 @@
|
|||
/* PX4IO GPIOs **********************************************************************/
|
||||
/* LEDs */
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|\
|
||||
GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
|
||||
/* Safety switch button *************************************************************/
|
||||
|
|
|
@ -74,9 +74,9 @@
|
|||
|
||||
/* LEDS **********************************************************************/
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
|
||||
|
||||
/* Safety switch button *******************************************************/
|
||||
|
||||
|
@ -114,7 +114,7 @@
|
|||
/* XXX these should be UART pins */
|
||||
#define GPIO_SBUS_INPUT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_SBUS_OUTPUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4)
|
||||
#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
|
||||
|
||||
/*
|
||||
* High-resolution timer
|
||||
|
|
|
@ -124,8 +124,6 @@ __EXPORT void stm32_boardinitialize(void)
|
|||
stm32_configgpio(GPIO_ADC_VSERVO);
|
||||
|
||||
stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
|
||||
|
||||
stm32_gpiowrite(GPIO_SBUS_OUTPUT, false);
|
||||
stm32_configgpio(GPIO_SBUS_OUTPUT);
|
||||
|
||||
/* sbus output enable is active low - disable it by default */
|
||||
|
|
|
@ -189,6 +189,24 @@ ORB_DECLARE(output_pwm);
|
|||
/** get the maximum PWM value the output will send */
|
||||
#define PWM_SERVO_GET_MAX_PWM _IOC(_PWM_SERVO_BASE, 19)
|
||||
|
||||
/** set the number of servos in (unsigned)arg - allows change of
|
||||
* split between servos and GPIO */
|
||||
#define PWM_SERVO_SET_COUNT _IOC(_PWM_SERVO_BASE, 20)
|
||||
|
||||
/** set the lockdown override flag to enable outputs in HIL */
|
||||
#define PWM_SERVO_SET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 21)
|
||||
|
||||
/** get the lockdown override flag to enable outputs in HIL */
|
||||
#define PWM_SERVO_GET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 22)
|
||||
|
||||
/*
|
||||
*
|
||||
*
|
||||
* WARNING WARNING WARNING! DO NOT EXCEED 31 IN IOC INDICES HERE!
|
||||
*
|
||||
*
|
||||
*/
|
||||
|
||||
/** set a single servo to a specific value */
|
||||
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
|
@ -62,6 +62,11 @@
|
|||
*/
|
||||
#define RC_INPUT_MAX_CHANNELS 18
|
||||
|
||||
/**
|
||||
* Maximum RSSI value
|
||||
*/
|
||||
#define RC_INPUT_RSSI_MAX 255
|
||||
|
||||
/**
|
||||
* Input signal type, value is a control position from zero to 100
|
||||
* percent.
|
||||
|
@ -83,8 +88,11 @@ enum RC_INPUT_SOURCE {
|
|||
* on the board involved.
|
||||
*/
|
||||
struct rc_input_values {
|
||||
/** decoding time */
|
||||
uint64_t timestamp;
|
||||
/** publication time */
|
||||
uint64_t timestamp_publication;
|
||||
|
||||
/** last valid reception time */
|
||||
uint64_t timestamp_last_signal;
|
||||
|
||||
/** number of channels actually being seen */
|
||||
uint32_t channel_count;
|
||||
|
@ -92,6 +100,40 @@ struct rc_input_values {
|
|||
/** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 255: full reception */
|
||||
int32_t rssi;
|
||||
|
||||
/**
|
||||
* explicit failsafe flag: true on TX failure or TX out of range , false otherwise.
|
||||
* Only the true state is reliable, as there are some (PPM) receivers on the market going
|
||||
* into failsafe without telling us explicitly.
|
||||
* */
|
||||
bool rc_failsafe;
|
||||
|
||||
/**
|
||||
* RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise.
|
||||
* True usally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems.
|
||||
* Will remain false, if a RX with failsafe option continues to transmit frames after a link loss.
|
||||
* */
|
||||
bool rc_lost;
|
||||
|
||||
/**
|
||||
* Number of lost RC frames.
|
||||
* Note: intended purpose: observe the radio link quality if RSSI is not available
|
||||
* This value must not be used to trigger any failsafe-alike funtionality.
|
||||
* */
|
||||
uint16_t rc_lost_frame_count;
|
||||
|
||||
/**
|
||||
* Number of total RC frames.
|
||||
* Note: intended purpose: observe the radio link quality if RSSI is not available
|
||||
* This value must not be used to trigger any failsafe-alike funtionality.
|
||||
* */
|
||||
uint16_t rc_total_frame_count;
|
||||
|
||||
/**
|
||||
* Length of a single PPM frame.
|
||||
* Zero for non-PPM systems
|
||||
*/
|
||||
uint16_t rc_ppm_frame_length;
|
||||
|
||||
/** Input source */
|
||||
enum RC_INPUT_SOURCE input_source;
|
||||
|
||||
|
@ -107,8 +149,12 @@ ORB_DECLARE(input_rc);
|
|||
#define _RC_INPUT_BASE 0x2b00
|
||||
|
||||
/** Fetch R/C input values into (rc_input_values *)arg */
|
||||
|
||||
#define RC_INPUT_GET _IOC(_RC_INPUT_BASE, 0)
|
||||
|
||||
/** Enable RSSI input via ADC */
|
||||
#define RC_INPUT_ENABLE_RSSI_ANALOG _IOC(_RC_INPUT_BASE, 1)
|
||||
|
||||
/** Enable RSSI input via PWM signal */
|
||||
#define RC_INPUT_ENABLE_RSSI_PWM _IOC(_RC_INPUT_BASE, 2)
|
||||
|
||||
#endif /* _DRV_RC_INPUT_H */
|
||||
|
|
|
@ -0,0 +1,58 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
* 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 drv_sbus.h
|
||||
*
|
||||
* Futaba S.BUS / S.BUS 2 compatible interface.
|
||||
*/
|
||||
|
||||
#ifndef _DRV_SBUS_H
|
||||
#define _DRV_SBUS_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
#include "drv_orb_dev.h"
|
||||
|
||||
/**
|
||||
* Path for the default S.BUS device
|
||||
*/
|
||||
#define SBUS_DEVICE_PATH "/dev/sbus"
|
||||
|
||||
#define _SBUS_BASE 0x2c00
|
||||
|
||||
/** Enable S.BUS version 1 / 2 output (0 to disable) */
|
||||
#define SBUS_SET_PROTO_VERSION _IOC(_SBUS_BASE, 0)
|
||||
|
||||
#endif /* _DRV_SBUS_H */
|
|
@ -839,42 +839,24 @@ HMC5883::collect()
|
|||
|
||||
/* scale values for output */
|
||||
|
||||
/*
|
||||
* 1) Scale raw value to SI units using scaling from datasheet.
|
||||
* 2) Subtract static offset (in SI units)
|
||||
* 3) Scale the statically calibrated values with a linear
|
||||
* dynamically obtained factor
|
||||
*
|
||||
* Note: the static sensor offset is the number the sensor outputs
|
||||
* at a nominally 'zero' input. Therefore the offset has to
|
||||
* be subtracted.
|
||||
*
|
||||
* Example: A gyro outputs a value of 74 at zero angular rate
|
||||
* the offset is 74 from the origin and subtracting
|
||||
* 74 from all measurements centers them around zero.
|
||||
*/
|
||||
|
||||
#ifdef PX4_I2C_BUS_ONBOARD
|
||||
if (_bus == PX4_I2C_BUS_ONBOARD) {
|
||||
/* to align the sensor axes with the board, x and y need to be flipped */
|
||||
new_report.x = ((report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
|
||||
/* flip axes and negate value for y */
|
||||
new_report.y = ((-report.x * _range_scale) - _scale.y_offset) * _scale.y_scale;
|
||||
/* z remains z */
|
||||
new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
|
||||
} else {
|
||||
#endif
|
||||
/* the standard external mag by 3DR has x pointing to the right, y pointing backwards, and z down,
|
||||
* therefore switch x and y and invert y */
|
||||
new_report.x = ((-report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
|
||||
/* flip axes and negate value for y */
|
||||
new_report.y = ((report.x * _range_scale) - _scale.y_offset) * _scale.y_scale;
|
||||
/* z remains z */
|
||||
new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
|
||||
#ifdef PX4_I2C_BUS_ONBOARD
|
||||
}
|
||||
// convert onboard so it matches offboard for the
|
||||
// scaling below
|
||||
report.y = -report.y;
|
||||
report.x = -report.x;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* the standard external mag by 3DR has x pointing to the
|
||||
* right, y pointing backwards, and z down, therefore switch x
|
||||
* and y and invert y */
|
||||
new_report.x = ((-report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
|
||||
/* flip axes and negate value for y */
|
||||
new_report.y = ((report.x * _range_scale) - _scale.y_offset) * _scale.y_scale;
|
||||
/* z remains z */
|
||||
new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
|
||||
|
||||
if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) {
|
||||
|
||||
if (_mag_topic != -1) {
|
||||
|
@ -886,7 +868,6 @@ HMC5883::collect()
|
|||
if (_mag_topic < 0)
|
||||
debug("failed to create sensor_mag publication");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* post a report to the ring */
|
||||
|
@ -909,6 +890,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
|
|||
struct mag_report report;
|
||||
ssize_t sz;
|
||||
int ret = 1;
|
||||
uint8_t good_count = 0;
|
||||
|
||||
// XXX do something smarter here
|
||||
int fd = (int)enable;
|
||||
|
@ -931,32 +913,17 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
|
|||
1.0f,
|
||||
};
|
||||
|
||||
float avg_excited[3] = {0.0f, 0.0f, 0.0f};
|
||||
unsigned i;
|
||||
float sum_excited[3] = {0.0f, 0.0f, 0.0f};
|
||||
|
||||
/* expected axis scaling. The datasheet says that 766 will
|
||||
* be places in the X and Y axes and 713 in the Z
|
||||
* axis. Experiments show that in fact 766 is placed in X,
|
||||
* and 713 in Y and Z. This is relative to a base of 660
|
||||
* LSM/Ga, giving 1.16 and 1.08 */
|
||||
float expected_cal[3] = { 1.16f, 1.08f, 1.08f };
|
||||
|
||||
warnx("starting mag scale calibration");
|
||||
|
||||
/* do a simple demand read */
|
||||
sz = read(filp, (char *)&report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report)) {
|
||||
warn("immediate read failed");
|
||||
ret = 1;
|
||||
goto out;
|
||||
}
|
||||
|
||||
warnx("current measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
warnx("sampling 500 samples for scaling offset");
|
||||
|
||||
/* set the queue depth to 10 */
|
||||
/* don't do this for now, it can lead to a crash in start() respectively work_queue() */
|
||||
// if (OK != ioctl(filp, SENSORIOCSQUEUEDEPTH, 10)) {
|
||||
// warn("failed to set queue depth");
|
||||
// ret = 1;
|
||||
// goto out;
|
||||
// }
|
||||
|
||||
/* start the sensor polling at 50 Hz */
|
||||
if (OK != ioctl(filp, SENSORIOCSPOLLRATE, 50)) {
|
||||
warn("failed to set 2Hz poll rate");
|
||||
|
@ -964,8 +931,9 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
|
|||
goto out;
|
||||
}
|
||||
|
||||
/* Set to 2.5 Gauss */
|
||||
if (OK != ioctl(filp, MAGIOCSRANGE, 2)) {
|
||||
/* Set to 2.5 Gauss. We ask for 3 to get the right part of
|
||||
* the chained if statement above. */
|
||||
if (OK != ioctl(filp, MAGIOCSRANGE, 3)) {
|
||||
warnx("failed to set 2.5 Ga range");
|
||||
ret = 1;
|
||||
goto out;
|
||||
|
@ -989,8 +957,8 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
|
|||
goto out;
|
||||
}
|
||||
|
||||
/* read the sensor 10x and report each value */
|
||||
for (i = 0; i < 500; i++) {
|
||||
// discard 10 samples to let the sensor settle
|
||||
for (uint8_t i = 0; i < 10; i++) {
|
||||
struct pollfd fds;
|
||||
|
||||
/* wait for data to be ready */
|
||||
|
@ -1008,32 +976,69 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
|
|||
|
||||
if (sz != sizeof(report)) {
|
||||
warn("periodic read failed");
|
||||
ret = -EIO;
|
||||
goto out;
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
avg_excited[0] += report.x;
|
||||
avg_excited[1] += report.y;
|
||||
avg_excited[2] += report.z;
|
||||
/* read the sensor up to 50x, stopping when we have 10 good values */
|
||||
for (uint8_t i = 0; i < 50 && good_count < 10; i++) {
|
||||
struct pollfd fds;
|
||||
|
||||
/* wait for data to be ready */
|
||||
fds.fd = fd;
|
||||
fds.events = POLLIN;
|
||||
ret = ::poll(&fds, 1, 2000);
|
||||
|
||||
if (ret != 1) {
|
||||
warn("timed out waiting for sensor data");
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* now go get it */
|
||||
sz = ::read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report)) {
|
||||
warn("periodic read failed");
|
||||
ret = -EIO;
|
||||
goto out;
|
||||
}
|
||||
float cal[3] = {fabsf(expected_cal[0] / report.x),
|
||||
fabsf(expected_cal[1] / report.y),
|
||||
fabsf(expected_cal[2] / report.z)};
|
||||
|
||||
if (cal[0] > 0.7f && cal[0] < 1.35f &&
|
||||
cal[1] > 0.7f && cal[1] < 1.35f &&
|
||||
cal[2] > 0.7f && cal[2] < 1.35f) {
|
||||
good_count++;
|
||||
sum_excited[0] += cal[0];
|
||||
sum_excited[1] += cal[1];
|
||||
sum_excited[2] += cal[2];
|
||||
}
|
||||
|
||||
//warnx("periodic read %u", i);
|
||||
//warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
|
||||
//warnx("cal: %.6f %.6f %.6f", (double)cal[0], (double)cal[1], (double)cal[2]);
|
||||
}
|
||||
|
||||
avg_excited[0] /= i;
|
||||
avg_excited[1] /= i;
|
||||
avg_excited[2] /= i;
|
||||
if (good_count < 5) {
|
||||
warn("failed calibration");
|
||||
ret = -EIO;
|
||||
goto out;
|
||||
}
|
||||
|
||||
warnx("done. Performed %u reads", i);
|
||||
warnx("measurement avg: %.6f %.6f %.6f", (double)avg_excited[0], (double)avg_excited[1], (double)avg_excited[2]);
|
||||
#if 0
|
||||
warnx("measurement avg: %.6f %.6f %.6f",
|
||||
(double)sum_excited[0]/good_count,
|
||||
(double)sum_excited[1]/good_count,
|
||||
(double)sum_excited[2]/good_count);
|
||||
#endif
|
||||
|
||||
float scaling[3];
|
||||
|
||||
/* calculate axis scaling */
|
||||
scaling[0] = fabsf(1.16f / avg_excited[0]);
|
||||
/* second axis inverted */
|
||||
scaling[1] = fabsf(1.16f / -avg_excited[1]);
|
||||
scaling[2] = fabsf(1.08f / avg_excited[2]);
|
||||
scaling[0] = sum_excited[0] / good_count;
|
||||
scaling[1] = sum_excited[1] / good_count;
|
||||
scaling[2] = sum_excited[2] / good_count;
|
||||
|
||||
warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]);
|
||||
|
||||
|
@ -1166,6 +1171,8 @@ int HMC5883::set_excitement(unsigned enable)
|
|||
conf_reg &= ~0x03;
|
||||
}
|
||||
|
||||
// ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)conf_reg);
|
||||
|
||||
ret = write_reg(ADDR_CONF_A, conf_reg);
|
||||
|
||||
if (OK != ret)
|
||||
|
@ -1174,6 +1181,8 @@ int HMC5883::set_excitement(unsigned enable)
|
|||
uint8_t conf_reg_ret;
|
||||
read_reg(ADDR_CONF_A, conf_reg_ret);
|
||||
|
||||
//print_info();
|
||||
|
||||
return !(conf_reg == conf_reg_ret);
|
||||
}
|
||||
|
||||
|
@ -1212,6 +1221,10 @@ HMC5883::print_info()
|
|||
perf_print_counter(_comms_errors);
|
||||
perf_print_counter(_buffer_overflows);
|
||||
printf("poll interval: %u ticks\n", _measure_ticks);
|
||||
printf("offsets (%.2f %.2f %.2f)\n", (double)_scale.x_offset, (double)_scale.y_offset, (double)_scale.z_offset);
|
||||
printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
|
||||
(double)_scale.x_scale, (double)_scale.y_scale, (double)_scale.z_scale,
|
||||
(double)1.0/_range_scale, (double)_range_ga);
|
||||
_reports->print_info("report queue");
|
||||
}
|
||||
|
||||
|
|
|
@ -77,7 +77,6 @@
|
|||
#include <systemlib/err.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
|
||||
#include <drivers/drv_airspeed.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
@ -178,24 +177,17 @@ MEASAirspeed::collect()
|
|||
return ret;
|
||||
}
|
||||
|
||||
//uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8);
|
||||
uint16_t temp = (val[3] & 0xE0) << 8 | val[2];
|
||||
|
||||
// XXX leaving this in until new calculation method has been cross-checked
|
||||
//diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
|
||||
//diff_pres_pa -= _diff_pres_offset;
|
||||
int16_t dp_raw = 0, dT_raw = 0;
|
||||
dp_raw = (val[0] << 8) + val[1];
|
||||
dp_raw = 0x3FFF & dp_raw; //mask the used bits
|
||||
/* mask the used bits */
|
||||
dp_raw = 0x3FFF & dp_raw;
|
||||
dT_raw = (val[2] << 8) + val[3];
|
||||
dT_raw = (0xFFE0 & dT_raw) >> 5;
|
||||
float temperature = ((200 * dT_raw) / 2047) - 50;
|
||||
|
||||
// XXX we may want to smooth out the readings to remove noise.
|
||||
|
||||
// Calculate differential pressure. As its centered around 8000
|
||||
// and can go positive or negative, enforce absolute value
|
||||
// uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f));
|
||||
/* calculate differential pressure. As its centered around 8000
|
||||
* and can go positive or negative, enforce absolute value
|
||||
*/
|
||||
const float P_min = -1.0f;
|
||||
const float P_max = 1.0f;
|
||||
float diff_press_pa = fabsf( ( ((float)dp_raw - 0.1f*16383.0f) * (P_max-P_min)/(0.8f*16383.0f) + P_min) * 6894.8f) - _diff_pres_offset;
|
||||
|
@ -204,7 +196,7 @@ MEASAirspeed::collect()
|
|||
|
||||
struct differential_pressure_s report;
|
||||
|
||||
// Track maximum differential pressure measured (so we can work out top speed).
|
||||
/* track maximum differential pressure measured (so we can work out top speed). */
|
||||
if (diff_press_pa > _max_differential_pressure_pa) {
|
||||
_max_differential_pressure_pa = diff_press_pa;
|
||||
}
|
||||
|
@ -394,7 +386,7 @@ test()
|
|||
err(1, "immediate read failed");
|
||||
|
||||
warnx("single read");
|
||||
warnx("diff pressure: %d pa", report.differential_pressure_pa);
|
||||
warnx("diff pressure: %d pa", (double)report.differential_pressure_pa);
|
||||
|
||||
/* start the sensor polling at 2Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012,2013 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
* Author: Marco Bauer <marco@wtns.de>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -65,7 +65,6 @@
|
|||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_gpio.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
|
||||
|
@ -93,16 +92,12 @@
|
|||
#define MOTOR_SPINUP_COUNTER 30
|
||||
#define ESC_UORB_PUBLISH_DELAY 500000
|
||||
|
||||
|
||||
|
||||
|
||||
class MK : public device::I2C
|
||||
{
|
||||
public:
|
||||
enum Mode {
|
||||
MODE_NONE,
|
||||
MODE_2PWM,
|
||||
MODE_4PWM,
|
||||
MODE_6PWM,
|
||||
};
|
||||
|
||||
enum MappingMode {
|
||||
MAPPING_MK = 0,
|
||||
MAPPING_PX4,
|
||||
|
@ -120,8 +115,7 @@ public:
|
|||
virtual int init(unsigned motors);
|
||||
virtual ssize_t write(file *filp, const char *buffer, size_t len);
|
||||
|
||||
int set_mode(Mode mode);
|
||||
int set_pwm_rate(unsigned rate);
|
||||
int set_update_rate(unsigned rate);
|
||||
int set_motor_count(unsigned count);
|
||||
int set_motor_test(bool motortest);
|
||||
int set_overrideSecurityChecks(bool overrideSecurityChecks);
|
||||
|
@ -133,7 +127,6 @@ private:
|
|||
static const unsigned _max_actuators = MAX_MOTORS;
|
||||
static const bool showDebug = false;
|
||||
|
||||
Mode _mode;
|
||||
int _update_rate;
|
||||
int _current_update_rate;
|
||||
int _task;
|
||||
|
@ -180,33 +173,15 @@ private:
|
|||
static const GPIOConfig _gpio_tab[];
|
||||
static const unsigned _ngpio;
|
||||
|
||||
void gpio_reset(void);
|
||||
void gpio_set_function(uint32_t gpios, int function);
|
||||
void gpio_write(uint32_t gpios, int function);
|
||||
uint32_t gpio_read(void);
|
||||
int gpio_ioctl(file *filp, int cmd, unsigned long arg);
|
||||
int mk_servo_arm(bool status);
|
||||
|
||||
int mk_servo_set(unsigned int chan, short val);
|
||||
int mk_servo_set_value(unsigned int chan, short val);
|
||||
int mk_servo_test(unsigned int chan);
|
||||
short scaling(float val, float inMin, float inMax, float outMin, float outMax);
|
||||
|
||||
|
||||
};
|
||||
|
||||
const MK::GPIOConfig MK::_gpio_tab[] = {
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
|
||||
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
|
||||
{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1},
|
||||
{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1},
|
||||
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1},
|
||||
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
|
||||
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
|
||||
};
|
||||
|
||||
const unsigned MK::_ngpio = sizeof(MK::_gpio_tab) / sizeof(MK::_gpio_tab[0]);
|
||||
|
||||
|
||||
const int blctrlAddr_quad_plus[] = { 2, 2, -2, -2, 0, 0, 0, 0 }; // Addresstranslator for Quad + configuration
|
||||
const int blctrlAddr_hexa_plus[] = { 0, 2, 2, -2, 1, -3, 0, 0 }; // Addresstranslator for Hexa + configuration
|
||||
|
@ -247,8 +222,7 @@ MK *g_mk;
|
|||
|
||||
MK::MK(int bus, const char *_device_path) :
|
||||
I2C("mkblctrl", "/dev/mkblctrl", bus, 0, I2C_BUS_SPEED),
|
||||
_mode(MODE_NONE),
|
||||
_update_rate(50),
|
||||
_update_rate(400),
|
||||
_task(-1),
|
||||
_t_actuators(-1),
|
||||
_t_actuator_armed(-1),
|
||||
|
@ -317,26 +291,23 @@ MK::init(unsigned motors)
|
|||
|
||||
usleep(500000);
|
||||
|
||||
if (sizeof(_device) > 0) {
|
||||
ret = register_driver(_device, &fops, 0666, (void *)this);
|
||||
if (sizeof(_device) > 0) {
|
||||
ret = register_driver(_device, &fops, 0666, (void *)this);
|
||||
|
||||
if (ret == OK) {
|
||||
if (ret == OK) {
|
||||
log("creating alternate output device");
|
||||
_primary_pwm_device = true;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* reset GPIOs */
|
||||
gpio_reset();
|
||||
}
|
||||
|
||||
/* start the IO interface task */
|
||||
_task = task_spawn_cmd("mkblctrl",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
(main_t)&MK::task_main_trampoline,
|
||||
nullptr);
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
(main_t)&MK::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
|
||||
if (_task < 0) {
|
||||
|
@ -354,43 +325,7 @@ MK::task_main_trampoline(int argc, char *argv[])
|
|||
}
|
||||
|
||||
int
|
||||
MK::set_mode(Mode mode)
|
||||
{
|
||||
/*
|
||||
* Configure for PWM output.
|
||||
*
|
||||
* Note that regardless of the configured mode, the task is always
|
||||
* listening and mixing; the mode just selects which of the channels
|
||||
* are presented on the output pins.
|
||||
*/
|
||||
switch (mode) {
|
||||
case MODE_2PWM:
|
||||
up_pwm_servo_deinit();
|
||||
_update_rate = UPDATE_RATE; /* default output rate */
|
||||
break;
|
||||
|
||||
case MODE_4PWM:
|
||||
up_pwm_servo_deinit();
|
||||
_update_rate = UPDATE_RATE; /* default output rate */
|
||||
break;
|
||||
|
||||
case MODE_NONE:
|
||||
debug("MODE_NONE");
|
||||
/* disable servo outputs and set a very low update rate */
|
||||
up_pwm_servo_deinit();
|
||||
_update_rate = UPDATE_RATE;
|
||||
break;
|
||||
|
||||
default:
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
_mode = mode;
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
MK::set_pwm_rate(unsigned rate)
|
||||
MK::set_update_rate(unsigned rate)
|
||||
{
|
||||
if ((rate > 500) || (rate < 10))
|
||||
return -EINVAL;
|
||||
|
@ -621,11 +556,13 @@ MK::task_main()
|
|||
}
|
||||
}
|
||||
|
||||
if(!_overrideSecurityChecks) {
|
||||
if (!_overrideSecurityChecks) {
|
||||
/* don't go under BLCTRL_MIN_VALUE */
|
||||
|
||||
if (outputs.output[i] < BLCTRL_MIN_VALUE) {
|
||||
outputs.output[i] = BLCTRL_MIN_VALUE;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* output to BLCtrl's */
|
||||
|
@ -675,21 +612,24 @@ MK::task_main()
|
|||
esc.esc[i].esc_current = (uint16_t) Motor[i].Current;
|
||||
esc.esc[i].esc_rpm = (uint16_t) 0;
|
||||
esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4;
|
||||
|
||||
if (Motor[i].Version == 1) {
|
||||
// BLCtrl 2.0 (11Bit)
|
||||
esc.esc[i].esc_setpoint_raw = (uint16_t) (Motor[i].SetPoint<<3) | Motor[i].SetPointLowerBits;
|
||||
esc.esc[i].esc_setpoint_raw = (uint16_t)(Motor[i].SetPoint << 3) | Motor[i].SetPointLowerBits;
|
||||
|
||||
} else {
|
||||
// BLCtrl < 2.0 (8Bit)
|
||||
esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint;
|
||||
}
|
||||
|
||||
esc.esc[i].esc_temperature = (uint16_t) Motor[i].Temperature;
|
||||
esc.esc[i].esc_state = (uint16_t) Motor[i].State;
|
||||
esc.esc[i].esc_errorcount = (uint16_t) 0;
|
||||
|
||||
// if motortest is requested - do it...
|
||||
if (_motortest == true) {
|
||||
mk_servo_test(i);
|
||||
}
|
||||
// if motortest is requested - do it...
|
||||
if (_motortest == true) {
|
||||
mk_servo_test(i);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
@ -728,7 +668,7 @@ MK::mk_servo_arm(bool status)
|
|||
unsigned int
|
||||
MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C)
|
||||
{
|
||||
if(initI2C) {
|
||||
if (initI2C) {
|
||||
I2C::init();
|
||||
}
|
||||
|
||||
|
@ -781,8 +721,8 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C)
|
|||
fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i, Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature);
|
||||
}
|
||||
|
||||
|
||||
if(!_overrideSecurityChecks) {
|
||||
|
||||
if (!_overrideSecurityChecks) {
|
||||
if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) {
|
||||
_task_should_exit = true;
|
||||
}
|
||||
|
@ -811,8 +751,8 @@ MK::mk_servo_set(unsigned int chan, short val)
|
|||
tmpVal = 0;
|
||||
}
|
||||
|
||||
Motor[chan].SetPoint = (uint8_t)(tmpVal>>3)&0xff;
|
||||
Motor[chan].SetPointLowerBits = ((uint8_t)tmpVal%8)&0x07;
|
||||
Motor[chan].SetPoint = (uint8_t)(tmpVal >> 3) & 0xff;
|
||||
Motor[chan].SetPointLowerBits = ((uint8_t)tmpVal % 8) & 0x07;
|
||||
|
||||
if (_armed == false) {
|
||||
Motor[chan].SetPoint = 0;
|
||||
|
@ -1019,28 +959,6 @@ MK::ioctl(file *filp, int cmd, unsigned long arg)
|
|||
{
|
||||
int ret;
|
||||
|
||||
// XXX disabled, confusing users
|
||||
|
||||
/* try it as a GPIO ioctl first */
|
||||
ret = gpio_ioctl(filp, cmd, arg);
|
||||
|
||||
if (ret != -ENOTTY)
|
||||
return ret;
|
||||
|
||||
/* if we are in valid PWM mode, try it as a PWM ioctl as well */
|
||||
/*
|
||||
switch (_mode) {
|
||||
case MODE_2PWM:
|
||||
case MODE_4PWM:
|
||||
case MODE_6PWM:
|
||||
ret = pwm_ioctl(filp, cmd, arg);
|
||||
break;
|
||||
|
||||
default:
|
||||
debug("not in a PWM mode");
|
||||
break;
|
||||
}
|
||||
*/
|
||||
ret = pwm_ioctl(filp, cmd, arg);
|
||||
|
||||
/* if nobody wants it, let CDev have it */
|
||||
|
@ -1075,6 +993,10 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
ret = OK;
|
||||
break;
|
||||
|
||||
case PWM_SERVO_GET_UPDATE_RATE:
|
||||
*(uint32_t *)arg = _update_rate;
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET_SELECT_UPDATE_RATE:
|
||||
ret = OK;
|
||||
break;
|
||||
|
@ -1084,6 +1006,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
if (arg < 2150) {
|
||||
Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue = (unsigned short)arg;
|
||||
mk_servo_set(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 2047));
|
||||
|
||||
} else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
|
@ -1198,139 +1121,10 @@ MK::write(file *filp, const char *buffer, size_t len)
|
|||
return count * 2;
|
||||
}
|
||||
|
||||
void
|
||||
MK::gpio_reset(void)
|
||||
{
|
||||
/*
|
||||
* Setup default GPIO config - all pins as GPIOs, GPIO driver chip
|
||||
* to input mode.
|
||||
*/
|
||||
for (unsigned i = 0; i < _ngpio; i++)
|
||||
stm32_configgpio(_gpio_tab[i].input);
|
||||
|
||||
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
|
||||
stm32_configgpio(GPIO_GPIO_DIR);
|
||||
}
|
||||
|
||||
void
|
||||
MK::gpio_set_function(uint32_t gpios, int function)
|
||||
{
|
||||
/*
|
||||
* GPIOs 0 and 1 must have the same direction as they are buffered
|
||||
* by a shared 2-port driver. Any attempt to set either sets both.
|
||||
*/
|
||||
if (gpios & 3) {
|
||||
gpios |= 3;
|
||||
|
||||
/* flip the buffer to output mode if required */
|
||||
if (GPIO_SET_OUTPUT == function)
|
||||
stm32_gpiowrite(GPIO_GPIO_DIR, 1);
|
||||
}
|
||||
|
||||
/* configure selected GPIOs as required */
|
||||
for (unsigned i = 0; i < _ngpio; i++) {
|
||||
if (gpios & (1 << i)) {
|
||||
switch (function) {
|
||||
case GPIO_SET_INPUT:
|
||||
stm32_configgpio(_gpio_tab[i].input);
|
||||
break;
|
||||
|
||||
case GPIO_SET_OUTPUT:
|
||||
stm32_configgpio(_gpio_tab[i].output);
|
||||
break;
|
||||
|
||||
case GPIO_SET_ALT_1:
|
||||
if (_gpio_tab[i].alt != 0)
|
||||
stm32_configgpio(_gpio_tab[i].alt);
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* flip buffer to input mode if required */
|
||||
if ((GPIO_SET_INPUT == function) && (gpios & 3))
|
||||
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
|
||||
}
|
||||
|
||||
void
|
||||
MK::gpio_write(uint32_t gpios, int function)
|
||||
{
|
||||
int value = (function == GPIO_SET) ? 1 : 0;
|
||||
|
||||
for (unsigned i = 0; i < _ngpio; i++)
|
||||
if (gpios & (1 << i))
|
||||
stm32_gpiowrite(_gpio_tab[i].output, value);
|
||||
}
|
||||
|
||||
uint32_t
|
||||
MK::gpio_read(void)
|
||||
{
|
||||
uint32_t bits = 0;
|
||||
|
||||
for (unsigned i = 0; i < _ngpio; i++)
|
||||
if (stm32_gpioread(_gpio_tab[i].input))
|
||||
bits |= (1 << i);
|
||||
|
||||
return bits;
|
||||
}
|
||||
|
||||
int
|
||||
MK::gpio_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
lock();
|
||||
|
||||
switch (cmd) {
|
||||
|
||||
case GPIO_RESET:
|
||||
gpio_reset();
|
||||
break;
|
||||
|
||||
case GPIO_SET_OUTPUT:
|
||||
case GPIO_SET_INPUT:
|
||||
case GPIO_SET_ALT_1:
|
||||
gpio_set_function(arg, cmd);
|
||||
break;
|
||||
|
||||
case GPIO_SET_ALT_2:
|
||||
case GPIO_SET_ALT_3:
|
||||
case GPIO_SET_ALT_4:
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
|
||||
case GPIO_SET:
|
||||
case GPIO_CLEAR:
|
||||
gpio_write(arg, cmd);
|
||||
break;
|
||||
|
||||
case GPIO_GET:
|
||||
*(uint32_t *)arg = gpio_read();
|
||||
break;
|
||||
|
||||
default:
|
||||
ret = -ENOTTY;
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
enum PortMode {
|
||||
PORT_MODE_UNSET = 0,
|
||||
PORT_FULL_GPIO,
|
||||
PORT_FULL_SERIAL,
|
||||
PORT_FULL_PWM,
|
||||
PORT_GPIO_AND_SERIAL,
|
||||
PORT_PWM_AND_SERIAL,
|
||||
PORT_PWM_AND_GPIO,
|
||||
};
|
||||
|
||||
enum MappingMode {
|
||||
MAPPING_MK = 0,
|
||||
MAPPING_PX4,
|
||||
|
@ -1341,20 +1135,11 @@ enum FrameType {
|
|||
FRAME_X,
|
||||
};
|
||||
|
||||
PortMode g_port_mode;
|
||||
|
||||
int
|
||||
mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype, bool overrideSecurityChecks)
|
||||
mk_new_mode(int update_rate, int motorcount, bool motortest, int px4mode, int frametype, bool overrideSecurityChecks)
|
||||
{
|
||||
uint32_t gpio_bits;
|
||||
int shouldStop = 0;
|
||||
MK::Mode servo_mode;
|
||||
|
||||
/* reset to all-inputs */
|
||||
g_mk->ioctl(0, GPIO_RESET, 0);
|
||||
|
||||
gpio_bits = 0;
|
||||
servo_mode = MK::MODE_NONE;
|
||||
|
||||
/* native PX4 addressing) */
|
||||
g_mk->set_px4mode(px4mode);
|
||||
|
@ -1368,7 +1153,6 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest,
|
|||
/* ovveride security checks if enabled */
|
||||
g_mk->set_overrideSecurityChecks(overrideSecurityChecks);
|
||||
|
||||
|
||||
/* count used motors */
|
||||
do {
|
||||
if (g_mk->mk_check_for_blctrl(8, false, false) != 0) {
|
||||
|
@ -1383,86 +1167,54 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest,
|
|||
|
||||
g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, true, false));
|
||||
|
||||
/* (re)set the PWM output mode */
|
||||
g_mk->set_mode(servo_mode);
|
||||
|
||||
|
||||
if ((servo_mode != MK::MODE_NONE) && (update_rate != 0))
|
||||
g_mk->set_pwm_rate(update_rate);
|
||||
g_mk->set_update_rate(update_rate);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
mk_start(unsigned bus, unsigned motors, char *device_path)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
if (g_mk == nullptr) {
|
||||
|
||||
g_mk = new MK(bus, device_path);
|
||||
|
||||
if (g_mk == nullptr) {
|
||||
ret = -ENOMEM;
|
||||
|
||||
} else {
|
||||
ret = g_mk->init(motors);
|
||||
|
||||
if (ret != OK) {
|
||||
delete g_mk;
|
||||
g_mk = nullptr;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
int
|
||||
mk_check_for_i2c_esc_bus(char *device_path, int motors)
|
||||
mk_start(unsigned motors, char *device_path)
|
||||
{
|
||||
int ret;
|
||||
|
||||
if (g_mk == nullptr) {
|
||||
// try i2c3 first
|
||||
g_mk = new MK(3, device_path);
|
||||
|
||||
g_mk = new MK(3, device_path);
|
||||
if (!g_mk)
|
||||
return -ENOMEM;
|
||||
|
||||
if (g_mk == nullptr) {
|
||||
return -1;
|
||||
|
||||
} else {
|
||||
ret = g_mk->mk_check_for_blctrl(8, false, true);
|
||||
delete g_mk;
|
||||
g_mk = nullptr;
|
||||
|
||||
if (ret > 0) {
|
||||
return 3;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
g_mk = new MK(1, device_path);
|
||||
|
||||
if (g_mk == nullptr) {
|
||||
return -1;
|
||||
|
||||
} else {
|
||||
ret = g_mk->mk_check_for_blctrl(8, false, true);
|
||||
delete g_mk;
|
||||
g_mk = nullptr;
|
||||
|
||||
if (ret > 0) {
|
||||
return 1;
|
||||
}
|
||||
if (OK == g_mk->init(motors)) {
|
||||
warnx("[mkblctrl] scanning i2c3...\n");
|
||||
ret = g_mk->mk_check_for_blctrl(8, false, true);
|
||||
|
||||
if (ret > 0) {
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
delete g_mk;
|
||||
g_mk = nullptr;
|
||||
|
||||
// fallback to bus 1
|
||||
g_mk = new MK(1, device_path);
|
||||
|
||||
if (!g_mk)
|
||||
return -ENOMEM;
|
||||
|
||||
if (OK == g_mk->init(motors)) {
|
||||
warnx("[mkblctrl] scanning i2c1...\n");
|
||||
ret = g_mk->mk_check_for_blctrl(8, false, true);
|
||||
|
||||
if (ret > 0) {
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
|
||||
delete g_mk;
|
||||
g_mk = nullptr;
|
||||
|
||||
return -ENXIO;
|
||||
}
|
||||
|
||||
|
||||
} // namespace
|
||||
|
@ -1472,10 +1224,8 @@ extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]);
|
|||
int
|
||||
mkblctrl_main(int argc, char *argv[])
|
||||
{
|
||||
PortMode port_mode = PORT_FULL_PWM;
|
||||
int pwm_update_rate_in_hz = UPDATE_RATE;
|
||||
int motorcount = 8;
|
||||
int bus = -1;
|
||||
int px4mode = MAPPING_PX4;
|
||||
int frametype = FRAME_PLUS; // + plus is default
|
||||
bool motortest = false;
|
||||
|
@ -1489,18 +1239,6 @@ mkblctrl_main(int argc, char *argv[])
|
|||
*/
|
||||
for (int i = 1; i < argc; i++) {
|
||||
|
||||
/* look for the optional i2c bus parameter */
|
||||
if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) {
|
||||
if (argc > i + 1) {
|
||||
bus = atoi(argv[i + 1]);
|
||||
newMode = true;
|
||||
|
||||
} else {
|
||||
errx(1, "missing argument for i2c bus (-b)");
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
/* look for the optional frame parameter */
|
||||
if (strcmp(argv[i], "-mkmode") == 0 || strcmp(argv[i], "--mkmode") == 0) {
|
||||
if (argc > i + 1) {
|
||||
|
@ -1560,51 +1298,43 @@ mkblctrl_main(int argc, char *argv[])
|
|||
fprintf(stderr, "mkblctrl: help:\n");
|
||||
fprintf(stderr, " [-mkmode {+/x}] [-b i2c_bus_number] [-d devicename] [--override-security-checks] [-h / --help]\n\n");
|
||||
fprintf(stderr, "\t -mkmode {+/x} \t\t Type of frame, if Mikrokopter motor order is used.\n");
|
||||
fprintf(stderr, "\t -b {i2c_bus_number} \t\t Set the i2c bus where the ESCs are connected to (default autoscan).\n");
|
||||
fprintf(stderr, "\t -d {devicepath & name}\t\t Create alternate pwm device.\n");
|
||||
fprintf(stderr, "\t --override-security-checks \t\t Disable all security checks (arming and number of ESCs). Used to test single Motors etc. (DANGER !!!)\n");
|
||||
fprintf(stderr, "\n");
|
||||
fprintf(stderr, "Motortest:\n");
|
||||
fprintf(stderr, "First you have to start mkblctrl, the you can enter Motortest Mode with:\n");
|
||||
fprintf(stderr, "mkblctrl -t\n");
|
||||
fprintf(stderr, "This will spin up once every motor in order of motoraddress. (DANGER !!!)\n");
|
||||
fprintf(stderr, "This will spin up once every motor in order of motoraddress. (DANGER !!!)\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
|
||||
if (!motortest) {
|
||||
if (g_mk == nullptr) {
|
||||
if (bus == -1) {
|
||||
bus = mk_check_for_i2c_esc_bus(devicepath, motorcount);
|
||||
}
|
||||
if (g_mk == nullptr) {
|
||||
if (mk_start(motorcount, devicepath) != OK) {
|
||||
errx(1, "failed to start the MK-BLCtrl driver");
|
||||
}
|
||||
|
||||
if (bus != -1) {
|
||||
if (mk_start(bus, motorcount, devicepath) != OK) {
|
||||
errx(1, "failed to start the MK-BLCtrl driver");
|
||||
}
|
||||
} else {
|
||||
errx(1, "failed to start the MK-BLCtrl driver (cannot find i2c esc's)");
|
||||
}
|
||||
/* parameter set ? */
|
||||
if (newMode) {
|
||||
/* switch parameter */
|
||||
return mk_new_mode(pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks);
|
||||
}
|
||||
|
||||
/* parameter set ? */
|
||||
if (newMode) {
|
||||
/* switch parameter */
|
||||
return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks);
|
||||
}
|
||||
exit(0);
|
||||
|
||||
exit(0);
|
||||
} else {
|
||||
errx(1, "MK-BLCtrl driver already running");
|
||||
}
|
||||
} else {
|
||||
errx(1, "MK-BLCtrl driver already running");
|
||||
}
|
||||
|
||||
} else {
|
||||
if (g_mk == nullptr) {
|
||||
errx(1, "MK-BLCtrl driver not running. You have to start it first.");
|
||||
} else {
|
||||
if (g_mk == nullptr) {
|
||||
errx(1, "MK-BLCtrl driver not running. You have to start it first.");
|
||||
|
||||
} else {
|
||||
g_mk->set_motor_test(motortest);
|
||||
exit(0);
|
||||
} else {
|
||||
g_mk->set_motor_test(motortest);
|
||||
exit(0);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -626,7 +626,7 @@ PX4FMU::task_main()
|
|||
#ifdef HRT_PPM_CHANNEL
|
||||
|
||||
// see if we have new PPM input data
|
||||
if (ppm_last_valid_decode != rc_in.timestamp) {
|
||||
if (ppm_last_valid_decode != rc_in.timestamp_last_signal) {
|
||||
// we have a new PPM frame. Publish it.
|
||||
rc_in.channel_count = ppm_decoded_channels;
|
||||
|
||||
|
@ -638,7 +638,15 @@ PX4FMU::task_main()
|
|||
rc_in.values[i] = ppm_buffer[i];
|
||||
}
|
||||
|
||||
rc_in.timestamp = ppm_last_valid_decode;
|
||||
rc_in.timestamp_publication = ppm_last_valid_decode;
|
||||
rc_in.timestamp_last_signal = ppm_last_valid_decode;
|
||||
|
||||
rc_in.rc_ppm_frame_length = ppm_frame_length;
|
||||
rc_in.rssi = RC_INPUT_RSSI_MAX;
|
||||
rc_in.rc_failsafe = false;
|
||||
rc_in.rc_lost = false;
|
||||
rc_in.rc_lost_frame_count = 0;
|
||||
rc_in.rc_total_frame_count = 0;
|
||||
|
||||
/* lazily advertise on first publication */
|
||||
if (to_input_rc == 0) {
|
||||
|
@ -1006,6 +1014,40 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET_COUNT: {
|
||||
/* change the number of outputs that are enabled for
|
||||
* PWM. This is used to change the split between GPIO
|
||||
* and PWM under control of the flight config
|
||||
* parameters. Note that this does not allow for
|
||||
* changing a set of pins to be used for serial on
|
||||
* FMUv1
|
||||
*/
|
||||
switch (arg) {
|
||||
case 0:
|
||||
set_mode(MODE_NONE);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
set_mode(MODE_2PWM);
|
||||
break;
|
||||
|
||||
case 4:
|
||||
set_mode(MODE_4PWM);
|
||||
break;
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
case 6:
|
||||
set_mode(MODE_6PWM);
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MIXERIOCRESET:
|
||||
if (_mixers != nullptr) {
|
||||
delete _mixers;
|
||||
|
@ -1108,10 +1150,12 @@ PX4FMU::sensor_reset(int ms)
|
|||
stm32_configgpio(GPIO_SPI_CS_GYRO_OFF);
|
||||
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG_OFF);
|
||||
stm32_configgpio(GPIO_SPI_CS_BARO_OFF);
|
||||
stm32_configgpio(GPIO_SPI_CS_MPU_OFF);
|
||||
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU_OFF, 0);
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI1_MISO_OFF);
|
||||
|
@ -1124,10 +1168,12 @@ PX4FMU::sensor_reset(int ms)
|
|||
stm32_configgpio(GPIO_GYRO_DRDY_OFF);
|
||||
stm32_configgpio(GPIO_MAG_DRDY_OFF);
|
||||
stm32_configgpio(GPIO_ACCEL_DRDY_OFF);
|
||||
stm32_configgpio(GPIO_EXTI_MPU_DRDY_OFF);
|
||||
|
||||
stm32_gpiowrite(GPIO_GYRO_DRDY_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_MAG_DRDY_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_ACCEL_DRDY_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_EXTI_MPU_DRDY_OFF, 0);
|
||||
|
||||
/* set the sensor rail off */
|
||||
stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
|
||||
|
@ -1160,6 +1206,13 @@ PX4FMU::sensor_reset(int ms)
|
|||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
|
||||
// // XXX bring up the EXTI pins again
|
||||
// stm32_configgpio(GPIO_GYRO_DRDY);
|
||||
// stm32_configgpio(GPIO_MAG_DRDY);
|
||||
// stm32_configgpio(GPIO_ACCEL_DRDY);
|
||||
// stm32_configgpio(GPIO_EXTI_MPU_DRDY);
|
||||
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
@ -1432,7 +1485,6 @@ void
|
|||
sensor_reset(int ms)
|
||||
{
|
||||
int fd;
|
||||
int ret;
|
||||
|
||||
fd = open(PX4FMU_DEVICE_PATH, O_RDWR);
|
||||
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue