SITL: move all models to unified rcS startup and remove old scripts

This commit is contained in:
Beat Küng 2018-08-11 18:02:12 +02:00 committed by Daniel Agar
parent 5ebd0116de
commit 273988c124
51 changed files with 391 additions and 2442 deletions

View File

@ -0,0 +1,30 @@
#!nsh
#
# @name 3DR Iris Quadrotor SITL (Optical Flow)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/10016_iris
if [ $AUTOCNF == yes ]
then
param set EKF2_AID_MASK 2
param set EKF2_EV_DELAY 5
param set EKF2_EVP_NOISE 0.05
param set EKF2_EVA_NOISE 0.05
param set INAV_LIDAR_EST 1
param set INAV_W_XY_FLOW 1.0
param set INAV_W_XY_GPS_P 0.0
param set INAV_W_XY_GPS_V 0.0
param set INAV_W_Z_GPS_P 0.0
# LPE: Flow-only mode
param set LPE_FUSION 242
param set LPE_FAKE_ORIGIN 1
param set MPC_ALT_MODE 2
fi

View File

@ -0,0 +1,4 @@
mavlink stream -r 10 -s DISTANCE_SENSOR -u $udp_gcs_port_local
mavlink stream -r 10 -s VISION_POSITION_ESTIMATE -u $udp_gcs_port_local

View File

@ -0,0 +1,17 @@
#!nsh
#
# @name 3DR Iris Quadrotor SITL (irlock)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/10016_iris
if [ $AUTOCNF == yes ]
then
# enable fusion of landing target velocity
param set LTEST_MODE 1
param set PLD_HACC_RAD 0.1
fi

View File

@ -0,0 +1,14 @@
#!nsh
#
# @name 3DR Iris Quadrotor SITL (rplidar)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/10016_iris
if [ $AUTOCNF == yes ]
then
param set LPE_FUSION 242
fi

View File

@ -0,0 +1,16 @@
#!nsh
#
# @name 3DR Iris Quadrotor SITL (Vision)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/1010_iris_opt_flow
if [ $AUTOCNF == yes ]
then
param set EKF2_AID_MASK 8
param set EKF2_EV_DELAY 5
fi

View File

@ -0,0 +1,17 @@
#!nsh
#
# @name Solo
#
# @type Quadrotor
#
sh /etc/init.d/rc.mc_defaults
if [ $AUTOCNF == yes ]
then
param set MC_PITCHRATE_P 0.15
param set MC_ROLLRATE_P 0.15
fi
set MIXER quad_x

View File

@ -0,0 +1,10 @@
#!nsh
#
# @name Hippocampus UUV
#
sh /etc/init.d/rc.mc_defaults
set MIXER uuv_quad_x

View File

@ -0,0 +1,42 @@
#!nsh
#
# @name Plane SITL
#
sh /etc/init.d/rc.fw_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 1
param set EKF2_ARSP_THR 8.0
param set EKF2_FUSE_BETA 1
param set EKF2_MAG_ACCLIM 0
param set EKF2_MAG_YAWLIM 0
param set FW_LND_ANG 8
param set FW_P_TC 0.5
param set FW_PR_FF 0.40
param set FW_PR_I 0.05
param set FW_PR_P 0.05
param set FW_R_TC 0.7
param set FW_RR_FF 0.20
param set FW_RR_I 0.02
param set FW_RR_P 0.22
param set FW_THR_IDLE 0.15
param set FW_W_EN 1
param set MIS_LTRMIN_ALT 30
param set MIS_TAKEOFF_ALT 30
param set NAV_ACC_RAD 15.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 50
param set RWTO_TKOFF 1
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
set MIXER custom

View File

@ -0,0 +1,45 @@
#!nsh
#
# @name Standard VTOL
#
# @type Standard VTOL
#
sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 22
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set NAV_ACC_RAD 5.0
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 5
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_TYPE 2
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
set MIXER custom

View File

