Merge remote-tracking branch 'px4/beta' into beta_mavlink

Conflicts:
	src/modules/mavlink/mavlink.c
	src/modules/mavlink/mavlink_receiver.h
	src/modules/mavlink/orb_listener.c
This commit is contained in:
Julian Oes
2014-02-12 17:10:20 +01:00
172 changed files with 4794 additions and 3548 deletions

View File

@@ -2,44 +2,13 @@
#
# HILStar / X-Plane
#
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
# Lorenz Meier <lm@inf.ethz.ch>
#
sh /etc/init.d/rc.fw_defaults
echo "HIL Rascal 110 starting.."
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
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 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
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_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
set HIL yes
set VEHICLE_TYPE fw
set MIXER FMU_AERT

View File

@@ -2,28 +2,28 @@
#
# Team Blacksheep Discovery Quadcopter
#
# Maintainers: Simon Wilks <sjwilks@gmail.com>
# Anton Babushkin <anton.babushkin@me.com>, Simon Wilks <sjwilks@gmail.com>
#
sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set MC_ATT_P 5.0
param set MC_ATT_I 0.0
param set MC_YAW_P 0.5
param set MC_YAW_I 0.15
param set MC_ATTRATE_P 0.17
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.006
param set MC_YAWRATE_P 0.2
# TODO review MC_YAWRATE_I
param set MC_ROLL_P 8.0
param set MC_ROLLRATE_P 0.07
param set MC_ROLLRATE_I 0.05
param set MC_ROLLRATE_D 0.0017
param set MC_PITCH_P 8.0
param set MC_PITCHRATE_P 0.14
param set MC_PITCHRATE_I 0.1
param set MC_PITCHRATE_D 0.0025
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.28
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
fi
set VEHICLE_TYPE mc
set MIXER FMU_quad_w
set PWM_OUTPUTS 1234
set PWM_RATE 400

View File

@@ -2,48 +2,31 @@
#
# 3DR Iris Quadcopter
#
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set MC_ATT_P 9.0
param set MC_ATT_I 0.0
# TODO tune roll/pitch separately
param set MC_ROLL_P 9.0
param set MC_ROLLRATE_P 0.13
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.004
param set MC_PITCH_P 9.0
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.004
param set MC_YAW_P 0.5
param set MC_YAW_I 0.15
param set MC_ATTRATE_P 0.13
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
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 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
param set BAT_V_SCALING 0.00989
param set BAT_C_SCALING 0.0124
fi
set VEHICLE_TYPE mc
set MIXER FMU_quad_w
set PWM_OUTPUTS 1234
set PWM_RATE 400
set PWM_DISARMED 900
set PWM_MIN 1000
set PWM_MAX 2000

View File

@@ -2,41 +2,11 @@
#
# HIL Quadcopter X
#
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton.babushkin@me.com>
#
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_YAW_P 2.0
param set MC_YAW_I 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_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.005
param set MPC_TILT_MAX 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
fi
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_x
set HIL yes
set VEHICLE_TYPE mc
set MIXER FMU_quad_x

View File

@@ -1,45 +0,0 @@
#!nsh
#
# HIL Rascal 110 (Flightgear)
#
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
#
echo "HIL Rascal 110 starting.."
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
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 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
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_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
set HIL yes
set VEHICLE_TYPE fw
set MIXER FMU_AERT

View File

@@ -2,9 +2,11 @@
#
# HIL Quadcopter +
#
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/1001_rc_quad_x.hil
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_+
set HIL yes

View File

@@ -2,44 +2,13 @@
#
# HIL Rascal 110 (Flightgear)
#
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
# Thomas Gubler <thomasgubler@gmail.com>
#
sh /etc/init.d/rc.fw_defaults
echo "HIL Rascal 110 starting.."
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
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 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
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_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
set HIL yes
set VEHICLE_TYPE fw
set MIXER FMU_AERT

View File

