aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults3
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb2
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS82
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp2
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp4
-rw-r--r--src/modules/commander/commander.cpp2
-rw-r--r--src/modules/fw_att_control/fw_att_control_params.c367
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp6
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c11
-rw-r--r--src/modules/mavlink/mavlink_main.cpp98
-rw-r--r--src/modules/mavlink/mavlink_main.h1
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp18
-rw-r--r--src/modules/navigator/navigator_main.cpp42
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c128
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c3
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h2
-rw-r--r--src/modules/uORB/topics/actuator_armed.h20
19 files changed, 520 insertions, 279 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index b6b0a5b4e..127e42164 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -37,10 +37,11 @@ then
param set MPC_LAND_SPEED 1.0
param set PE_VELNE_NOISE 0.5
- param set PE_VELNE_NOISE 0.7
+ param set PE_VELD_NOISE 0.7
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.0
+ param set NAV_ACCEPT_RAD 2.0
fi
set PWM_RATE 400
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index 76593881d..d6e638c0a 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -17,6 +17,8 @@ mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
usleep 100000
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
usleep 100000
+mavlink stream -d /dev/ttyACM0 -s GLOBAL_POSITION_SETPOINT_INT -r 20
+usleep 100000
# Exit shell to make it available to MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 87ec4293e..6d06f897a 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -65,12 +65,12 @@ then
# Start CDC/ACM serial driver
#
sercon
-
+
#
# Start the ORB (first app to start)
#
uorb start
-
+
#
# Load parameters
#
@@ -79,7 +79,7 @@ then
then
set PARAM_FILE /fs/mtd_params
fi
-
+
param select $PARAM_FILE
if param load
then
@@ -87,7 +87,7 @@ then
else
echo "[init] ERROR: Params loading failed: $PARAM_FILE"
fi
-
+
#
# Start system state indicator
#
@@ -105,7 +105,7 @@ then
if pca8574 start
then
fi
-
+
#
# Set default values
#
@@ -126,7 +126,7 @@ then
set LOAD_DEFAULT_APPS yes
set GPS yes
set GPS_FAKE no
-
+
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
#
@@ -136,7 +136,7 @@ then
else
set DO_AUTOCONFIG no
fi
-
+
#
# Set USE_IO flag
#
@@ -146,7 +146,7 @@ then
else
set USE_IO no
fi
-
+
#
# Set parameters and env variables for selected AUTOSTART
#
@@ -176,9 +176,9 @@ then
param set SYS_AUTOCONFIG 0
param save
fi
-
+
set IO_PRESENT no
-
+
if [ $USE_IO == yes ]
then
#
@@ -190,19 +190,19 @@ then
else
set IO_FILE /etc/extras/px4io-v1_default.bin
fi
-
+
if px4io checkcrc $IO_FILE
then
echo "[init] PX4IO CRC OK"
echo "PX4IO CRC OK" >> $LOG_FILE
-
+
set IO_PRESENT yes
else
echo "[init] Trying to update"
echo "PX4IO Trying to update" >> $LOG_FILE
-
+
tone_alarm MLL32CP8MB
-
+
if px4io forceupdate 14662 $IO_FILE
then
usleep 500000
@@ -211,7 +211,7 @@ then
echo "[init] PX4IO CRC OK, update successful"
echo "PX4IO CRC OK after updating" >> $LOG_FILE
tone_alarm MLL8CDE
-
+
set IO_PRESENT yes
else
echo "[init] ERROR: PX4IO update failed"
@@ -224,14 +224,14 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
if [ $IO_PRESENT == no ]
then
echo "[init] ERROR: PX4IO not found"
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
#
# Set default output if not set
#
@@ -250,7 +250,7 @@ then
# Need IO for output but it not present, disable output
set OUTPUT_MODE none
echo "[init] ERROR: PX4IO not found, disabling output"
-
+
# Avoid using ttyS0 for MAVLink on FMUv1
if ver hwcmp PX4FMU_V1
then
@@ -274,17 +274,17 @@ then
# Try to get an USB console
nshterm /dev/ttyACM0 &
-
+
#
# Start the Commander (needs to be this early for in-air-restarts)
#
commander start
-
+
#
# Start primary output
#
set TTYS1_BUSY no
-
+
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
if [ $OUTPUT_MODE != none ]
then
@@ -300,7 +300,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
then
echo "[init] Use FMU as primary output"
@@ -311,7 +311,7 @@ then
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
@@ -324,7 +324,7 @@ then
fi
fi
fi
-
+
if [ $OUTPUT_MODE == mkblctrl ]
then
echo "[init] Use MKBLCTRL as primary output"
@@ -337,7 +337,7 @@ then
then
set MKBLCTRL_ARG "-mkmode +"
fi
-
+
if mkblctrl $MKBLCTRL_ARG
then
echo "[init] MKBLCTRL started"
@@ -345,9 +345,9 @@ then
echo "[init] ERROR: MKBLCTRL start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
fi
-
+
if [ $OUTPUT_MODE == hil ]
then
echo "[init] Use HIL as primary output"
@@ -359,7 +359,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
#
# Start IO or FMU for RC PPM input if needed
#
@@ -386,7 +386,7 @@ then
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
@@ -401,7 +401,7 @@ then
fi
fi
fi
-
+
#
# MAVLink
#
@@ -422,7 +422,7 @@ then
fi
mavlink start $MAVLINK_FLAGS
-
+
#
# Sensors, Logging, GPS
#
@@ -433,7 +433,7 @@ then
echo "[init] Start logging"
sh /etc/init.d/rc.logging
fi
-
+
if [ $GPS == yes ]
then
echo "[init] Start GPS"
@@ -443,7 +443,7 @@ then
gps start -f
else
gps start
- fi
+ fi
fi
#
@@ -460,24 +460,24 @@ then
if [ $VEHICLE_TYPE == fw ]
then
echo "[init] Vehicle type: FIXED WING"
-
+
if [ $MIXER == none ]
then
# Set default mixer for fixed wing if not defined
set MIXER FMU_AERT
fi
-
+
if [ $MAV_TYPE == none ]
then
# Use MAV_TYPE = 1 (fixed wing) if not defined
set MAV_TYPE 1
fi
-
+
param set MAV_TYPE $MAV_TYPE
-
+
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
-
+
# Start standard fixedwing apps
if [ $LOAD_DEFAULT_APPS == yes ]
then
@@ -525,7 +525,7 @@ then
set MAV_TYPE 14
fi
fi
-
+
# Still no MAV_TYPE found
if [ $MAV_TYPE == none ]
then
@@ -533,10 +533,10 @@ then
else
param set MAV_TYPE $MAV_TYPE
fi
-
+
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
-
+
# Start standard multicopter apps
if [ $LOAD_DEFAULT_APPS == yes ]
then
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 4ca8b5e42..8bf76dcc3 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -880,7 +880,7 @@ LSM303D::mag_read(struct file *filp, char *buffer, size_t buflen)
/* manual measurement */
_mag_reports->flush();
- measure();
+ _mag->measure();
/* measurement will have generated a report, copy it out */
if (_mag_reports->get(mrb))
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 0a909d02f..a0a18bc2e 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -61,9 +61,9 @@ ECL_PitchController::ECL_PitchController() :
_integrator(0.0f),
_rate_error(0.0f),
_rate_setpoint(0.0f),
- _bodyrate_setpoint(0.0f)
+ _bodyrate_setpoint(0.0f),
+ _nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control pitch nonfinite input"))
{
- perf_alloc(PC_COUNT, "fw att control pitch nonfinite input");
}
ECL_PitchController::~ECL_PitchController()
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
index 82903ef5a..d2a231694 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -59,9 +59,9 @@ ECL_RollController::ECL_RollController() :
_integrator(0.0f),
_rate_error(0.0f),
_rate_setpoint(0.0f),
- _bodyrate_setpoint(0.0f)
+ _bodyrate_setpoint(0.0f),
+ _nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control roll nonfinite input"))
{
- perf_alloc(PC_COUNT, "fw att control roll nonfinite input");
}
ECL_RollController::~ECL_RollController()
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
index e53ffc644..79184e2cd 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -58,9 +58,9 @@ ECL_YawController::ECL_YawController() :
_rate_error(0.0f),
_rate_setpoint(0.0f),
_bodyrate_setpoint(0.0f),
- _coordinated_min_speed(1.0f)
+ _coordinated_min_speed(1.0f),
+ _nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control yaw nonfinite input"))
{
- perf_alloc(PC_COUNT, "fw att control yaw nonfinite input");
}
ECL_YawController::~ECL_YawController()
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 5c0628a16..65922b2a5 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1408,7 +1408,7 @@ int commander_thread_main(int argc, char *argv[])
home.alt = global_position.alt;
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
- mavlink_log_info(mavlink_fd, "#audio: home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
+ mavlink_log_info(mavlink_fd, "home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
/* announce new home position */
if (home_pub > 0) {
diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c
index aa637e207..7cae84678 100644
--- a/src/modules/fw_att_control/fw_att_control_params.c
+++ b/src/modules/fw_att_control/fw_att_control_params.c
@@ -50,149 +50,322 @@ f * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Controller parameters, accessible via MAVLink
*
*/
-// @DisplayName Attitude Time Constant
-// @Description This defines the latency between a step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed.
-// @Range 0.4 to 1.0 seconds, in tens of seconds
+
+/**
+ * Attitude Time Constant
+ *
+ * This defines the latency between a step input and the achieved setpoint
+ * (inverse to a P gain). Half a second is a good start value and fits for
+ * most average systems. Smaller systems may require smaller values, but as
+ * this will wear out servos faster, the value should only be decreased as
+ * needed.
+ *
+ * @unit seconds
+ * @min 0.4
+ * @max 1.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_ATT_TC, 0.5f);
-// @DisplayName Pitch rate proportional gain.
-// @Description This defines how much the elevator input will be commanded depending on the current body angular rate error.
-// @Range 10 to 200, 1 increments
+/**
+ * Pitch rate proportional gain.
+ *
+ * This defines how much the elevator input will be commanded depending on the
+ * current body angular rate error.
+ *
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_PR_P, 0.05f);
-// @DisplayName Pitch rate integrator gain.
-// @Description This gain defines how much control response will result out of a steady state error. It trims any constant error.
-// @Range 0 to 50.0
+/**
+ * Pitch rate integrator gain.
+ *
+ * This gain defines how much control response will result out of a steady
+ * state error. It trims any constant error.
+ *
+ * @min 0.0
+ * @max 50.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_PR_I, 0.0f);
-// @DisplayName Maximum positive / up pitch rate.
-// @Description This limits the maximum pitch up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
-// @Range 0 to 90.0 degrees per seconds, in 1 increments
+/**
+ * Maximum positive / up pitch rate.
+ *
+ * This limits the maximum pitch up angular rate the controller will output (in
+ * degrees per second). Setting a value of zero disables the limit.
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 0.0f);
-// @DisplayName Maximum negative / down pitch rate.
-// @Description This limits the maximum pitch down up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
-// @Range 0 to 90.0 degrees per seconds, in 1 increments
+/**
+ * Maximum negative / down pitch rate.
+ *
+ * This limits the maximum pitch down up angular rate the controller will
+ * output (in degrees per second). Setting a value of zero disables the limit.
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 0.0f);
-// @DisplayName Pitch rate integrator limit
-// @Description The portion of the integrator part in the control surface deflection is limited to this value
-// @Range 0.0 to 1
-// @Increment 0.1
+/**
+ * Pitch rate integrator limit
+ *
+ * The portion of the integrator part in the control surface deflection is
+ * limited to this value
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.2f);
-// @DisplayName Roll to Pitch feedforward gain.
-// @Description This compensates during turns and ensures the nose stays level.
-// @Range 0.5 2.0
-// @Increment 0.05
-// @User User
+/**
+ * Roll to Pitch feedforward gain.
+ *
+ * This compensates during turns and ensures the nose stays level.
+ *
+ * @min 0.0
+ * @max 2.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 0.0f); //xxx: set to 0 as default, see comment in ECL_PitchController::control_attitude (float turn_offset = ...)
-// @DisplayName Roll rate proportional Gain.
-// @Description This defines how much the aileron input will be commanded depending on the current body angular rate error.
-// @Range 10.0 200.0
-// @Increment 10.0
-// @User User
+/**
+ * Roll rate proportional Gain
+ *
+ * This defines how much the aileron input will be commanded depending on the
+ * current body angular rate error.
+ *
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_RR_P, 0.05f);
-// @DisplayName Roll rate integrator Gain
-// @Description This gain defines how much control response will result out of a steady state error. It trims any constant error.
-// @Range 0.0 100.0
-// @Increment 5.0
-// @User User
+/**
+ * Roll rate integrator Gain
+ *
+ * This gain defines how much control response will result out of a steady
+ * state error. It trims any constant error.
+ *
+ * @min 0.0
+ * @max 100.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_RR_I, 0.0f);
-// @DisplayName Roll Integrator Anti-Windup
-// @Description The portion of the integrator part in the control surface deflection is limited to this value.
-// @Range 0.0 to 1.0
-// @Increment 0.1
+/**
+ * Roll Integrator Anti-Windup
+ *
+ * The portion of the integrator part in the control surface deflection is limited to this value.
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_RR_IMAX, 0.2f);
-// @DisplayName Maximum Roll Rate
-// @Description This limits the maximum roll rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
-// @Range 0 to 90.0 degrees per seconds
-// @Increment 1.0
-PARAM_DEFINE_FLOAT(FW_R_RMAX, 0);
+/**
+ * Maximum Roll Rate
+ *
+ * This limits the maximum roll rate the controller will output (in degrees per
+ * second). Setting a value of zero disables the limit.
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
+PARAM_DEFINE_FLOAT(FW_R_RMAX, 0.0f);
-// @DisplayName Yaw rate proportional gain.
-// @Description This defines how much the rudder input will be commanded depending on the current body angular rate error.
-// @Range 10 to 200, 1 increments
-PARAM_DEFINE_FLOAT(FW_YR_P, 0.05);
+/**
+ * Yaw rate proportional gain
+ *
+ * This defines how much the rudder input will be commanded depending on the
+ * current body angular rate error.
+ *
+ * @group FW Attitude Control
+ */
+PARAM_DEFINE_FLOAT(FW_YR_P, 0.05f);
-// @DisplayName Yaw rate integrator gain.
-// @Description This gain defines how much control response will result out of a steady state error. It trims any constant error.
-// @Range 0 to 50.0
+/**
+ * Yaw rate integrator gain
+ *
+ * This gain defines how much control response will result out of a steady
+ * state error. It trims any constant error.
+ *
+ * @min 0.0
+ * @max 50.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_YR_I, 0.0f);
-// @DisplayName Yaw rate integrator limit
-// @Description The portion of the integrator part in the control surface deflection is limited to this value
-// @Range 0.0 to 1
-// @Increment 0.1
+/**
+ * Yaw rate integrator limit
+ *
+ * The portion of the integrator part in the control surface deflection is
+ * limited to this value
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_YR_IMAX, 0.2f);
-// @DisplayName Maximum Yaw Rate
-// @Description This limits the maximum yaw rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
-// @Range 0 to 90.0 degrees per seconds
-// @Increment 1.0
-PARAM_DEFINE_FLOAT(FW_Y_RMAX, 0);
+/**
+ * Maximum Yaw Rate
+ *
+ * This limits the maximum yaw rate the controller will output (in degrees per
+ * second). Setting a value of zero disables the limit.
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
+PARAM_DEFINE_FLOAT(FW_Y_RMAX, 0.0f);
-// @DisplayName Roll rate feed forward
-// @Description Direct feed forward from rate setpoint to control surface output
-// @Range 0 to 10
-// @Increment 0.1
+/**
+ * Roll rate feed forward
+ *
+ * Direct feed forward from rate setpoint to control surface output
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_RR_FF, 0.3f);
-// @DisplayName Pitch rate feed forward
-// @Description Direct feed forward from rate setpoint to control surface output
-// @Range 0 to 10
-// @Increment 0.1
+/**
+ * Pitch rate feed forward
+ *
+ * Direct feed forward from rate setpoint to control surface output
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_PR_FF, 0.4f);
-// @DisplayName Yaw rate feed forward
-// @Description Direct feed forward from rate setpoint to control surface output
-// @Range 0 to 10
-// @Increment 0.1
+/**
+ * Yaw rate feed forward
+ *
+ * Direct feed forward from rate setpoint to control surface output
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_YR_FF, 0.3f);
-// @DisplayName Minimal speed for yaw coordination
-// @Description For airspeeds above this value the yaw rate is calculated for a coordinated turn. Set to a very high value to disable.
-// @Range 0 to 90.0 degrees per seconds
-// @Increment 1.0
+/**
+ * Minimal speed for yaw coordination
+ *
+ * For airspeeds above this value, the yaw rate is calculated for a coordinated
+ * turn. Set to a very high value to disable.
+ *
+ * @unit m/s
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_YCO_VMIN, 1000.0f);
-/* Airspeed parameters: the following parameters about airspeed are used by the attitude and the positon controller */
+/* Airspeed parameters:
+ * The following parameters about airspeed are used by the attitude and the
+ * position controller.
+ * */
-// @DisplayName Minimum Airspeed
-// @Description If the airspeed falls below this value the TECS controller will try to increase airspeed more aggressively
-// @Range 0.0 to 30
+/**
+ * Minimum Airspeed
+ *
+ * If the airspeed falls below this value, the TECS controller will try to
+ * increase airspeed more aggressively.
+ *
+ * @unit m/s
+ * @min 0.0
+ * @max 30.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 13.0f);
-// @DisplayName Trim Airspeed
-// @Description The TECS controller tries to fly at this airspeed
-// @Range 0.0 to 30
+/**
+ * Trim Airspeed
+ *
+ * The TECS controller tries to fly at this airspeed.
+ *
+ * @unit m/s
+ * @min 0.0
+ * @max 30.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 20.0f);
-// @DisplayName Maximum Airspeed
-// @Description If the airspeed is above this value the TECS controller will try to decrease airspeed more aggressively
-// @Range 0.0 to 30
+/**
+ * Maximum Airspeed
+ *
+ * If the airspeed is above this value, the TECS controller will try to decrease
+ * airspeed more aggressively.
+ *
+ * @unit m/s
+ * @min 0.0
+ * @max 30.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 50.0f);
-// @DisplayName Roll Setpoint Offset
-// @Description An airframe specific offset of the roll setpoint in degrees, the value is added to the roll setpoint and should correspond to the typical cruise speed of the airframe
-// @Range -90.0 to 90.0
+/**
+ * Roll Setpoint Offset
+ *
+ * An airframe specific offset of the roll setpoint in degrees, the value is
+ * added to the roll setpoint and should correspond to the typical cruise speed
+ * of the airframe.
+ *
+ * @unit deg
+ * @min -90.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_RSP_OFF, 0.0f);
-// @DisplayName Pitch Setpoint Offset
-// @Description An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the typical cruise speed of the airframe
-// @Range -90.0 to 90.0
+/**
+ * Pitch Setpoint Offset
+ *
+ * An airframe specific offset of the pitch setpoint in degrees, the value is
+ * added to the pitch setpoint and should correspond to the typical cruise
+ * speed of the airframe.
+ *
+ * @unit deg
+ * @min -90.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_PSP_OFF, 0.0f);
-// @DisplayName Max Manual Roll
-// @Description Max roll for manual control in attitude stabilized mode
-// @Range 0.0 to 90.0
+/**
+ * Max Manual Roll
+ *
+ * Max roll for manual control in attitude stabilized mode
+ *
+ * @unit deg
+ * @min 0.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_MAN_R_MAX, 45.0f);
-// @DisplayName Max Manual Pitch
-// @Description Max pitch for manual control in attitude stabilized mode
-// @Range 0.0 to 90.0
+/**
+ * Max Manual Pitch
+ *
+ * Max pitch for manual control in attitude stabilized mode
+ *
+ * @unit deg
+ * @min 0.0
+ * @max 90.0
+ * @group FW Attitude Control
+ */
PARAM_DEFINE_FLOAT(FW_MAN_P_MAX, 45.0f);
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 5b877cd77..116d3cc63 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -232,8 +232,6 @@ private:
float throttle_land_max;
- float loiter_hold_radius;
-
float heightrate_p;
float speedrate_p;
@@ -277,8 +275,6 @@ private:
param_t throttle_land_max;
- param_t loiter_hold_radius;
-
param_t heightrate_p;
param_t speedrate_p;
@@ -441,7 +437,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.l1_period = param_find("FW_L1_PERIOD");
_parameter_handles.l1_damping = param_find("FW_L1_DAMPING");
- _parameter_handles.loiter_hold_radius = param_find("FW_LOITER_R");
_parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
_parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
@@ -513,7 +508,6 @@ FixedwingPositionControl::parameters_update()
/* L1 control parameters */
param_get(_parameter_handles.l1_damping, &(_parameters.l1_damping));
param_get(_parameter_handles.l1_period, &(_parameters.l1_period));
- param_get(_parameter_handles.loiter_hold_radius, &(_parameters.loiter_hold_radius));
param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index f258f77da..52128e1b7 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -72,17 +72,6 @@ PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 25.0f);
PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
/**
- * Default Loiter Radius
- *
- * This radius is used when no other loiter radius is set.
- *
- * @min 10.0
- * @max 100.0
- * @group L1 Control
- */
-PARAM_DEFINE_FLOAT(FW_LOITER_R, 50.0f);
-
-/**
* Cruise throttle
*
* This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7.
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index bb1ad86ef..e300be074 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -105,7 +105,8 @@ static struct file_operations fops;
*/
extern "C" __EXPORT int mavlink_main(int argc, char *argv[]);
-static uint64_t last_write_times[6] = {0};
+static uint64_t last_write_success_times[6] = {0};
+static uint64_t last_write_try_times[6] = {0};
/*
* Internal function to send the bytes through the right serial port
@@ -166,38 +167,40 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
if (instance->get_flow_control_enabled()
&& ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) {
- if (buf_free == 0) {
-
- if (last_write_times[(unsigned)channel] != 0 &&
- hrt_elapsed_time(&last_write_times[(unsigned)channel]) > 500 * 1000UL) {
-
- warnx("DISABLING HARDWARE FLOW CONTROL");
- instance->enable_flow_control(false);
- }
-
- } else {
-
- /* apparently there is space left, although we might be
- * partially overflooding the buffer already */
- last_write_times[(unsigned)channel] = hrt_absolute_time();
+ /* Disable hardware flow control:
+ * if no successful write since a defined time
+ * and if the last try was not the last successful write
+ */
+ if (last_write_try_times[(unsigned)channel] != 0 &&
+ hrt_elapsed_time(&last_write_success_times[(unsigned)channel]) > 500 * 1000UL &&
+ last_write_success_times[(unsigned)channel] !=
+ last_write_try_times[(unsigned)channel])
+ {
+ warnx("DISABLING HARDWARE FLOW CONTROL");
+ instance->enable_flow_control(false);
}
+
}
/* If the wait until transmit flag is on, only transmit after we've received messages.
Otherwise, transmit all the time. */
if (instance->should_transmit()) {
+ last_write_try_times[(unsigned)channel] = hrt_absolute_time();
/* check if there is space in the buffer, let it overflow else */
if (!ioctl(uart, FIONWRITE, (unsigned long)&buf_free)) {
- if (desired > buf_free) {
- desired = buf_free;
+ if (buf_free < desired) {
+ /* we don't want to send anything just in half, so return */
+ return;
}
}
ssize_t ret = write(uart, ch, desired);
if (ret != desired) {
warnx("TX FAIL");
+ } else {
+ last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel];
}
}
@@ -222,6 +225,8 @@ Mavlink::Mavlink() :
_subscriptions(nullptr),
_streams(nullptr),
_mission_pub(-1),
+ _mode(MAVLINK_MODE_NORMAL),
+ _total_counter(0),
_verbose(false),
_forwarding_on(false),
_passing_on(false),
@@ -785,9 +790,14 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav
{
switch (msg->msgid) {
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
- /* Start sending parameters */
- mavlink_pm_start_queued_send();
- mavlink_missionlib_send_gcs_string("[mavlink pm] sending list");
+ mavlink_param_request_list_t req;
+ mavlink_msg_param_request_list_decode(msg, &req);
+ if (req.target_system == mavlink_system.sysid &&
+ (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) {
+ /* Start sending parameters */
+ mavlink_pm_start_queued_send();
+ mavlink_missionlib_send_gcs_string("[mavlink pm] sending list");
+ }
} break;
case MAVLINK_MSG_ID_PARAM_SET: {
@@ -891,6 +901,7 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
default:
mission_item->acceptance_radius = mavlink_mission_item->param2;
+ mission_item->time_inside = mavlink_mission_item->param1;
break;
}
@@ -899,7 +910,6 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
- mission_item->time_inside = mavlink_mission_item->param1;
mission_item->autocontinue = mavlink_mission_item->autocontinue;
// mission_item->index = mavlink_mission_item->seq;
mission_item->origin = ORIGIN_MAVLINK;
@@ -918,11 +928,12 @@ int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_
switch (mission_item->nav_cmd) {
case NAV_CMD_TAKEOFF:
- mavlink_mission_item->param2 = mission_item->pitch_min;
+ mavlink_mission_item->param1 = mission_item->pitch_min;
break;
default:
mavlink_mission_item->param2 = mission_item->acceptance_radius;
+ mavlink_mission_item->param1 = mission_item->time_inside;
break;
}
@@ -933,7 +944,6 @@ int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_
mavlink_mission_item->param4 = mission_item->yaw * M_RAD_TO_DEG_F;
mavlink_mission_item->param3 = mission_item->loiter_radius * (float)mission_item->loiter_direction;
mavlink_mission_item->command = mission_item->nav_cmd;
- mavlink_mission_item->param1 = mission_item->time_inside;
mavlink_mission_item->autocontinue = mission_item->autocontinue;
// mavlink_mission_item->seq = mission_item->index;
@@ -949,6 +959,7 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state)
state->current_partner_compid = 0;
state->timestamp_lastaction = 0;
state->timestamp_last_send_setpoint = 0;
+ state->timestamp_last_send_request = 0;
state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT;
state->current_dataman_id = 0;
}
@@ -1049,6 +1060,7 @@ void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t
} else {
mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
+ mavlink_missionlib_send_gcs_string("#audio: Unable to read from micro SD");
if (_verbose) { warnx("ERROR: could not read WP%u", seq); }
}
@@ -1064,6 +1076,7 @@ void Mavlink::mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, u
wpr.seq = seq;
mavlink_msg_mission_request_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpr);
mavlink_missionlib_send_message(&msg);
+ _wpm->timestamp_last_send_request = hrt_absolute_time();
if (_verbose) { warnx("Sent waypoint request %u to ID %u", wpr.seq, wpr.target_system); }
@@ -1106,6 +1119,10 @@ void Mavlink::mavlink_waypoint_eventloop(uint64_t now)
_wpm->current_state = MAVLINK_WPM_STATE_IDLE;
_wpm->current_partner_sysid = 0;
_wpm->current_partner_compid = 0;
+
+ } else if (now - _wpm->timestamp_last_send_request > 500000 && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
+ /* try to get WP again after short timeout */
+ mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
}
}
@@ -1168,11 +1185,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
if (_verbose) { warnx("IGN WP CURR CMD: Busy"); }
}
-
- } else {
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
-
- if (_verbose) { warnx("REJ. WP CMD: target id mismatch"); }
}
break;
@@ -1205,11 +1217,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
if (_verbose) { warnx("IGN REQUEST LIST: Busy"); }
}
-
- } else {
- mavlink_missionlib_send_gcs_string("REJ. REQUEST LIST: target id mismatch");
-
- if (_verbose) { warnx("REJ. REQUEST LIST: target id mismatch"); }
}
break;
@@ -1298,12 +1305,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.", msg->sysid, _wpm->current_partner_sysid); }
-
- } else {
-
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
-
- if (_verbose) { warnx("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); }
}
}
@@ -1362,12 +1363,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
if (_verbose) { warnx("IGN MISSION_COUNT CMD: Busy"); }
}
-
- } else {
-
- mavlink_missionlib_send_gcs_string("REJ. WP COUNT CMD: target id mismatch");
-
- if (_verbose) { warnx("IGNORED WAYPOINT COUNT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); }
}
}
break;
@@ -1435,6 +1430,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
if (dm_write(dm_next, wp.seq, DM_PERSIST_IN_FLIGHT_RESET, &mission_item, len) != len) {
mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
+ mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD");
_wpm->current_state = MAVLINK_WPM_STATE_IDLE;
break;
}
@@ -1466,11 +1462,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
} else {
mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
}
-
- } else {
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
-
- if (_verbose) { warnx("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); }
}
break;
@@ -1506,13 +1497,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
if (_verbose) { warnx("IGN WP CLEAR CMD: Busy"); }
}
-
-
- } else if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && _wpm->current_state != MAVLINK_WPM_STATE_IDLE) {
-
- mavlink_missionlib_send_gcs_string("REJ. WP CLERR CMD: target id mismatch");
-
- if (_verbose) { warnx("IGNORED WAYPOINT CLEAR COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); }
}
break;
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 25c0da820..40edc4b85 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -93,6 +93,7 @@ struct mavlink_wpm_storage {
uint8_t current_partner_compid;
uint64_t timestamp_lastaction;
uint64_t timestamp_last_send_setpoint;
+ uint64_t timestamp_last_send_request;
uint32_t timeout;
int current_dataman_id;
};
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 146e2d4b8..0ceee32a1 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -274,7 +274,7 @@ protected:
status->onboard_control_sensors_health,
status->load * 1000.0f,
status->battery_voltage * 1000.0f,
- status->battery_current * 1000.0f,
+ status->battery_current * 100.0f,
status->battery_remaining * 100.0f,
status->drop_rate_comm,
status->errors_comm,
@@ -938,14 +938,14 @@ protected:
void send(const hrt_abstime t)
{
- if (pos_sp_triplet_sub->update(t)) {
- mavlink_msg_global_position_setpoint_int_send(_channel,
- MAV_FRAME_GLOBAL,
- (int32_t)(pos_sp_triplet->current.lat * 1e7),
- (int32_t)(pos_sp_triplet->current.lon * 1e7),
- (int32_t)(pos_sp_triplet->current.alt * 1000),
- (int16_t)(pos_sp_triplet->current.yaw * M_RAD_TO_DEG_F * 100.0f));
- }
+ /* always send this message, even if it has not been updated */
+ pos_sp_triplet_sub->update(t);
+ mavlink_msg_global_position_setpoint_int_send(_channel,
+ MAV_FRAME_GLOBAL,
+ (int32_t)(pos_sp_triplet->current.lat * 1e7),
+ (int32_t)(pos_sp_triplet->current.lon * 1e7),
+ (int32_t)(pos_sp_triplet->current.alt * 1000),
+ (int16_t)(pos_sp_triplet->current.yaw * M_RAD_TO_DEG_F * 100.0f));
}
};
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 401d50f7e..06e0c5904 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1458,7 +1458,6 @@ Navigator::check_mission_item_reached()
/* XXX TODO count turns */
if ((_mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
_mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED) &&
_mission_item.loiter_radius > 0.01f) {
@@ -1477,27 +1476,27 @@ Navigator::check_mission_item_reached()
acceptance_radius = _parameters.acceptance_radius;
}
- float dist = -1.0f;
- float dist_xy = -1.0f;
- float dist_z = -1.0f;
-
- /* calculate AMSL altitude for this waypoint */
- float wp_alt_amsl = _mission_item.altitude;
-
- if (_mission_item.altitude_is_relative)
- wp_alt_amsl += _home_pos.alt;
-
- dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, wp_alt_amsl,
- (double)_global_pos.lat, (double)_global_pos.lon, _global_pos.alt,
- &dist_xy, &dist_z);
-
if (_do_takeoff) {
- if (_global_pos.alt > wp_alt_amsl - acceptance_radius) {
- /* require only altitude for takeoff */
+ /* require only altitude for takeoff */
+ if (_global_pos.alt > _pos_sp_triplet.current.alt - acceptance_radius) {
_waypoint_position_reached = true;
}
} else {
+ float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
+ /* calculate AMSL altitude for this waypoint */
+ float wp_alt_amsl = _mission_item.altitude;
+
+ if (_mission_item.altitude_is_relative)
+ wp_alt_amsl += _home_pos.alt;
+
+ dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, wp_alt_amsl,
+ (double)_global_pos.lat, (double)_global_pos.lon, _global_pos.alt,
+ &dist_xy, &dist_z);
+
if (dist >= 0.0f && dist <= acceptance_radius) {
_waypoint_position_reached = true;
}
@@ -1567,7 +1566,14 @@ Navigator::on_mission_item_reached()
}
if (_mission.current_mission_available()) {
- set_mission_item();
+ if (_mission_item.autocontinue) {
+ /* continue mission */
+ set_mission_item();
+
+ } else {
+ /* autocontinue disabled for this item */
+ request_loiter_or_ready();
+ }
} else {
/* if no more mission items available then finish mission */
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index d7503e42d..f908d7a3b 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -71,19 +71,20 @@
#include "inertial_filter.h"
#define MIN_VALID_W 0.00001f
+#define PUB_INTERVAL 10000 // limit publish rate to 100 Hz
+#define EST_BUF_SIZE 250000 / PUB_INTERVAL // buffer size is 0.5s
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int position_estimator_inav_task; /**< Handle of deamon task / thread */
static bool verbose_mode = false;
-static const hrt_abstime gps_topic_timeout = 1000000; // GPS topic timeout = 1s
+static const hrt_abstime gps_topic_timeout = 500000; // GPS topic timeout = 0.5s
static const hrt_abstime flow_topic_timeout = 1000000; // optical flow topic timeout = 1s
static const hrt_abstime sonar_timeout = 150000; // sonar timeout = 150ms
static const hrt_abstime sonar_valid_timeout = 1000000; // estimate sonar distance during this time after sonar loss
static const hrt_abstime xy_src_timeout = 2000000; // estimate position during this time after position sources loss
static const uint32_t updates_counter_len = 1000000;
-static const uint32_t pub_interval = 10000; // limit publish rate to 100 Hz
static const float max_flow = 1.0f; // max flow value that can be used, rad/s
__EXPORT int position_estimator_inav_main(int argc, char *argv[]);
@@ -92,6 +93,16 @@ int position_estimator_inav_thread_main(int argc, char *argv[]);
static void usage(const char *reason);
+static inline int min(int val1, int val2)
+{
+ return (val1 < val2) ? val1 : val2;
+}
+
+static inline int max(int val1, int val2)
+{
+ return (val1 > val2) ? val1 : val2;
+}
+
/**
* Print the correct usage.
*/
@@ -135,7 +146,7 @@ int position_estimator_inav_main(int argc, char *argv[])
thread_should_exit = false;
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
- SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4000,
+ SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 5000,
position_estimator_inav_thread_main,
(argv) ? (const char **) &argv[2] : (const char **) NULL);
exit(0);
@@ -199,8 +210,21 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float y_est[2] = { 0.0f, 0.0f }; // pos, vel
float z_est[2] = { 0.0f, 0.0f }; // pos, vel
- float eph = 1.0;
- float epv = 1.0;
+ float est_buf[EST_BUF_SIZE][3][2]; // estimated position buffer
+ float R_buf[EST_BUF_SIZE][3][3]; // rotation matrix buffer
+ float R_gps[3][3]; // rotation matrix for GPS correction moment
+ memset(est_buf, 0, sizeof(est_buf));
+ memset(R_buf, 0, sizeof(R_buf));
+ memset(R_gps, 0, sizeof(R_gps));
+ int buf_ptr = 0;
+
+ static const float min_eph_epv = 2.0f; // min EPH/EPV, used for weight calculation
+ static const float max_eph_epv = 20.0f; // max EPH/EPV acceptable for estimation
+
+ float eph = max_eph_epv;
+ float epv = 1.0f;
+
+ float eph_flow = 1.0f;
float x_est_prev[2], y_est_prev[2], z_est_prev[2];
memset(x_est_prev, 0, sizeof(x_est_prev));
@@ -257,9 +281,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float corr_flow[] = { 0.0f, 0.0f }; // N E
float w_flow = 0.0f;
- static float min_eph_epv = 2.0f; // min EPH/EPV, used for weight calculation
- static float max_eph_epv = 10.0f; // max EPH/EPV acceptable for estimation
-
float sonar_prev = 0.0f;
hrt_abstime flow_prev = 0; // time of last flow measurement
hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered)
@@ -536,9 +557,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
w_flow *= 0.05f;
}
- flow_valid = true;
+ /* under ideal conditions, on 1m distance assume EPH = 10cm */
+ eph_flow = 0.1 / w_flow;
- eph = fminf(eph, 0.1 / att.R[2][2] / flow_q * fmaxf(1.0f, flow_dist)); // under ideal conditions, on 1m distance assume EPH = 10cm
+ flow_valid = true;
} else {
w_flow = 0.0f;
@@ -597,13 +619,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* hysteresis for GPS quality */
if (gps_valid) {
- if (gps.eph_m > max_eph_epv * 1.5f || gps.epv_m > max_eph_epv * 1.5f || gps.fix_type < 3) {
+ if (gps.eph_m > max_eph_epv || gps.epv_m > max_eph_epv || gps.fix_type < 3) {
gps_valid = false;
mavlink_log_info(mavlink_fd, "[inav] GPS signal lost");
}
} else {
- if (gps.eph_m < max_eph_epv && gps.epv_m < max_eph_epv && gps.fix_type >= 3) {
+ if (gps.eph_m < max_eph_epv * 0.7f && gps.epv_m < max_eph_epv * 0.7f && gps.fix_type >= 3) {
gps_valid = true;
reset_est = true;
mavlink_log_info(mavlink_fd, "[inav] GPS signal found");
@@ -657,16 +679,22 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
y_est[1] = gps.vel_e_m_s;
}
+ /* calculate index of estimated values in buffer */
+ int est_i = buf_ptr - 1 - min(EST_BUF_SIZE - 1, max(0, (int)(params.delay_gps * 1000000.0f / PUB_INTERVAL)));
+ if (est_i < 0) {
+ est_i += EST_BUF_SIZE;
+ }
+
/* calculate correction for position */
- corr_gps[0][0] = gps_proj[0] - x_est[0];
- corr_gps[1][0] = gps_proj[1] - y_est[0];
- corr_gps[2][0] = local_pos.ref_alt - alt - z_est[0];
+ corr_gps[0][0] = gps_proj[0] - est_buf[est_i][0][0];
+ corr_gps[1][0] = gps_proj[1] - est_buf[est_i][1][0];
+ corr_gps[2][0] = local_pos.ref_alt - alt - est_buf[est_i][2][0];
/* calculate correction for velocity */
if (gps.vel_ned_valid) {
- corr_gps[0][1] = gps.vel_n_m_s - x_est[1];
- corr_gps[1][1] = gps.vel_e_m_s - y_est[1];
- corr_gps[2][1] = gps.vel_d_m_s - z_est[1];
+ corr_gps[0][1] = gps.vel_n_m_s - est_buf[est_i][0][1];
+ corr_gps[1][1] = gps.vel_e_m_s - est_buf[est_i][1][1];
+ corr_gps[2][1] = gps.vel_d_m_s - est_buf[est_i][2][1];
} else {
corr_gps[0][1] = 0.0f;
@@ -674,8 +702,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
corr_gps[2][1] = 0.0f;
}
- eph = fminf(eph, gps.eph_m);
- epv = fminf(epv, gps.epv_m);
+ /* save rotation matrix at this moment */
+ memcpy(R_gps, R_buf[est_i], sizeof(R_gps));
w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, gps.eph_m);
w_gps_z = min_eph_epv / fmaxf(min_eph_epv, gps.epv_m);
@@ -717,8 +745,12 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
t_prev = t;
/* increase EPH/EPV on each step */
- eph *= 1.0 + dt;
- epv += 0.005 * dt; // add 1m to EPV each 200s (baro drift)
+ if (eph < max_eph_epv) {
+ eph *= 1.0 + dt;
+ }
+ if (epv < max_eph_epv) {
+ epv += 0.005 * dt; // add 1m to EPV each 200s (baro drift)
+ }
/* use GPS if it's valid and reference position initialized */
bool use_gps_xy = ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W;
@@ -731,7 +763,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
xy_src_time = t;
}
- bool can_estimate_xy = eph < max_eph_epv * 1.5;
+ bool can_estimate_xy = (eph < max_eph_epv) || use_gps_xy || use_flow;
bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
@@ -763,7 +795,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
corr_baro += offs_corr;
}
- /* accelerometer bias correction */
+ /* accelerometer bias correction for GPS (use buffered rotation matrix) */
float accel_bias_corr[3] = { 0.0f, 0.0f, 0.0f };
if (use_gps_xy) {
@@ -777,6 +809,24 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
accel_bias_corr[2] -= corr_gps[2][0] * w_z_gps_p * w_z_gps_p;
}
+ /* transform error vector from NED frame to body frame */
+ for (int i = 0; i < 3; i++) {
+ float c = 0.0f;
+
+ for (int j = 0; j < 3; j++) {
+ c += R_gps[j][i] * accel_bias_corr[j];
+ }
+
+ if (isfinite(c)) {
+ acc_bias[i] += c * params.w_acc_bias * dt;
+ }
+ }
+
+ /* accelerometer bias correction for flow and baro (assume that there is no delay) */
+ accel_bias_corr[0] = 0.0f;
+ accel_bias_corr[1] = 0.0f;
+ accel_bias_corr[2] = 0.0f;
+
if (use_flow) {
accel_bias_corr[0] -= corr_flow[0] * params.w_xy_flow;
accel_bias_corr[1] -= corr_flow[1] * params.w_xy_flow;
@@ -807,7 +857,12 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* inertial filter correction for altitude */
inertial_filter_correct(corr_baro, dt, z_est, 0, params.w_z_baro);
- inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
+
+ if (use_gps_z) {
+ epv = fminf(epv, gps.epv_m);
+
+ inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
+ }
if (!(isfinite(z_est[0]) && isfinite(z_est[1]))) {
write_debug_log("BAD ESTIMATE AFTER Z CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
@@ -832,11 +887,15 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* inertial filter correction for position */
if (use_flow) {
+ eph = fminf(eph, eph_flow);
+
inertial_filter_correct(corr_flow[0], dt, x_est, 1, params.w_xy_flow * w_flow);
inertial_filter_correct(corr_flow[1], dt, y_est, 1, params.w_xy_flow * w_flow);
}
if (use_gps_xy) {
+ eph = fminf(eph, gps.eph_m);
+
inertial_filter_correct(corr_gps[0][0], dt, x_est, 0, w_xy_gps_p);
inertial_filter_correct(corr_gps[1][0], dt, y_est, 0, w_xy_gps_p);
@@ -910,8 +969,25 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
- if (t > pub_last + pub_interval) {
+ if (t > pub_last + PUB_INTERVAL) {
pub_last = t;
+
+ /* push current estimate to buffer */
+ est_buf[buf_ptr][0][0] = x_est[0];
+ est_buf[buf_ptr][0][1] = x_est[1];
+ est_buf[buf_ptr][1][0] = y_est[0];
+ est_buf[buf_ptr][1][1] = y_est[1];
+ est_buf[buf_ptr][2][0] = z_est[0];
+ est_buf[buf_ptr][2][1] = z_est[1];
+
+ /* push current rotation matrix to buffer */
+ memcpy(R_buf[buf_ptr], att.R, sizeof(att.R));
+
+ buf_ptr++;
+ if (buf_ptr >= EST_BUF_SIZE) {
+ buf_ptr = 0;
+ }
+
/* publish local position */
local_pos.xy_valid = can_estimate_xy;
local_pos.v_xy_valid = can_estimate_xy;
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index 8aa08b6f2..d88419c25 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -55,6 +55,7 @@ PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f);
+PARAM_DEFINE_FLOAT(INAV_DELAY_GPS, 0.2f);
int parameters_init(struct position_estimator_inav_param_handles *h)
{
@@ -73,6 +74,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
h->land_t = param_find("INAV_LAND_T");
h->land_disp = param_find("INAV_LAND_DISP");
h->land_thr = param_find("INAV_LAND_THR");
+ h->delay_gps = param_find("INAV_DELAY_GPS");
return OK;
}
@@ -94,6 +96,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
param_get(h->land_t, &(p->land_t));
param_get(h->land_disp, &(p->land_disp));
param_get(h->land_thr, &(p->land_thr));
+ param_get(h->delay_gps, &(p->delay_gps));
return OK;
}
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index 08ec996a1..df1cfaa71 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -56,6 +56,7 @@ struct position_estimator_inav_params {
float land_t;
float land_disp;
float land_thr;
+ float delay_gps;
};
struct position_estimator_inav_param_handles {
@@ -74,6 +75,7 @@ struct position_estimator_inav_param_handles {
param_t land_t;
param_t land_disp;
param_t land_thr;
+ param_t delay_gps;
};
/**
diff --git a/src/modules/uORB/topics/actuator_armed.h b/src/modules/uORB/topics/actuator_armed.h
index 6e944ffee..a98d3fc3a 100644
--- a/src/modules/uORB/topics/actuator_armed.h
+++ b/src/modules/uORB/topics/actuator_armed.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -44,15 +44,25 @@
#include <stdint.h>
#include "../uORB.h"
+/**
+ * @addtogroup topics
+ * @{
+ */
+
/** global 'actuator output is live' control. */
struct actuator_armed_s {
- uint64_t timestamp;
- bool armed; /**< Set to true if system is armed */
- bool ready_to_arm; /**< Set to true if system is ready to be armed */
- bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
+ uint64_t timestamp; /**< Microseconds since system boot */
+ bool armed; /**< Set to true if system is armed */
+ bool ready_to_arm; /**< Set to true if system is ready to be armed */
+ bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
};
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
ORB_DECLARE(actuator_armed);
#endif \ No newline at end of file