@ -0,0 +1,47 @@
#!nsh
#
# @name Quadrotor + Tailsitter
#
# @type VTOL Quad Tailsitter
#
sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 20
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.15
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.05
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.8
param set NAV_ACC_RAD 5.0
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 1.5
param set VT_F_TRANS_THR 0.7
param set VT_MOT_COUNT 0
param set VT_TYPE 0
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/quad_x_vtol.main.mix
set MIXER custom

View File

@ -0,0 +1,50 @@
#!nsh
#
# @name VTOL Tiltrotor
#
# @type VTOL Tiltrotor
#
sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 21
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.15
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.05
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.8
param set NAV_ACC_RAD 5.0
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 1.5
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_TILT_FW 3.1415
param set VT_TILT_TRANS 1.2
param set VT_TYPE 1
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/tiltrotor_sitl.main.mix
set MIXER custom

View File

@ -0,0 +1,38 @@
#!nsh
#
# @name Rover
#
sh /etc/init.d/rc.ugv_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 10
param set GND_L1_DIST 5
param set GND_SP_CTRL_MODE 1
param set GND_SPEED_D 3
param set GND_SPEED_I 0.001
param set GND_SPEED_IMAX 0.125
param set GND_SPEED_P 0.25
param set GND_SPEED_THR_SC 1
param set GND_THR_CRUISE 0.3
param set GND_THR_IDLE 0
param set GND_THR_MAX 0.5
param set GND_THR_MIN 0
param set GND_SPEED_TRIM 4
param set GND_WR_D 1.2
param set GND_WR_I 0.9674
param set GND_WR_IMAX 0.1
param set GND_WR_P 2
param set MIS_LTRMIN_ALT 0.01
param set MIS_TAKEOFF_ALT 0.01
param set NAV_ACC_RAD 0.5
param set NAV_LOITER_RAD 2
param set CBRK_AIRSPD_CHK 162128
fi
set MIXER_FILE etc/mixers-sitl/rover_sitl.main.mix

View File

@ -4,8 +4,9 @@
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
#
# Main SITL startup script
#
# check for ekf2 replay
if [ "$replay_mode" == "ekf2" ]
@ -21,6 +22,7 @@ set LOG_FILE bootlog.txt
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
set OUTPUT_MODE sim
set PWM_OUT none
set SDCARD_MIXERS_PATH etc/mixers
@ -34,6 +36,28 @@ if [ "$PX4_SIM_MODEL" == "shell" ]; then
set RUN_MINIMAL_SHELL yes
elif [ "$PX4_SIM_MODEL" == "iris" ]; then
set REQUESTED_AUTOSTART 10016
elif [ "$PX4_SIM_MODEL" == "iris_opt_flow" ]; then
set REQUESTED_AUTOSTART 1010
elif [ "$PX4_SIM_MODEL" == "iris_irlock" ]; then
set REQUESTED_AUTOSTART 1011
elif [ "$PX4_SIM_MODEL" == "iris_rplidar" ]; then
set REQUESTED_AUTOSTART 1012
elif [ "$PX4_SIM_MODEL" == "iris_vision" ]; then
set REQUESTED_AUTOSTART 1013
elif [ "$PX4_SIM_MODEL" == "solo" ]; then
set REQUESTED_AUTOSTART 1014
elif [ "$PX4_SIM_MODEL" == "hippocampus" ]; then
set REQUESTED_AUTOSTART 1020
elif [ "$PX4_SIM_MODEL" == "plane" ]; then
set REQUESTED_AUTOSTART 1030
elif [ "$PX4_SIM_MODEL" == "standard_vtol" ]; then
set REQUESTED_AUTOSTART 1040
elif [ "$PX4_SIM_MODEL" == "tailsitter" ]; then
set REQUESTED_AUTOSTART 1041
elif [ "$PX4_SIM_MODEL" == "tiltrotor" ]; then
set REQUESTED_AUTOSTART 1042
elif [ "$PX4_SIM_MODEL" == "rover" ]; then
set REQUESTED_AUTOSTART 1060
elif [ "$PX4_SIM_MODEL" == "typhoon_h480" ]; then
set REQUESTED_AUTOSTART 6011
else
@ -96,6 +120,8 @@ then
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set SENS_DPRES_OFF 0.001
param set CBRK_AIRSPD_CHK 0
param set COM_DISARM_LAND 3
param set COM_OBL_ACT 2
@ -114,6 +140,7 @@ then
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MIS_TAKEOFF_ALT 2.5
param set MPC_ALT_MODE 0
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
@ -127,6 +154,11 @@ then
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_RESTART_TYPE 2
# LPE: GPS only mode
param set LPE_FUSION 145
param set WEST_EN 0
fi
# Autostart ID
@ -153,6 +185,10 @@ sensors start
commander start
navigator start
if param compare WEST_EN 1
then
wind_estimator start
fi
if ! param compare MNT_MODE_IN -1
then
@ -166,6 +202,15 @@ then
camera_feedback start
fi
if [ ${VEHICLE_TYPE} == fw -o ${VEHICLE_TYPE} == vtol ]
then
if param compare CBRK_AIRSPD_CHK 0
then
measairspeedsim start
fi
fi
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.ugv_apps, and rc.vtol_apps.