@@ -0,0 +1,47 @@
#!nsh
#
# HIL Malolo 1 (Flightgear)
#
# Thomas Gubler <thomasgubler@gmail.com>
#
sh /etc/init.d/rc.fw_defaults
if [ $DO_AUTOCONFIG == yes ]
then
param set FW_AIRSPD_MIN 12
param set FW_AIRSPD_TRIM 25
param set FW_AIRSPD_MAX 40
param set FW_ATT_TC 0.3
param set FW_L1_DAMPING 0.74
param set FW_L1_PERIOD 15
param set FW_PR_FF 0.8
param set FW_PR_I 0.05
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.1
param set FW_P_ROLLFF 0
param set FW_RR_FF 0.6
param set FW_RR_I 0.02
param set FW_RR_IMAX 0.2
param set FW_RR_P 0.1
param set FW_R_LIM 45
param set FW_R_RMAX 0
param set FW_T_CLMB_MAX 5
param set FW_T_HRATE_P 0.02
param set FW_T_PTCH_DAMP 0
param set FW_T_RLL2THR 15
param set FW_T_SINK_MAX 5
param set FW_T_SINK_MIN 2
param set FW_T_SRATE_P 0.01
param set FW_T_TIME_CONST 3
param set FW_T_VERT_ACC 7
param set FW_YR_FF 0.0
param set FW_YR_I 0
param set FW_YR_IMAX 0.2
param set FW_YR_P 0.0
fi
set HIL yes
# Set the AERT mixer for HIL (even if the malolo is a flying wing)
set MIXER FMU_AERT

View File

@@ -0,0 +1,15 @@
#!nsh
#
# UNTESTED UNTESTED!
#
# Generic 10” Hexa coaxial geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
#
sh /etc/init.d/rc.mc_defaults
set MIXER hexa_cox
# We only can run one channel group with one rate, so set all 8 channels
set PWM_OUTPUTS 12345678

View File

@@ -0,0 +1,12 @@
#!nsh
#
# Generic 10” Octo coaxial geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
#
sh /etc/init.d/rc.mc_defaults
set MIXER octo_cox
set PWM_OUTPUTS 12345678

View File

@@ -1,37 +0,0 @@
#!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

View File

@@ -2,38 +2,7 @@
#
# MPX EasyStar Plane
#
# Maintainers: ???
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
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 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
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_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16
param set RC_SCALE_ROLL 1.0
param set RC_SCALE_PITCH 1.0
fi
sh /etc/init.d/rc.fw_defaults
set VEHICLE_TYPE fw
set MIXER FMU_RET

View File

@@ -1,40 +1,5 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
sh /etc/init.d/rc.fw_defaults
#
# Load default params for this platform
#
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
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 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
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_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
set VEHICLE_TYPE fw
set MIXER FMU_AERT

View File

@@ -1,40 +1,5 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
sh /etc/init.d/rc.fw_defaults
#
# Load default params for this platform
#
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
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 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
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_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
set VEHICLE_TYPE fw
set MIXER FMU_AERT

View File

@@ -1,40 +1,5 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
sh /etc/init.d/rc.fw_defaults
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

View File

@@ -2,43 +2,7 @@
#
# Phantom FPV Flying Wing
#
# Maintainers: Simon Wilks <sjwilks@gmail.com>
# 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

View File

@@ -2,42 +2,38 @@
#
# Skywalker X5 Flying Wing
#
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
# Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
#
sh /etc/init.d/rc.fw_defaults
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_AIRSPD_MIN 15
param set FW_AIRSPD_TRIM 20
param set FW_AIRSPD_MAX 40
param set FW_ATT_TC 0.3
param set FW_L1_DAMPING 0.74
param set FW_L1_PERIOD 15
param set FW_PR_FF 0.3
param set FW_PR_I 0
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.03
param set FW_P_LIM_MAX 45
param set FW_P_LIM_MIN -45
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 FW_P_ROLLFF 0
param set FW_RR_FF 0.3
param set FW_RR_I 0
param set FW_RR_IMAX 0.2
param set FW_RR_P 0.03
param set FW_R_LIM 60
param set FW_R_RMAX 0
param set FW_T_HRATE_P 0.01
param set FW_T_RLL2THR 15
param set FW_T_SRATE_P 0.01
param set FW_T_TIME_CONST 5
fi
set VEHICLE_TYPE fw
set MIXER FMU_X5

View File

@@ -2,42 +2,9 @@
#
# Wing Wing (aka Z-84) Flying Wing
#
# Maintainers: Simon Wilks <sjwilks@gmail.com>
# 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
sh /etc/init.d/rc.fw_defaults
set VEHICLE_TYPE fw
set MIXER FMU_Q

View File

@@ -2,42 +2,9 @@
#
# FX-79 Buffalo Flying Wing
#
# Maintainers: Simon Wilks <sjwilks@gmail.com>
# 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
sh /etc/init.d/rc.fw_defaults
set VEHICLE_TYPE fw
set MIXER FMU_FX79

