mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Merge branch 'beta' into acro2
This commit is contained in:
commit
dfd4dc3e6a
@ -2,7 +2,7 @@
|
||||
#
|
||||
# HILStar / X-Plane
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
echo "HIL Rascal 110 starting.."
|
||||
@ -26,17 +26,12 @@ then
|
||||
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
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Team Blacksheep Discovery Quadcopter
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# 3DR Iris Quadcopter
|
||||
#
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# HIL Quadcopter X
|
||||
#
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
@ -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
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# HIL Quadcopter +
|
||||
#
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/1001_rc_quad_x.hil
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# HIL Rascal 110 (Flightgear)
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
# Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "HIL Rascal 110 starting.."
|
||||
@ -34,9 +34,6 @@ then
|
||||
param set FW_L1_PERIOD 16
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
set HIL yes
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# HIL Malolo 1 (Flightgear)
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
# Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "HIL Malolo 1 starting.."
|
||||
@ -49,6 +49,9 @@ then
|
||||
param set FW_YR_IMAX 0.2
|
||||
param set FW_YR_P 0.0
|
||||
param set FW_Y_RMAX 0
|
||||
param set NAV_LAND_ALT 90
|
||||
param set NAV_RTL_ALT 100
|
||||
param set NAV_RTL_LAND_T -1
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Generic 10” Octo coaxial geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
# Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/8001_octo_x
|
||||
|
||||
@ -1,10 +1,5 @@
|
||||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
@ -1,10 +1,5 @@
|
||||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
@ -23,8 +18,6 @@ then
|
||||
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
|
||||
|
||||
@ -1,7 +1,5 @@
|
||||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
@ -26,7 +24,7 @@ then
|
||||
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_MAX 1.0
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Phantom FPV Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# 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>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Wing Wing (aka Z-84) Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# FX-79 Buffalo Flying Wing
|
||||
#
|
||||
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Generic 10” Quad X geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# DJI Flame Wheel F330 Quadcopter
|
||||
#
|
||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# DJI Flame Wheel F450 Quadcopter
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
|
||||
@ -2,48 +2,10 @@
|
||||
#
|
||||
# HobbyKing X550 Quadcopter
|
||||
#
|
||||
# Maintainers: Todd Stellanova <tstellanova@gmail.com>
|
||||
# Todd Stellanova <tstellanova@gmail.com>
|
||||
#
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set MC_ROLL_P 5.5
|
||||
param set MC_ROLLRATE_P 0.14
|
||||
param set MC_ROLLRATE_I 0
|
||||
param set MC_ROLLRATE_D 0.006
|
||||
param set MC_PITCH_P 5.5
|
||||
param set MC_PITCHRATE_P 0.14
|
||||
param set MC_PITCHRATE_I 0
|
||||
param set MC_PITCHRATE_D 0.006
|
||||
param set MC_YAW_P 0.6
|
||||
param set MC_YAWRATE_P 0.08
|
||||
param set MC_YAWRATE_I 0
|
||||
param set MC_YAWRATE_D 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_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 VEHICLE_TYPE mc
|
||||
set MIXER FMU_quad_x
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Generic 10” Quad + geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Generic 10” Hexa X geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Generic 10” Hexa + geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/6001_hexa_x
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Generic 10” Octo X geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#
|
||||
# Generic 10” Octo + geometry
|
||||
#
|
||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/8001_octo_x
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -4,7 +4,6 @@
|
||||
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
#
|
||||
px4io recovery
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
@ -3,10 +3,6 @@
|
||||
# Standard startup script for PX4FMU onboard sensor drivers.
|
||||
#
|
||||
|
||||
#
|
||||
# Start sensor drivers here.
|
||||
#
|
||||
|
||||
ms5611 start
|
||||
adc start
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
|
||||
@ -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
|
||||
--------
|
||||
|
||||
@ -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
|
||||
|
||||
@ -83,14 +83,10 @@ bool LaunchDetector::getLaunchDetected()
|
||||
|
||||
void LaunchDetector::updateParams() {
|
||||
|
||||
warnx(" LaunchDetector::updateParams()");
|
||||
launchdetection_on.update();
|
||||
throttlePreTakeoff.update();
|
||||
|
||||
for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
|
||||
launchMethods[i]->updateParams();
|
||||
warnx("updating component %d", i);
|
||||
}
|
||||
|
||||
warnx(" LaunchDetector::updateParams() ended");
|
||||
}
|
||||
|
||||
@ -210,7 +210,7 @@ transition_result_t set_main_state_rc(struct vehicle_status_s *status);
|
||||
|
||||
void set_control_mode();
|
||||
|
||||
void print_reject_mode(const char *msg);
|
||||
void print_reject_mode(struct vehicle_status_s *current_status, const char *msg);
|
||||
|
||||
void print_reject_arm(const char *msg);
|
||||
|
||||
@ -658,6 +658,8 @@ int commander_thread_main(int argc, char *argv[])
|
||||
/* vehicle status topic */
|
||||
memset(&status, 0, sizeof(status));
|
||||
status.condition_landed = true; // initialize to safe value
|
||||
// We want to accept RC inputs as default
|
||||
status.rc_input_blocked = false;
|
||||
status.main_state = MAIN_STATE_MANUAL;
|
||||
status.set_nav_state = NAV_STATE_NONE;
|
||||
status.set_nav_state_timestamp = 0;
|
||||
@ -927,10 +929,12 @@ int commander_thread_main(int argc, char *argv[])
|
||||
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid, &(status.condition_local_position_valid), &status_changed);
|
||||
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
|
||||
|
||||
static bool published_condition_landed_fw = false;
|
||||
if (status.is_rotary_wing && status.condition_local_altitude_valid) {
|
||||
if (status.condition_landed != local_position.landed) {
|
||||
status.condition_landed = local_position.landed;
|
||||
status_changed = true;
|
||||
published_condition_landed_fw = false; //make sure condition_landed is published again if the system type changes
|
||||
|
||||
if (status.condition_landed) {
|
||||
mavlink_log_critical(mavlink_fd, "#audio: LANDED");
|
||||
@ -939,6 +943,12 @@ int commander_thread_main(int argc, char *argv[])
|
||||
mavlink_log_critical(mavlink_fd, "#audio: IN AIR");
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (!published_condition_landed_fw) {
|
||||
status.condition_landed = false; // Fixedwing does not have a landing detector currently
|
||||
published_condition_landed_fw = true;
|
||||
status_changed = true;
|
||||
}
|
||||
}
|
||||
|
||||
/* update battery status */
|
||||
@ -1097,7 +1107,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
/* start RC input check */
|
||||
if (sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
|
||||
if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
|
||||
/* handle the case where RC signal was regained */
|
||||
if (!status.rc_signal_found_once) {
|
||||
status.rc_signal_found_once = true;
|
||||
@ -1468,7 +1478,7 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
|
||||
{
|
||||
/* main mode switch */
|
||||
if (!isfinite(sp_man->mode_switch)) {
|
||||
warnx("mode sw not finite");
|
||||
/* default to manual if signal is invalid */
|
||||
status->mode_switch = MODE_SWITCH_MANUAL;
|
||||
|
||||
} else if (sp_man->mode_switch > STICK_ON_OFF_LIMIT) {
|
||||
@ -1550,7 +1560,7 @@ set_main_state_rc(struct vehicle_status_s *status)
|
||||
break; // changed successfully or already in this state
|
||||
|
||||
// else fallback to SEATBELT
|
||||
print_reject_mode("EASY");
|
||||
print_reject_mode(status, "EASY");
|
||||
}
|
||||
|
||||
res = main_state_transition(status, MAIN_STATE_SEATBELT);
|
||||
@ -1559,7 +1569,7 @@ set_main_state_rc(struct vehicle_status_s *status)
|
||||
break; // changed successfully or already in this mode
|
||||
|
||||
if (status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages
|
||||
print_reject_mode("SEATBELT");
|
||||
print_reject_mode(status, "SEATBELT");
|
||||
|
||||
// else fallback to MANUAL
|
||||
res = main_state_transition(status, MAIN_STATE_MANUAL);
|
||||
@ -1573,7 +1583,7 @@ set_main_state_rc(struct vehicle_status_s *status)
|
||||
break; // changed successfully or already in this state
|
||||
|
||||
// else fallback to SEATBELT (EASY likely will not work too)
|
||||
print_reject_mode("AUTO");
|
||||
print_reject_mode(status, "AUTO");
|
||||
res = main_state_transition(status, MAIN_STATE_SEATBELT);
|
||||
|
||||
if (res != TRANSITION_DENIED)
|
||||
@ -1592,6 +1602,7 @@ set_main_state_rc(struct vehicle_status_s *status)
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
set_control_mode()
|
||||
{
|
||||
/* set vehicle_control_mode according to main state and failsafe state */
|
||||
@ -1699,16 +1710,25 @@ set_control_mode()
|
||||
}
|
||||
|
||||
void
|
||||
print_reject_mode(const char *msg)
|
||||
print_reject_mode(struct vehicle_status_s *status, const char *msg)
|
||||
{
|
||||
hrt_abstime t = hrt_absolute_time();
|
||||
|
||||
if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
|
||||
last_print_mode_reject_time = t;
|
||||
char s[80];
|
||||
sprintf(s, "#audio: warning: reject %s", msg);
|
||||
sprintf(s, "#audio: REJECT %s", msg);
|
||||
mavlink_log_critical(mavlink_fd, s);
|
||||
tune_negative();
|
||||
|
||||
// only buzz if armed, because else we're driving people nuts indoors
|
||||
// they really need to look at the leds as well.
|
||||
if (status->arming_state == ARMING_STATE_ARMED) {
|
||||
tune_negative();
|
||||
} else {
|
||||
|
||||
// Always show the led indication
|
||||
led_negative();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -1856,7 +1876,15 @@ void *commander_low_prio_loop(void *arg)
|
||||
} else if ((int)(cmd.param4) == 1) {
|
||||
/* RC calibration */
|
||||
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
calib_ret = do_rc_calibration(mavlink_fd);
|
||||
/* disable RC control input completely */
|
||||
status.rc_input_blocked = true;
|
||||
calib_ret = OK;
|
||||
mavlink_log_info(mavlink_fd, "CAL: Disabling RC IN");
|
||||
|
||||
} else if ((int)(cmd.param4) == 2) {
|
||||
/* RC trim calibration */
|
||||
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
calib_ret = do_trim_calibration(mavlink_fd);
|
||||
|
||||
} else if ((int)(cmd.param5) == 1) {
|
||||
/* accelerometer calibration */
|
||||
@ -1867,6 +1895,18 @@ void *commander_low_prio_loop(void *arg)
|
||||
/* airspeed calibration */
|
||||
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
calib_ret = do_airspeed_calibration(mavlink_fd);
|
||||
} else if ((int)(cmd.param4) == 0) {
|
||||
/* RC calibration ended - have we been in one worth confirming? */
|
||||
if (status.rc_input_blocked) {
|
||||
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
/* enable RC control input */
|
||||
status.rc_input_blocked = false;
|
||||
mavlink_log_info(mavlink_fd, "CAL: Re-enabling RC IN");
|
||||
}
|
||||
|
||||
/* this always succeeds */
|
||||
calib_ret = OK;
|
||||
|
||||
}
|
||||
|
||||
if (calib_ret == OK)
|
||||
|
||||
@ -123,11 +123,16 @@ void tune_neutral()
|
||||
}
|
||||
|
||||
void tune_negative()
|
||||
{
|
||||
led_negative();
|
||||
ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
|
||||
}
|
||||
|
||||
void led_negative()
|
||||
{
|
||||
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
|
||||
rgbled_set_color(RGBLED_COLOR_RED);
|
||||
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
|
||||
ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
|
||||
}
|
||||
|
||||
int tune_arm()
|
||||
|
||||
@ -62,6 +62,9 @@ int tune_arm(void);
|
||||
int tune_low_bat(void);
|
||||
int tune_critical_bat(void);
|
||||
void tune_stop(void);
|
||||
|
||||
void led_negative();
|
||||
|
||||
int blink_msg_state();
|
||||
|
||||
int led_init(void);
|
||||
|
||||
@ -53,17 +53,16 @@
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
int do_rc_calibration(int mavlink_fd)
|
||||
int do_trim_calibration(int mavlink_fd)
|
||||
{
|
||||
mavlink_log_info(mavlink_fd, "trim calibration starting");
|
||||
|
||||
int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
usleep(200000);
|
||||
struct manual_control_setpoint_s sp;
|
||||
bool changed;
|
||||
orb_check(sub_man, &changed);
|
||||
|
||||
if (!changed) {
|
||||
mavlink_log_critical(mavlink_fd, "no manual control, aborting");
|
||||
mavlink_log_critical(mavlink_fd, "no inputs, aborting");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
@ -82,12 +81,12 @@ int do_rc_calibration(int mavlink_fd)
|
||||
int save_ret = param_save_default();
|
||||
|
||||
if (save_ret != 0) {
|
||||
mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
|
||||
mavlink_log_critical(mavlink_fd, "TRIM: SAVE FAIL");
|
||||
close(sub_man);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
mavlink_log_info(mavlink_fd, "trim calibration done");
|
||||
mavlink_log_info(mavlink_fd, "trim cal done");
|
||||
close(sub_man);
|
||||
return OK;
|
||||
}
|
||||
|
||||
@ -41,6 +41,6 @@
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
int do_rc_calibration(int mavlink_fd);
|
||||
int do_trim_calibration(int mavlink_fd);
|
||||
|
||||
#endif /* RC_CALIBRATION_H_ */
|
||||
|
||||
@ -688,7 +688,8 @@ Navigator::task_main()
|
||||
/* RETURN switch, overrides MISSION switch */
|
||||
if (_vstatus.return_switch == RETURN_SWITCH_RETURN) {
|
||||
/* switch to RTL if not already landed after RTL and home position set */
|
||||
if (!(_rtl_state == RTL_STATE_DESCEND && (myState == NAV_STATE_READY || myState == NAV_STATE_LAND)) &&
|
||||
if (!(_rtl_state == RTL_STATE_DESCEND &&
|
||||
(myState == NAV_STATE_READY || myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) &&
|
||||
_vstatus.condition_home_position_valid) {
|
||||
dispatch(EVENT_RTL_REQUESTED);
|
||||
}
|
||||
@ -746,7 +747,8 @@ Navigator::task_main()
|
||||
break;
|
||||
|
||||
case NAV_STATE_RTL:
|
||||
if (!(_rtl_state == RTL_STATE_DESCEND && (myState == NAV_STATE_READY || myState == NAV_STATE_LAND)) &&
|
||||
if (!(_rtl_state == RTL_STATE_DESCEND &&
|
||||
(myState == NAV_STATE_READY || myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) &&
|
||||
_vstatus.condition_home_position_valid) {
|
||||
dispatch(EVENT_RTL_REQUESTED);
|
||||
}
|
||||
@ -1443,14 +1445,7 @@ Navigator::check_mission_item_reached()
|
||||
}
|
||||
|
||||
if (_mission_item.nav_cmd == NAV_CMD_LAND) {
|
||||
if (_vstatus.is_rotary_wing) {
|
||||
return _vstatus.condition_landed;
|
||||
|
||||
} else {
|
||||
/* For fw there is currently no landing detector:
|
||||
* make sure control is not stopped when overshooting the landing waypoint */
|
||||
return false;
|
||||
}
|
||||
return _vstatus.condition_landed;
|
||||
}
|
||||
|
||||
/* XXX TODO count turns */
|
||||
@ -1580,6 +1575,7 @@ Navigator::on_mission_item_reached()
|
||||
dispatch(EVENT_LAND_REQUESTED);
|
||||
|
||||
} else {
|
||||
_reset_loiter_pos = false;
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
}
|
||||
|
||||
|
||||
@ -60,4 +60,4 @@ PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
|
||||
PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
|
||||
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, 10.0f); // delay after descend before landing
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f); // delay after descend before landing, if set to -1 the system will not land but loiter at NAV_LAND_ALT
|
||||
|
||||
@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.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
|
||||
@ -639,37 +638,39 @@ Sensors::parameters_update()
|
||||
if (!rc_valid)
|
||||
warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
|
||||
|
||||
const char *paramerr = "FAIL PARM LOAD";
|
||||
|
||||
/* channel mapping */
|
||||
if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) {
|
||||
warnx("Failed getting roll chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_pitch, &(_parameters.rc_map_pitch)) != OK) {
|
||||
warnx("Failed getting pitch chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_yaw, &(_parameters.rc_map_yaw)) != OK) {
|
||||
warnx("Failed getting yaw chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_throttle, &(_parameters.rc_map_throttle)) != OK) {
|
||||
warnx("Failed getting throttle chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
|
||||
warnx("Failed getting mode sw chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_return_sw, &(_parameters.rc_map_return_sw)) != OK) {
|
||||
warnx("Failed getting return sw chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_assisted_sw, &(_parameters.rc_map_assisted_sw)) != OK) {
|
||||
warnx("Failed getting assisted sw chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_mission_sw, &(_parameters.rc_map_mission_sw)) != OK) {
|
||||
warnx("Failed getting mission sw chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_acro_sw, &(_parameters.rc_map_acro_sw)) != OK) {
|
||||
@ -677,7 +678,7 @@ Sensors::parameters_update()
|
||||
}
|
||||
|
||||
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
|
||||
warnx("Failed getting flaps chan index");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
|
||||
@ -750,12 +751,12 @@ Sensors::parameters_update()
|
||||
|
||||
/* scaling of ADC ticks to battery voltage */
|
||||
if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) {
|
||||
warnx("Failed updating voltage scaling param");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
/* scaling of ADC ticks to battery current */
|
||||
if (param_get(_parameter_handles.battery_current_scaling, &(_parameters.battery_current_scaling)) != OK) {
|
||||
warnx("Failed updating current scaling param");
|
||||
warnx(paramerr);
|
||||
}
|
||||
|
||||
param_get(_parameter_handles.board_rotation, &(_parameters.board_rotation));
|
||||
@ -1664,17 +1665,17 @@ int sensors_main(int argc, char *argv[])
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (sensors::g_sensors != nullptr)
|
||||
errx(0, "sensors task already running");
|
||||
errx(0, "already running");
|
||||
|
||||
sensors::g_sensors = new Sensors;
|
||||
|
||||
if (sensors::g_sensors == nullptr)
|
||||
errx(1, "sensors task alloc failed");
|
||||
errx(1, "alloc failed");
|
||||
|
||||
if (OK != sensors::g_sensors->start()) {
|
||||
delete sensors::g_sensors;
|
||||
sensors::g_sensors = nullptr;
|
||||
err(1, "sensors task start failed");
|
||||
err(1, "start failed");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
@ -1682,7 +1683,7 @@ int sensors_main(int argc, char *argv[])
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
if (sensors::g_sensors == nullptr)
|
||||
errx(1, "sensors task not running");
|
||||
errx(1, "not running");
|
||||
|
||||
delete sensors::g_sensors;
|
||||
sensors::g_sensors = nullptr;
|
||||
@ -1691,10 +1692,10 @@ int sensors_main(int argc, char *argv[])
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (sensors::g_sensors) {
|
||||
errx(0, "task is running");
|
||||
errx(0, "is running");
|
||||
|
||||
} else {
|
||||
errx(1, "task is not running");
|
||||
errx(1, "not running");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@ -216,6 +216,7 @@ struct vehicle_status_s
|
||||
|
||||
bool rc_signal_found_once;
|
||||
bool rc_signal_lost; /**< true if RC reception lost */
|
||||
bool rc_input_blocked; /**< set if RC input should be ignored */
|
||||
|
||||
bool offboard_control_signal_found_once;
|
||||
bool offboard_control_signal_lost;
|
||||
|
||||
@ -257,7 +257,6 @@ mtd_start(char *partition_names[], unsigned n_partitions)
|
||||
|
||||
/* Now create MTD FLASH partitions */
|
||||
|
||||
warnx("Creating partitions");
|
||||
FAR struct mtd_dev_s *part[n_partitions];
|
||||
char blockname[32];
|
||||
|
||||
@ -266,9 +265,6 @@ mtd_start(char *partition_names[], unsigned n_partitions)
|
||||
|
||||
for (offset = 0, i = 0; i < n_partitions; offset += nblocks, i++) {
|
||||
|
||||
warnx(" Partition %d. Block offset=%lu, size=%lu",
|
||||
i, (unsigned long)offset, (unsigned long)nblocks);
|
||||
|
||||
/* Create the partition */
|
||||
|
||||
part[i] = mtd_partition(mtd_dev, offset, nblocks);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user