View File

@ -29,7 +29,3 @@ fw_pos_control_l1 start
#
land_detector start fixedwing
#
# Start Wind and Airspeed Scale Estimator.
#
#wind_estimator start

View File

@ -55,7 +55,3 @@ fw_pos_control_l1 start
#
land_detector start vtol
#
# Start Wind and Airspeed Scale Estimator
#
#wind_estimator start

View File

@ -486,7 +486,10 @@ else
#
# Start the standalone wind estimator.
#
wind_estimator start
if param compare WEST_EN 1
then
wind_estimator start
fi
#
# Start a thermal calibration if required.

View File

@ -98,16 +98,10 @@ pushd "$rootfs" >/dev/null
# Do not exit on failure now from here on because we want the complete cleanup
set +e
# Use the new unified rcS for the supported models
# (All models will be transitioned over)
if [[ ($rcS_path == posix-configs/SITL/init/ekf2 || $rcS_path == posix-configs/SITL/init/lpe)
&& ($model == "iris" || $model == "typhoon_h480") ]]; then
echo "Using new unified rcS for $model"
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -t $src_path/test_data"
elif [[ ${model} == tests* ]]; then
if [[ ${model} == tests* ]]; then
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_test -s ${src_path}/${rcS_path}/${model} -t $src_path/test_data"
else
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s ${src_path}/${rcS_path}/${model} -t $src_path/test_data"
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -t $src_path/test_data"
fi
echo SITL COMMAND: $sitl_command

View File

@ -1,2 +0,0 @@
#!/bin/bash
export PX4_SIM_MODEL="iris"

View File

@ -14,7 +14,6 @@
<arg name="vehicle" default="iris"/>
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)"/>
<!-- gazebo configs -->
<arg name="gui" default="true"/>
@ -38,7 +37,6 @@
<arg name="world" value="$(arg world)"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="sdf" value="$(arg sdf)"/>
<arg name="rcS" value="$(arg rcS)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="interactive" value="$(arg interactive)"/>
<arg name="debug" value="$(arg debug)"/>

View File

@ -33,7 +33,6 @@
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="rcS" value="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
<arg name="mavlink_udp_port" value="14561"/>
<arg name="ID" value="$(arg ID)"/>
</include>
@ -59,7 +58,6 @@
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="rcS" value="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
<arg name="mavlink_udp_port" value="14562"/>
<arg name="ID" value="$(arg ID)"/>
</include>

View File