View File

@@ -0,0 +1,12 @@
#!nsh
#
# Generic 10” Quad X geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_x
set PWM_OUTPUTS 1234

View File

@@ -1,57 +0,0 @@
#!nsh
echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set MC_ATTRATE_D 0
param set MC_ATTRATE_I 0
param set MC_ATTRATE_P 0.13
param set MC_ATT_D 0
param set MC_ATT_I 0.3
param set MC_ATT_P 5
param set MC_YAWPOS_D 0.1
param set MC_YAWPOS_I 0.15
param set MC_YAWPOS_P 1
param set MC_YAWRATE_D 0
param set MC_YAWRATE_I 0
param set MC_YAWRATE_P 0.15
param set SYS_AUTOCONFIG 0
param save
fi
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
param set BAT_V_SCALING 0.008381
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
# Exit, because /dev/ttyS0 is needed for MAVLink
exit

View File

@@ -1,83 +0,0 @@
#!nsh
echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set MC_ATTRATE_D 0
param set MC_ATTRATE_I 0
param set MC_ATTRATE_P 0.13
param set MC_ATT_D 0
param set MC_ATT_I 0.3
param set MC_ATT_P 5
param set MC_YAWPOS_D 0.1
param set MC_YAWPOS_I 0.15
param set MC_YAWPOS_P 1
param set MC_YAWRATE_D 0
param set MC_YAWRATE_I 0
param set MC_YAWRATE_P 0.15
param set SYS_AUTOCONFIG 0
param save
fi
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
param set BAT_V_SCALING 0.008381
#
# Start MAVLink and MAVLink Onboard (PX4FLOW Sensor)
#
mavlink start -d /dev/ttyS0 -b 57600
mavlink_onboard start -d /dev/ttyS3 -b 115200
usleep 5000
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Start the position estimator
#
flow_position_estimator start
#
# Fire up the multi rotor attitude controller
#
mc_att_control_vector start
#
# Fire up the flow position controller
#
flow_position_control start
#
# Fire up the flow speed controller
#
flow_speed_control start
# Exit, because /dev/ttyS0 is needed for MAVLink
exit

View File

@@ -2,46 +2,26 @@
#
# DJI Flame Wheel F330 Quadcopter
#
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/4001_quad_x
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_ROLL_P 7.0
param set MC_ROLLRATE_P 0.1
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCHRATE_P 0.1
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAW_I 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_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.05
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MPC_TILT_MAX 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
fi
set VEHICLE_TYPE mc
set MIXER FMU_quad_x
set PWM_OUTPUTS 1234
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
set PWM_MIN 1200
set PWM_MIN 1175
set PWM_MAX 1900

View File

@@ -2,34 +2,27 @@
#
# DJI Flame Wheel F450 Quadcopter
#
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
# Lorenz Meier <lm@inf.ethz.ch>
#
sh /etc/init.d/4001_quad_x
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_YAW_P 2.0
param set MC_YAW_I 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_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.005
# TODO add default MPC parameters
# TODO REVIEW
param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.1
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCHRATE_P 0.1
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
fi
set VEHICLE_TYPE mc
set MIXER FMU_quad_x
set PWM_OUTPUTS 1234
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
set PWM_MIN 1200
set PWM_MIN 1175
set PWM_MAX 1900

View File

@@ -1,31 +0,0 @@
#!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_YAW_P 0.6
param set MC_YAW_I 0
param set MC_ATTRATE_P 0.14
param set MC_ATTRATE_I 0
param set MC_ATTRATE_D 0.006
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

View File

@@ -0,0 +1,12 @@
#!nsh
#
# Generic 10” Quad + geometry
#
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_+
set PWM_OUTPUTS 1234

View File

@@ -1,37 +0,0 @@
#!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

View File

@@ -0,0 +1,13 @@
#!nsh
#
# Generic 10” Hexa X geometry
#
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_x
# We only can run one channel group with one rate, so set all 8 channels
set PWM_OUTPUTS 12345678

View File

@@ -1,37 +0,0 @@
#!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

View File

@@ -0,0 +1,13 @@
#!nsh
#
# Generic 10” Hexa + geometry
#
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_+
# We only can run one channel group with one rate, so set all 8 channels
set PWM_OUTPUTS 12345678

View File