@ -14,7 +14,8 @@
<arg name="vehicle" default="iris"/>
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)"/>
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
<env name="PX4_ESTIMATOR" value="$(arg est)" />
<!-- gazebo configs -->
<arg name="gui" default="true"/>
@ -28,7 +29,7 @@
<arg unless="$(arg interactive)" name="px4_command_arg1" value="-d"/>
<arg if="$(arg interactive)" name="px4_command_arg1" value=""/>
<node name="sitl" pkg="px4" type="px4" output="screen"
args="$(find px4)/ROMFS/px4fmu_common -s $(arg rcS) $(arg px4_command_arg1)" required="true"/>
args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS $(arg px4_command_arg1)" required="true"/>
<!-- Gazebo sim -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
@ -41,8 +42,5 @@
</include>
<!-- gazebo model -->
<node name="$(anon vehicle_spawn)" pkg="gazebo_ros" type="spawn_model" output="screen" args="-sdf -file $(arg sdf) -model $(arg vehicle) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
<!-- This will set the environment variable needed to select iris in the startup. -->
<machine name="px4" env-loader="iris_env.sh" address="none" />
</launch>

View File

@ -13,7 +13,8 @@
<arg name="est" default="ekf2"/>
<arg name="vehicle" default="iris"/>
<arg name="ID" default="1"/>
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
<env name="PX4_ESTIMATOR" value="$(arg est)" />
<arg name="mavlink_udp_port" default="14560"/>
<!-- PX4 configs -->
<arg name="interactive" default="true"/>
@ -23,7 +24,7 @@
<!-- PX4 SITL -->
<arg unless="$(arg interactive)" name="px4_command_arg1" value=""/>
<arg if="$(arg interactive)" name="px4_command_arg1" value="-d"/>
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen" args="$(find px4)/ROMFS/px4fmu_common -s $(arg rcS) -i $(arg ID) $(arg px4_command_arg1)">
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg ID) $(arg px4_command_arg1)">
</node>
<!-- spawn vehicle -->
<node name="$(arg vehicle)_$(arg ID)_spawn" output="screen" pkg="gazebo_ros" type="spawn_model" args="-urdf -param rotors_description -model $(arg vehicle)_$(arg ID) -package_to_model -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>

View File

@ -1,41 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set COM_DISARM_LAND 0
param set MAV_TYPE 3
param set SDLOG_DIRS_MAX 7
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
dataman start
simulator start -s
pwm_out_sim start
mixer load /dev/pwm_output0 etc/mixers/uuv_quad_x.mix
gyrosim start
accelsim start
barosim start
gpssim start
sleep 1
sensors start
commander start
ekf2 start
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
logger start -r 100 -e
mavlink boot_complete

View File

@ -1,83 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 3
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set COM_OF_LOSS_T 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set MAV_TYPE 2
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MIS_TAKEOFF_ALT 2.5
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 2.0
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_AUTOSTART 4010
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,85 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 3
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set COM_OF_LOSS_T 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set MAV_TYPE 2
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MIS_TAKEOFF_ALT 2.5
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 2.0
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_AUTOSTART 4010
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
landing_target_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,89 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 2
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set SDLOG_DIRS_MAX 7
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set EKF2_MAG_TYPE 1
param set EKF2_AID_MASK 2
param set EKF2_HGT_MODE 0
param set EKF2_EV_DELAY 5
param set EKF2_EVP_NOISE 0.05
param set EKF2_EVA_NOISE 0.05
param set MPC_ALT_MODE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
mavlink stream -r 10 -s DISTANCE_SENSOR -u 14556
mavlink stream -r 10 -s VISION_POSITION_ESTIMATE -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,83 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 3
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set COM_OF_LOSS_T 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set MAV_TYPE 2
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MIS_TAKEOFF_ALT 2.5
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 2.0
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_AUTOSTART 4010
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,88 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 2
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set SDLOG_DIRS_MAX 7
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set EKF2_MAG_TYPE 1
param set EKF2_AID_MASK 8
param set EKF2_HGT_MODE 0
param set EKF2_EV_DELAY 5
param set EKF2_EVP_NOISE 0.05
param set EKF2_EVA_NOISE 0.05
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
mavlink stream -r 10 -s DISTANCE_SENSOR -u 14556
mavlink stream -r 10 -s VISION_POSITION_ESTIMATE -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,82 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 3
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set COM_OF_LOSS_T 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set MAV_TYPE 2
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MIS_TAKEOFF_ALT 2.5
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 2.0
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_AUTOSTART 4010
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
replay tryapplyparams
simulator start -s -u _SIMPORT_
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u _MAVPORT_ -r 4000000 -o _MAVOPORT_
mavlink start -x -u _MAVPORT2_ -r 4000000 -m onboard -o _MAVOPORT2_
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u _MAVPORT_
mavlink stream -r 50 -s LOCAL_POSITION_NED -u _MAVPORT_
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u _MAVPORT_
mavlink stream -r 50 -s ATTITUDE -u _MAVPORT_
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u _MAVPORT_
mavlink stream -r 50 -s ATTITUDE_TARGET -u _MAVPORT_
mavlink stream -r 20 -s RC_CHANNELS -u _MAVPORT_
mavlink stream -r 250 -s HIGHRES_IMU -u _MAVPORT_
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u _MAVPORT_
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,106 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_POS_FS_DELAY 5
param set COM_POS_FS_EPH 25
param set COM_POS_FS_EPV 50
param set COM_POS_FS_GAIN 0
param set COM_POS_FS_PROB 1
param set COM_RC_IN_MODE 1
param set COM_VEL_FS_EVH 5
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_ARSP_THR 8.0
param set EKF2_FUSE_BETA 1
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_ACCLIM 0
param set EKF2_MAG_TYPE 1
param set EKF2_MAG_YAWLIM 0
param set FW_LND_ANG 8
param set FW_P_TC 0.5
param set FW_PR_FF 0.40
param set FW_PR_I 0.05
param set FW_PR_P 0.05
param set FW_R_TC 0.7
param set FW_RR_FF 0.20
param set FW_RR_I 0.02
param set FW_RR_P 0.22
param set FW_THR_IDLE 0.15
param set FW_W_EN 1
param set MAV_TYPE 1
param set MIS_LTRMIN_ALT 30
param set MIS_TAKEOFF_ALT 30
param set NAV_ACC_RAD 15.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 50
param set RWTO_TKOFF 1
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_AUTOSTART 3033
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sensors start
commander start
navigator start
ekf2 start
fw_pos_control_l1 start
fw_att_control start
land_detector start fixedwing
wind_estimator start
mixer load /dev/pwm_output0 etc/mixers-sitl/plane_sitl.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,88 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_RC_IN_MODE 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_MAG_TYPE 1
param set GND_L1_DIST 5
param set GND_SP_CTRL_MODE 1
param set GND_SPEED_D 3
param set GND_SPEED_I 0.001
param set GND_SPEED_IMAX 0.125
param set GND_SPEED_P 0.25
param set GND_SPEED_THR_SC 1
param set GND_THR_CRUISE 0.3
param set GND_THR_IDLE 0
param set GND_THR_MAX 0.5
param set GND_THR_MIN 0
param set GND_SPEED_TRIM 4
param set GND_WR_D 1.2
param set GND_WR_I 0.9674
param set GND_WR_IMAX 0.1
param set GND_WR_P 2
param set MAV_TYPE 10
param set MIS_LTRMIN_ALT 0.01
param set MIS_TAKEOFF_ALT 0.01
param set NAV_ACC_RAD 0.5
param set NAV_DLL_ACT 0
param set NAV_LOITER_RAD 2
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SDLOG_DIRS_MAX 7
param set SYS_AUTOSTART 50002
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sleep 1
sensors start
commander start
land_detector start ugv
navigator start
ekf2 start
gnd_pos_control start
gnd_att_control start
mixer load /dev/pwm_output0 etc/mixers-sitl/rover_sitl.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,80 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 3
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set MAV_TYPE 2
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.15
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.15
param set MIS_TAKEOFF_ALT 2.5
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 2.0
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_AUTOSTART 4010
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_x.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,103 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MAV_TYPE 22
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 5.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 80
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_AUTOSTART 13006
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_TYPE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sensors start
commander start
land_detector start vtol
navigator start
ekf2 start
vtol_att_control start
mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
wind_estimator start
mixer load /dev/pwm_output0 etc/mixers-sitl/standard_vtol_sitl.main.mix
mavlink start -x -u 14556 -r 2000000 -f
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540 -f
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14557
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,85 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set MAV_TYPE 20
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MPC_XY_P 0.15
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_P 0.05
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.8
param set MPC_LAND_SPEED 1.5
param set NAV_DLL_ACT 2
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_AUTOSTART 13003
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set VT_TYPE 0
param set VT_F_TRANS_DUR 1.5
param set VT_F_TRANS_THR 0.7
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sensors start
commander start
land_detector start vtol
navigator start
ekf2 start
vtol_att_control start
mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
wind_estimator start
mixer load /dev/pwm_output0 etc/mixers-sitl/quad_x_vtol.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,120 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MAV_TYPE 21
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 5.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 80
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_AUTOSTART 13012
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set VT_MOT_COUNT 4
param set VT_F_TRANS_THR 0.75
param set VT_TYPE 1
param set VT_TILT_FW 3.1415
param set VT_TILT_TRANS 1.2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sensors start
commander start
land_detector start vtol
navigator start
ekf2 start
vtol_att_control start
mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
wind_estimator start
mixer load /dev/pwm_output0 etc/mixers-sitl/tiltrotor_sitl.main.mix
mavlink start -x -u 14556 -r 2000000 -f
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540 -f
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14557
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,93 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.001
param set CAL_ACC0_XSCALE 1.0001
param set CAL_ACC0_YOFF -0.001
param set CAL_ACC0_YSCALE 1.0001
param set CAL_ACC0_ZOFF 0.001
param set CAL_ACC0_ZSCALE 1.0001
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.001
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.001
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.001
param set COM_DISARM_LAND 3
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set MAV_TYPE 13
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.1
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.05
param set MIS_TAKEOFF_ALT 2.5
param set MPC_HOLD_MAX_Z 2.0
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 2.0
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_AUTOSTART 6001
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set TRIG_INTERFACE 3
param set TRIG_MODE 4
param set MNT_MODE_IN 0
param set MAV_PROTO_VER 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/hexa_x.main.mix
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
mavlink stream -r 10 -s MOUNT_ORIENTATION -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14557
mavlink stream -r 10 -s MOUNT_ORIENTATION -u 14557
logger start -e -t
vmount start
camera_trigger start
mavlink boot_complete
replay trystart