@@ -1,37 +0,0 @@
#!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

View File

@@ -0,0 +1,12 @@
#!nsh
#
# Generic 10” Octo X geometry
#
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_x
set PWM_OUTPUTS 12345678

View File

@@ -1,37 +0,0 @@
#!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

View File

@@ -0,0 +1,12 @@
#!nsh
#
# Generic 10” Octo + geometry
#
# Anton Babushkin <anton.babushkin@me.com>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_+
set PWM_OUTPUTS 12345678

View File

@@ -1,37 +0,0 @@
#!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

View File

@@ -23,7 +23,7 @@
if param compare SYS_AUTOSTART 1000
then
#sh /etc/init.d/1000_rc_fw_easystar.hil
sh /etc/init.d/1000_rc_fw_easystar.hil
fi
if param compare SYS_AUTOSTART 1001
@@ -31,11 +31,6 @@ 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
@@ -46,6 +41,11 @@ then
sh /etc/init.d/1004_rc_fw_Rascal110.hil
fi
if param compare SYS_AUTOSTART 1005
then
sh /etc/init.d/1005_rc_fw_Malolo1.hil
fi
#
# Standard plane
#
@@ -101,14 +101,9 @@ fi
# Quad X
#
if param compare SYS_AUTOSTART 4008 8
if param compare SYS_AUTOSTART 4001
then
#sh /etc/init.d/4008_ardrone
fi
if param compare SYS_AUTOSTART 4009 9
then
#sh /etc/init.d/4009_ardrone_flow
sh /etc/init.d/4001_quad_x
fi
if param compare SYS_AUTOSTART 4010 10
@@ -121,18 +116,13 @@ 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
sh /etc/init.d/5001_quad_+
fi
#
@@ -141,7 +131,7 @@ fi
if param compare SYS_AUTOSTART 6001
then
sh /etc/init.d/6001_hexa_x_pwm
sh /etc/init.d/6001_hexa_x
fi
#
@@ -150,7 +140,7 @@ fi
if param compare SYS_AUTOSTART 7001
then
sh /etc/init.d/7001_hexa_+_pwm
sh /etc/init.d/7001_hexa_+
fi
#
@@ -159,7 +149,7 @@ fi
if param compare SYS_AUTOSTART 8001
then
sh /etc/init.d/8001_octo_x_pwm
sh /etc/init.d/8001_octo_x
fi
#
@@ -168,7 +158,7 @@ fi
if param compare SYS_AUTOSTART 9001
then
sh /etc/init.d/9001_octo_+_pwm
sh /etc/init.d/9001_octo_+
fi
#
@@ -185,11 +175,20 @@ then
sh /etc/init.d/10016_3dr_iris
fi
#
# Hexa Coaxial
#
if param compare SYS_AUTOSTART 11001
then
sh /etc/init.d/11001_hexa_cox
fi
#
# Octo Coaxial
#
if param compare SYS_AUTOSTART 12001
then
sh /etc/init.d/12001_octo_cox_pwm
sh /etc/init.d/12001_octo_cox
fi

View File

@@ -3,17 +3,6 @@
# 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

View File

@@ -0,0 +1,13 @@
#!nsh
set VEHICLE_TYPE fw
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for FW
#
param set NAV_LAND_ALT 90
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
fi

View File

@@ -4,7 +4,6 @@
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
#
px4io recovery

View File

@@ -8,7 +8,7 @@ then
if hw_ver compare PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
sdlog2 start -r 50 -a -b 16 -t
sdlog2 start -r 50 -a -b 8 -t
else
echo "Start sdlog2 at 200Hz"
sdlog2 start -r 200 -a -b 16 -t

View File

@@ -1,24 +1,11 @@
#!nsh
#
# Standard apps for multirotors
# Standard apps for multirotors:
# att & pos estimator, att & pos control.
#
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Start position estimator
#
position_estimator_inav start
#
# Start attitude control
#
mc_att_control start
#
# Start position control
#
mc_pos_control start

View File