View File

@ -1,81 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set MC_PITCHRATE_P 0.15
param set MC_ROLLRATE_P 0.15
param set MC_YAW_P 2.0
param set MC_YAWRATE_P 0.35
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 0
dataman start
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set MPC_XY_P 0.4
param set MPC_XY_VEL_P 0.2
param set MPC_XY_VEL_D 0.005
param set MPP_XY_P 1.0
param set MPP_XY_FF 0.0
param set MPP_XY_VEL_P 0.01
param set MPP_XY_VEL_I 0.0
param set MPP_XY_VEL_D 0.01
param set MPP_XY_VEL_MAX 2.0
param set MPP_Z_VEL_P 0.3
param set MPP_Z_P 2
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set MP_ROLL_P 3
param set MP_ROLLRATE_P 0.3
param set MP_ROLLRATE_I 0.001
param set MP_ROLLRATE_D 0.001
param set MP_PITCH_P 4
param set MP_PITCHRATE_P 0.3
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
position_estimator_inav start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_x.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,83 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 0
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 12.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.3
param set MC_PITCHRATE_P 0.3
param set MC_PITCH_P 5.5
param set MC_ROLL_P 5.5
param set MC_ROLLRATE_I 0.1
param set MC_PITCHRATE_I 0.1
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.8
param set MPC_Z_VEL_I 0.15
param set MPC_XY_VEL_P 0.15
param set MPC_XY_VEL_I 0.2
param set INAV_LIDAR_EST 1
param set INAV_W_XY_FLOW 1.0
param set INAV_W_XY_GPS_P 0.0
param set INAV_W_XY_GPS_V 0.0
param set INAV_W_Z_GPS_P 0.0
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
position_estimator_inav start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,41 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set COM_DISARM_LAND 0
param set MAV_TYPE 3
param set SDLOG_DIRS_MAX 7
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
dataman start
simulator start -s
pwm_out_sim start
mixer load /dev/pwm_output0 etc/mixers/uuv_quad_x.mix
gyrosim start
accelsim start
barosim start
sleep 1
sensors start
commander start
attitude_estimator_q start
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
logger start -r 100 -e
mavlink boot_complete

View File

@ -1,84 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set SDLOG_DIRS_MAX 7
# GPS only mode
param set LPE_FUSION 145
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,86 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_SYS_ID 1
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set SITL_UDP_PRT 14560
param set SDLOG_DIRS_MAX 7
# GPS only mode
param set LPE_FUSION 145
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,86 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_SYS_ID 2
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set SITL_UDP_PRT 14562
param set SDLOG_DIRS_MAX 7
# GPS only mode
param set LPE_FUSION 145
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14558 -r 4000000
mavlink start -x -u 14559 -r 4000000 -m onboard -o 14541
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14558
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14558
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14558
mavlink stream -r 50 -s ATTITUDE -u 14558
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14558
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14558
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14558
mavlink stream -r 20 -s RC_CHANNELS -u 14558
mavlink stream -r 250 -s HIGHRES_IMU -u 14558
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14558
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,93 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set MPC_XY_VEL_P 0.13
param set MPC_XY_P 1.2
param set MC_PITCHRATE_MAX 150
param set MC_ROLLRATE_MAX 150
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set SDLOG_DIRS_MAX 7
# GPS only mode
param set LPE_FUSION 145
param set LPE_EPH_MAX 5
# enable fusion of landing target velocity
param set LTEST_MODE 1
param set PLD_HACC_RAD 0.1
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
landing_target_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,101 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.3
param set MC_PITCHRATE_P 0.3
param set MC_PITCH_P 5.5
param set MC_ROLL_P 5.5
param set MC_ROLLRATE_I 0.1
param set MC_PITCHRATE_I 0.1
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.8
param set MPC_Z_VEL_I 0.15
param set MPC_XY_VEL_P 0.15
param set MPC_XY_VEL_I 0.2
param set SDLOG_DIRS_MAX 7
# changes for optical flow navigation
param set MC_PITCH_P 5.0
param set MC_ROLL_P 5.0
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_ROLLRATE_I 0.05
param set MC_PITCHRATE_I 0.05
param set MPC_ALT_MODE 1
param set LPE_T_MAX_GRADE 0
param set MPC_XY_VEL_MAX 2
param set MPC_Z_VEL_MAX_DN 2
param set MPC_TILTMAX_AIR 10
param set MPC_TILTMAX_LND 10
param set MPC_XY_P 0.5
param set MIS_TAKEOFF_ALT 2
param set NAV_ACC_RAD 1.0
param set CBRK_GPSFAIL 240024
# Flow-only mode
param set LPE_FUSION 242
param set LPE_FAKE_ORIGIN 1
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,83 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set LPE_FUSION 242
param set SDLOG_DIRS_MAX 7
replay tryapplyparams
simulator start -s
rgbledsim start
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sleep 1
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,88 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 1
param set SYS_AUTOSTART 3033
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_DPRES_OFF 0.001
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set NAV_ACC_RAD 15.0
param set NAV_LOITER_RAD 50
param set MIS_LTRMIN_ALT 30
param set MIS_TAKEOFF_ALT 30
param set SDLOG_DIRS_MAX 7
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set EKF2_MAG_TYPE 1
param set FW_THR_IDLE 0.15
param set FW_LND_ANG 8
param set FW_R_TC 0.7
param set FW_RR_FF 0.20
param set FW_RR_I 0.02
param set FW_RR_P 0.22
param set FW_P_TC 0.5
param set FW_PR_FF 0.40
param set FW_PR_I 0.05
param set FW_PR_P 0.05
param set FW_W_EN 1
param set RWTO_TKOFF 1
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sensors start
commander start
navigator start
local_position_estimator start
fw_pos_control_l1 start
fw_att_control start
land_detector start fixedwing
mixer load /dev/pwm_output0 etc/mixers-sitl/plane_sitl.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,84 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_RC_IN_MODE 1
param set GND_L1_DIST 5
param set GND_SP_CTRL_MODE 0
param set GND_SPEED_D 3
param set GND_SPEED_I 0.001
param set GND_SPEED_IMAX 0.125
param set GND_SPEED_P 0.25
param set GND_SPEED_THR_SC 1
param set GND_THR_CRUISE 0.3
param set GND_THR_IDLE 0
param set GND_THR_MAX 1
param set GND_THR_MIN 0
param set GND_WR_D 1.2
param set GND_WR_I 0.9674
param set GND_WR_IMAX 0.1
param set GND_WR_P 2
param set MAV_TYPE 10
param set MIS_LTRMIN_ALT 0.01
param set MIS_TAKEOFF_ALT 0.01
param set NAV_ACC_RAD 0.5
param set NAV_DLL_ACT 0
param set NAV_LOITER_RAD 2
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_AUTOSTART 50002
param set SYS_MC_EST_GROUP 1
param set SYS_RESTART_TYPE 2
param set SDLOG_DIRS_MAX 7
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sleep 1
sensors start
commander start
land_detector start ugv
navigator start
ekf2 start
gnd_pos_control start
gnd_att_control start
mixer load /dev/pwm_output0 etc/mixers-sitl/rover_sitl.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,84 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set SDLOG_DIRS_MAX 7
param set LPE_FUSION 247
# 11110111 no vis yaw (1 << 3)
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/quad_x.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,97 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 22
param set VT_TYPE 2
param set VT_MOT_COUNT 4
param set VT_F_TRANS_THR 0.75
param set SYS_AUTOSTART 13006
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set MC_ROLLRATE_P 0.3
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_XY_P 0.5
param set MPC_ACC_HOR_MAX 1.0
param set MPC_XY_VEL_P 0.1
param set MPC_XY_VEL_I 0.1
param set MPC_XY_VEL_D 0.005
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set FW_AIRSPD_MAX 25
param set SENS_BOARD_ROT 0
param set SENS_DPRES_OFF 0.001
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set NAV_ACC_RAD 5.0
param set NAV_LOITER_RAD 50
param set MPC_TKO_SPEED 1.0
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set COM_DISARM_LAND 5
param set MPC_ACC_HOR_MAX 2
param set SDLOG_DIRS_MAX 7
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sensors start
commander start
land_detector start vtol
navigator start
attitude_estimator_q start
local_position_estimator start
vtol_att_control start
mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
mixer load /dev/pwm_output0 etc/mixers-sitl/standard_vtol_sitl.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,83 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 13
param set SYS_AUTOSTART 6001
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 1
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
param set MPC_XY_VEL_P 0.15
param set MPC_XY_VEL_I 0.2
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set EKF2_MAG_TYPE 1
param set SDLOG_DIRS_MAX 7
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
pwm_out_sim start
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 etc/mixers/hexa_x.main.mix
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
vmount start
mavlink boot_complete
replay trystart

View File

@ -327,13 +327,12 @@ int WindEstimatorModule::print_status()
perf_print_counter(_perf_interval);
if (_instance > -1) {
unsigned instance = _instance;
uORB::Subscription<wind_estimate_s> est{ORB_ID(wind_estimate), instance};
uORB::Subscription<wind_estimate_s> est{ORB_ID(wind_estimate), (unsigned)_instance};
est.update();
print_message(est.get());
} else {
PX4_INFO("never published");
PX4_INFO("Running, but never published");
}
return 0;
@ -344,12 +343,5 @@ extern "C" __EXPORT int wind_estimator_main(int argc, char *argv[]);
int
wind_estimator_main(int argc, char *argv[])
{
int32_t wind_estimator_enabled = 0;
param_get(param_find("WEST_EN"), &wind_estimator_enabled);
if (wind_estimator_enabled == 1) {
return WindEstimatorModule::main(argc, argv);
}
return PX4_OK;
return WindEstimatorModule::main(argc, argv);
}