@@ -0,0 +1,43 @@
#!nsh
set VEHICLE_TYPE mc
if [ $DO_AUTOCONFIG == yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.1
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
param set MC_PITCHRATE_P 0.1
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.5
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_P 0.1
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_MAX 5
param set MPC_XY_FF 0.5
param set MPC_Z_P 1.0
param set MPC_Z_VEL_P 0.1
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_MAX 3
param set MPC_Z_FF 0.5
param set MPC_TILT_MAX 1.0
param set MPC_LAND_SPEED 1.0
param set MPC_LAND_TILT 0.3
fi
set PWM_RATE 400
set PWM_DISARMED 900
set PWM_MIN 1075
set PWM_MAX 2000

View File

@@ -3,10 +3,6 @@
# Standard startup script for PX4FMU onboard sensor drivers.
#
#
# Start sensor drivers here.
#
ms5611 start
adc start

View File

@@ -3,8 +3,7 @@
# PX4FMU startup script.
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
# Default to auto-start mode.
#
set MODE autostart
@@ -465,17 +464,25 @@ then
if [ $MIXER == none ]
then
# Set default mixer for multicopter if not defined
set MIXER quad_x
echo "Default mixer for multicopter not defined"
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_+ ]
if [ $MIXER == FMU_quad_x -o $MIXER == FMU_quad_+ ]
then
set MAV_TYPE 2
fi
if [ $MIXER == FMU_quad_w ]
then
set MAV_TYPE 2
fi
if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ]
then
set MAV_TYPE 13
fi
if [ $MIXER == hexa_cox ]
then
set MAV_TYPE 13
fi
@@ -488,8 +495,14 @@ then
set MAV_TYPE 14
fi
fi
param set MAV_TYPE $MAV_TYPE
# Still no MAV_TYPE found
if [ $MAV_TYPE == none ]
then
echo "Unknown MAV_TYPE"
else
param set MAV_TYPE $MAV_TYPE
fi
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
@@ -503,10 +516,8 @@ then
#
if [ $VEHICLE_TYPE == none ]
then
echo "[init] Vehicle type: GENERIC"
echo "[init] Vehicle type: No autostart ID found"
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
fi
# Start any custom addons

View File

@@ -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
--------

View File

@@ -23,13 +23,13 @@ for the elevons.
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 -3000 -5000 0 -10000 10000
S: 0 1 -5000 -5000 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 -5000 -3000 0 -10000 10000
S: 0 1 5000 5000 0 -10000 10000
S: 0 0 -8000 -8000 0 -10000 10000
S: 0 1 -6000 -6000 0 -10000 10000
Output 2
--------
@@ -48,7 +48,7 @@ M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
Gimbal / payload mixer for last four channels
Gimbal / flaps / payload mixer for last four channels
-----------------------------------------------------
M: 1
@@ -66,4 +66,3 @@ S: 0 6 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 7 10000 10000 0 -10000 10000

View File

@@ -1,18 +0,0 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a hexacopter in the + configuration. All controls
are mixed 100%.
R: 6+ 10000 10000 10000 0
Gimbal / payload mixer for last two channels
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 7 10000 10000 0 -10000 10000

View File

@@ -1,18 +0,0 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a hexacopter in the X configuration. All controls
are mixed 100%.
R: 6x 10000 10000 10000 0
Gimbal / payload mixer for last two channels
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 7 10000 10000 0 -10000 10000

View File

@@ -0,0 +1,3 @@
# Hexa +
R: 6+ 10000 10000 10000 0

View File

@@ -0,0 +1,3 @@
# Hexa X
R: 6x 10000 10000 10000 0

View File

@@ -1,7 +1,3 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a octocopter in the + configuration. All controls
are mixed 100%.
# Octo +
R: 8+ 10000 10000 10000 0

View File

@@ -1,7 +1,3 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a Coaxial Octocopter in the X configuration. All controls
are mixed 100%.
# Octo coaxial
R: 8c 10000 10000 10000 0

View File

@@ -1,7 +1,3 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a octocopter in the X configuration. All controls
are mixed 100%.
# Octo X
R: 8x 10000 10000 10000 0

View File

@@ -1,154 +0,0 @@
PX4 mixer definitions
=====================
Files in this directory implement example mixers that can be used as a basis
for customisation, or for general testing purposes.
Mixer basics
------------
Mixers combine control values from various sources (control tasks, user inputs,
etc.) and produce output values suitable for controlling actuators; servos,
motors, switches and so on.
An actuator derives its value from the combination of one or more control
values. Each of the control values is scaled according to the actuator's
configuration and then combined to produce the actuator value, which may then be
further scaled to suit the specific output type.
Internally, all scaling is performed using floating point values. Inputs and
outputs are clamped to the range -1.0 to 1.0.
control control control
| | |
v v v
scale scale scale
| | |
| v |
+-------> mix <------+
|
scale
|
v
out
Scaling
-------
Basic scalers provide linear scaling of the input to the output.
Each scaler allows the input value to be scaled independently for inputs
greater/less than zero. An offset can be applied to the output, and lower and
upper boundary constraints can be applied. Negative scaling factors cause the
output to be inverted (negative input produces positive output).
Scaler pseudocode:
if (input < 0)
output = (input * NEGATIVE_SCALE) + OFFSET
else
output = (input * POSITIVE_SCALE) + OFFSET
if (output < LOWER_LIMIT)
output = LOWER_LIMIT
if (output > UPPER_LIMIT)
output = UPPER_LIMIT
Syntax
------
Mixer definitions are text files; lines beginning with a single capital letter
followed by a colon are significant. All other lines are ignored, meaning that
explanatory text can be freely mixed with the definitions.
Each file may define more than one mixer; the allocation of mixers to actuators
is specific to the device reading the mixer definition, and the number of
actuator outputs generated by a mixer is specific to the mixer.
A mixer begins with a line of the form
<tag>: <mixer arguments>
The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
multirotor mixer, etc.
Null Mixer
..........
A null mixer consumes no controls and generates a single actuator output whose
value is always zero. Typically a null mixer is used as a placeholder in a
collection of mixers in order to achieve a specific pattern of actuator outputs.
The null mixer definition has the form:
Z:
Simple Mixer
............
A simple mixer combines zero or more control inputs into a single actuator
output. Inputs are scaled, and the mixing function sums the result before
applying an output scaler.
A simple mixer definition begins with:
M: <control count>
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
If <control count> is zero, the sum is effectively zero and the mixer will
output a fixed value that is <offset> constrained by <lower limit> and <upper
limit>.
The second line defines the output scaler with scaler parameters as discussed
above. Whilst the calculations are performed as floating-point operations, the
values stored in the definition file are scaled by a factor of 10000; i.e. an
offset of -0.5 is encoded as -5000.
The definition continues with <control count> entries describing the control
inputs and their scaling, in the form:
S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
The <group> value identifies the control group from which the scaler will read,
and the <index> value an offset within that group. These values are specific to
the device reading the mixer definition.
When used to mix vehicle controls, mixer group zero is the vehicle attitude
control group, and index values zero through three are normally roll, pitch,
yaw and thrust respectively.
The remaining fields on the line configure the control scaler with parameters as
discussed above. Whilst the calculations are performed as floating-point
operations, the values stored in the definition file are scaled by a factor of
10000; i.e. an offset of -0.5 is encoded as -5000.
Multirotor Mixer
................
The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
into a set of actuator outputs intended to drive motor speed controllers.
The mixer definition is a single line of the form:
R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
The supported geometries include:
4x - quadrotor in X configuration
4+ - quadrotor in + configuration
6x - hexcopter in X configuration
6+ - hexcopter in + configuration
8x - octocopter in X configuration
8+ - octocopter in + configuration
Each of the roll, pitch and yaw scale values determine scaling of the roll,
pitch and yaw controls relative to the thrust control. Whilst the calculations
are performed as floating-point operations, the values stored in the definition
file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
range -1.0 to 1.0.
In the case where an actuator saturates, all actuator values are rescaled so that
the saturating actuator is limited to 1.0.

View File

@@ -0,0 +1,3 @@
# Hexa coaxial
R: 6c 10000 10000 10000 0

View File

@@ -1,2 +1,3 @@
parameters.wiki
parameters.xml
parameters.xml
cookies.txt

View File

@@ -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

View File

@@ -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"

View File

@@ -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('Latin-1') + ' ', 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('Latin-1'))
print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1'))
print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
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('Latin-1'), end='') # show user
print('')
print("erase...")
self.__erase()

View File

@@ -21,7 +21,6 @@ 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
@@ -44,7 +43,6 @@ MODULES += modules/sensors
#
MODULES += systemcmds/mtd
MODULES += systemcmds/bl_update
MODULES += systemcmds/boardinfo
MODULES += systemcmds/i2c
MODULES += systemcmds/mixer
MODULES += systemcmds/param
@@ -65,14 +63,12 @@ MODULES += systemcmds/hw_ver
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/attitude_estimator_ekf
MODULES += modules/attitude_estimator_so3
MODULES += modules/att_pos_estimator_ekf
MODULES += modules/position_estimator_inav
#MODULES += examples/flow_position_estimator

View File

@@ -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.

View File

@@ -18,6 +18,12 @@ MODULES += drivers/stm32/tone_alarm
MODULES += drivers/led
MODULES += drivers/boards/px4fmu-v2
MODULES += drivers/px4io
MODULES += drivers/rgbled
MODULES += drivers/mpu6000
MODULES += drivers/lsm303d
MODULES += drivers/l3gd20
MODULES += drivers/hmc5883
MODULES += drivers/ms5611
MODULES += systemcmds/perf
MODULES += systemcmds/reboot
MODULES += systemcmds/tests
@@ -31,6 +37,9 @@ MODULES += systemcmds/hw_ver
MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/uORB
LIBRARIES += lib/mathlib/CMSIS
MODULES += lib/mathlib
MODULES += lib/mathlib/math/filter
#
# Libraries

File diff suppressed because one or more lines are too long

View File

@@ -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
}

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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
}

View File

@@ -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
}

View File

@@ -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);

View File

@@ -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

View File

@@ -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

View File

@@ -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

View File

@@ -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);
}

View File

@@ -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

View File

@@ -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));

View File

@@ -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

View File

@@ -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

View File

@@ -209,8 +209,8 @@
#define GPIO_USART3_RX GPIO_USART3_RX_3
#define GPIO_USART3_TX GPIO_USART3_TX_3
#define GPIO_USART2_RTS GPIO_USART2_RTS_2
#define GPIO_USART2_CTS GPIO_USART2_CTS_2
#define GPIO_USART3_RTS GPIO_USART3_RTS_2
#define GPIO_USART3_CTS GPIO_USART3_CTS_2
#define GPIO_UART4_RX GPIO_UART4_RX_1
#define GPIO_UART4_TX GPIO_UART4_TX_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

View File

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -86,6 +86,7 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) :
_collect_phase(false),
_diff_pres_offset(0.0f),
_airspeed_pub(-1),
_class_instance(-1),
_conversion_interval(conversion_interval),
_sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")),
_comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors"))
@@ -102,6 +103,9 @@ Airspeed::~Airspeed()
/* make sure we are truly inactive */
stop();
if (_class_instance != -1)
unregister_class_devname(AIRSPEED_DEVICE_PATH, _class_instance);
/* free any existing reports */
if (_reports != nullptr)
delete _reports;
@@ -126,13 +130,23 @@ Airspeed::init()
if (_reports == nullptr)
goto out;
/* get a publish handle on the airspeed topic */
differential_pressure_s zero_report;
memset(&zero_report, 0, sizeof(zero_report));
_airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &zero_report);
/* register alternate interfaces if we have to */
_class_instance = register_class_devname(AIRSPEED_DEVICE_PATH);
if (_airspeed_pub < 0)
warnx("failed to create airspeed sensor object. Did you start uOrb?");
/* publication init */
if (_class_instance == CLASS_DEVICE_PRIMARY) {
/* advertise sensor topic, measure manually to initialize valid report */
struct differential_pressure_s arp;
measure();
_reports->get(&arp);
/* measurement will have generated a report, publish */
_airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp);
if (_airspeed_pub < 0)
warnx("failed to create airspeed sensor object. uORB started?");
}
ret = OK;
/* sensor is ok, but we don't really know if it is within range */

View File

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -127,6 +127,8 @@ protected:
orb_advert_t _airspeed_pub;
int _class_instance;
unsigned _conversion_interval;
perf_counter_t _sample_perf;

View File

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 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
@@ -153,6 +153,7 @@ private:
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
int _class_instance;
unsigned _current_lowpass;
unsigned _current_range;
@@ -238,6 +239,7 @@ BMA180::BMA180(int bus, spi_dev_e device) :
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
_accel_topic(-1),
_class_instance(-1),
_current_lowpass(0),
_current_range(0),
_sample_perf(perf_alloc(PC_ELAPSED, "bma180_read"))
@@ -282,11 +284,6 @@ BMA180::init()
if (_reports == nullptr)
goto out;
/* advertise sensor topic */
struct accel_report zero_report;
memset(&zero_report, 0, sizeof(zero_report));
_accel_topic = orb_advertise(ORB_ID(sensor_accel), &zero_report);
/* perform soft reset (p48) */
write_reg(ADDR_RESET, SOFT_RESET);
@@ -322,6 +319,19 @@ BMA180::init()
ret = ERROR;
}
_class_instance = register_class_devname(ACCEL_DEVICE_PATH);
/* advertise sensor topic, measure manually to initialize valid report */
measure();
if (_class_instance == CLASS_DEVICE_PRIMARY) {
struct accel_report arp;
_reports->get(&arp);
/* measurement will have generated a report, publish */
_accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
}
out:
return ret;
}
@@ -723,7 +733,8 @@ BMA180::measure()
poll_notify(POLLIN);
/* publish for subscribers */
orb_publish(ORB_ID(sensor_accel), _accel_topic, &report);
if (_accel_topic > 0 && !(_pub_blocked))
orb_publish(ORB_ID(sensor_accel), _accel_topic, &report);
/* stop the perf counter */
perf_end(_sample_perf);

View File

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 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
@@ -38,6 +38,7 @@
*/
#include "device.h"
#include "drivers/drv_device.h"
#include <sys/ioctl.h>
#include <arch/irq.h>
@@ -93,6 +94,7 @@ CDev::CDev(const char *name,
Device(name, irq),
// public
// protected
_pub_blocked(false),
// private
_devname(devname),
_registered(false),
@@ -256,6 +258,14 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg)
case DIOC_GETPRIV:
*(void **)(uintptr_t)arg = (void *)this;
return OK;
break;
case DEVIOCSPUBBLOCK:
_pub_blocked = (arg != 0);
return OK;
break;
case DEVIOCGPUBBLOCK:
return _pub_blocked;
break;
}
return -ENOTTY;

View File

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 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

View File

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 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
@@ -415,6 +415,8 @@ protected:
*/
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
bool _pub_blocked; /**< true if publishing should be blocked */
private:
static const unsigned _max_pollwaiters = 8;

62
src/drivers/drv_device.h Normal file
View File

@@ -0,0 +1,62 @@
/****************************************************************************
*
* 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_device.h
*
* Generic device / sensor interface.
*/
#ifndef _DRV_DEVICE_H
#define _DRV_DEVICE_H
#include <stdint.h>
#include <sys/ioctl.h>
#include "drv_sensor.h"
#include "drv_orb_dev.h"
/*
* ioctl() definitions
*/
#define _DEVICEIOCBASE (0x100)
#define _DEVICEIOC(_n) (_IOC(_DEVICEIOCBASE, _n))
/** ask device to stop publishing */
#define DEVIOCSPUBBLOCK _DEVICEIOC(0)
/** check publication block status */
#define DEVIOCGPUBBLOCK _DEVICEIOC(1)
#endif /* _DRV_DEVICE_H */

View File

@@ -193,6 +193,20 @@ ORB_DECLARE(output_pwm);
* 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)

View File

@@ -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 */

58
src/drivers/drv_sbus.h Normal file
View File

@@ -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 */

View File

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -184,8 +184,10 @@ ETSAirspeed::collect()
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
/* announce the airspeed if needed, just publish else */
orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report);
if (_airspeed_pub > 0 && !(_pub_blocked)) {
/* publish it */
orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report);
}
new_report(report);

View File

@@ -225,7 +225,7 @@ void frsky_send_frame2(int uart)
float course = 0, lat = 0, lon = 0, speed = 0, alt = 0;
char lat_ns = 0, lon_ew = 0;
int sec = 0;
if (global_pos.valid) {
if (global_pos.global_valid) {
time_t time_gps = global_pos.time_gps_usec / 1000000;
struct tm *tm_gps = gmtime(&time_gps);

View File

@@ -289,11 +289,13 @@ GPS::task_main()
//no time and satellite information simulated
if (_report_pub > 0) {
orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
if (!(_pub_blocked)) {
if (_report_pub > 0) {
orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
} else {
_report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
} else {
_report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
}
}
usleep(2e5);
@@ -330,11 +332,14 @@ GPS::task_main()
while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
// lock();
/* opportunistic publishing - else invalid data would end up on the bus */
if (_report_pub > 0) {
orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
} else {
_report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
if (!(_pub_blocked)) {
if (_report_pub > 0) {
orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
} else {
_report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
}
}
last_rate_count++;

View File

@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012,2013 PX4 Development Team. All rights reserved.
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
* 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
@@ -41,6 +39,9 @@
/**
* @file gps_helper.cpp
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
*/
float

Some files were not shown because too many files have changed in this diff Show More