Browse Source
- Add flightgear_bridge submodule. - Add traget px4_sitl_nolockstep with disabled LOCKSTEP simulation. - Add flightgear viewer targets and startup scripts - Add a few possible vehicles plane (rascal), autogyro (tf-g1), and rover (tf-r1)) Co-authored-by: Vit Hanousek <vithanousek@seznam.cz>sbg
Jakub Kákona
5 years ago
committed by
GitHub
10 changed files with 412 additions and 1 deletions
@ -0,0 +1,58 @@ |
|||||||
|
#!/bin/sh |
||||||
|
# |
||||||
|
# @name Plane SITL |
||||||
|
# |
||||||
|
|
||||||
|
sh /etc/init.d/rc.fw_defaults |
||||||
|
|
||||||
|
if [ $AUTOCNF = yes ] |
||||||
|
then |
||||||
|
param set EKF2_ARSP_THR 8 |
||||||
|
param set EKF2_FUSE_BETA 1 |
||||||
|
#param set EKF2_MAG_ACCLIM 0 |
||||||
|
#param set EKF2_MAG_YAWLIM 0 |
||||||
|
|
||||||
|
param set FW_LND_AIRSPD_SC 1.1 |
||||||
|
param set FW_LND_ANG 5 |
||||||
|
param set FW_THR_LND_MAX 0 |
||||||
|
param set FW_LND_HHDIST 30 |
||||||
|
param set FW_LND_FL_PMIN 9.5 |
||||||
|
param set FW_LND_FL_PMAX 20 |
||||||
|
param set FW_LND_FLALT 5 |
||||||
|
param set FW_LND_TLALT 15 |
||||||
|
|
||||||
|
param set FW_L1_PERIOD 25 |
||||||
|
|
||||||
|
param set FW_P_TC 0.4 |
||||||
|
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.45 |
||||||
|
param set FW_RR_FF 0.40 |
||||||
|
param set FW_RR_I 0.132 |
||||||
|
param set FW_RR_P 0.085 |
||||||
|
|
||||||
|
param set FW_W_EN 1 |
||||||
|
|
||||||
|
param set MIS_LTRMIN_ALT 30 |
||||||
|
param set MIS_TAKEOFF_ALT 20 |
||||||
|
param set MIS_DIST_1WP 2500 |
||||||
|
param set MIS_DIST_WPS 10000 |
||||||
|
|
||||||
|
param set NAV_ACC_RAD 15 |
||||||
|
param set NAV_DLL_ACT 2 |
||||||
|
param set NAV_LOITER_RAD 50 |
||||||
|
|
||||||
|
param set RWTO_TKOFF 1 |
||||||
|
#param set FW_THR_SLEW_MAX 0.3 # fix takeoff failure for JSBsim in autonomous mission mode. |
||||||
|
param set RWTO_MAX_PITCH 20 |
||||||
|
param set RWTO_MAX_ROLL 10 |
||||||
|
#param set RWTO_MAX_THR 0.6 # fix takeoff failure for JSBsim in autonomous mission mode. |
||||||
|
param set RWTO_PSP 8 |
||||||
|
param set RWTO_AIRSPD_SCL 1.8 |
||||||
|
|
||||||
|
fi |
||||||
|
|
||||||
|
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix |
||||||
|
set MIXER custom |
@ -0,0 +1,58 @@ |
|||||||
|
#!/bin/sh |
||||||
|
# |
||||||
|
# @name Plane SITL |
||||||
|
# |
||||||
|
|
||||||
|
sh /etc/init.d/rc.fw_defaults |
||||||
|
|
||||||
|
if [ $AUTOCNF = yes ] |
||||||
|
then |
||||||
|
param set EKF2_ARSP_THR 8 |
||||||
|
param set EKF2_FUSE_BETA 1 |
||||||
|
#param set EKF2_MAG_ACCLIM 0 |
||||||
|
#param set EKF2_MAG_YAWLIM 0 |
||||||
|
|
||||||
|
param set FW_LND_AIRSPD_SC 1.1 |
||||||
|
param set FW_LND_ANG 5 |
||||||
|
param set FW_THR_LND_MAX 0 |
||||||
|
param set FW_LND_HHDIST 30 |
||||||
|
param set FW_LND_FL_PMIN 9.5 |
||||||
|
param set FW_LND_FL_PMAX 20 |
||||||
|
param set FW_LND_FLALT 5 |
||||||
|
param set FW_LND_TLALT 15 |
||||||
|
|
||||||
|
param set FW_L1_PERIOD 25 |
||||||
|
|
||||||
|
param set FW_P_TC 0.4 |
||||||
|
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.45 |
||||||
|
param set FW_RR_FF 0.40 |
||||||
|
param set FW_RR_I 0.132 |
||||||
|
param set FW_RR_P 0.085 |
||||||
|
|
||||||
|
param set FW_W_EN 1 |
||||||
|
|
||||||
|
param set MIS_LTRMIN_ALT 30 |
||||||
|
param set MIS_TAKEOFF_ALT 20 |
||||||
|
param set MIS_DIST_1WP 2500 |
||||||
|
param set MIS_DIST_WPS 10000 |
||||||
|
|
||||||
|
param set NAV_ACC_RAD 15 |
||||||
|
param set NAV_DLL_ACT 2 |
||||||
|
param set NAV_LOITER_RAD 50 |
||||||
|
|
||||||
|
param set RWTO_TKOFF 1 |
||||||
|
#param set FW_THR_SLEW_MAX 0.3 # fix takeoff failure for JSBsim in autonomous mission mode. |
||||||
|
param set RWTO_MAX_PITCH 20 |
||||||
|
param set RWTO_MAX_ROLL 10 |
||||||
|
#param set RWTO_MAX_THR 0.6 # fix takeoff failure for JSBsim in autonomous mission mode. |
||||||
|
param set RWTO_PSP 8 |
||||||
|
param set RWTO_AIRSPD_SCL 1.8 |
||||||
|
|
||||||
|
fi |
||||||
|
|
||||||
|
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix |
||||||
|
set MIXER custom |
@ -0,0 +1,43 @@ |
|||||||
|
#!/bin/sh |
||||||
|
# |
||||||
|
# @name ThunderFly TF-R1 UAV Rover |
||||||
|
# @type Rover |
||||||
|
# @class Rover |
||||||
|
# |
||||||
|
# @url https://github.com/ThunderFly-aerospace/TF-R1/ |
||||||
|
# @maintainer ThunderFly s.r.o. |
||||||
|
# |
||||||
|
|
||||||
|
sh /etc/init.d/rc.rover_defaults |
||||||
|
|
||||||
|
if [ $AUTOCNF = yes ] |
||||||
|
then |
||||||
|
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_SPEED_TRIM 15 |
||||||
|
param set GND_SPEED_MAX 25 |
||||||
|
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 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 |
||||||
|
|
||||||
|
param set GND_MAX_ANG 0.6 |
||||||
|
param set GND_WHEEL_BASE 3.0 |
||||||
|
|
||||||
|
fi |
||||||
|
|
||||||
|
set MAV_TYPE 10 |
||||||
|
|
||||||
|
set MIXER_FILE etc/mixers-sitl/rover_sitl.main.mix |
@ -0,0 +1,64 @@ |
|||||||
|
#!/bin/sh |
||||||
|
# |
||||||
|
# @name ThunderFly TF-G1 |
||||||
|
# ThunderFly TF-G1 autogyro airframe. Only for FlightGear simulator |
||||||
|
# |
||||||
|
# @type Autogyro |
||||||
|
# @class Autogyro |
||||||
|
# |
||||||
|
# @url https://github.com/ThunderFly-aerospace/TF-G1/ |
||||||
|
# |
||||||
|
# |
||||||
|
|
||||||
|
sh /etc/init.d/rc.fw_defaults |
||||||
|
|
||||||
|
if [ $AUTOCNF = yes ] |
||||||
|
then |
||||||
|
param set EKF2_ARSP_THR 8 |
||||||
|
param set EKF2_FUSE_BETA 1 |
||||||
|
param set ASPD_STALL 10.0 |
||||||
|
|
||||||
|
param set FW_P_RMAX_NEG 20.0 |
||||||
|
param set FW_P_RMAX_POS 60.0 |
||||||
|
param set FW_W_RMAX 10 |
||||||
|
param set FW_W_EN 1 |
||||||
|
|
||||||
|
param set FW_PR_IMAX 0.4 |
||||||
|
param set FW_R_TC 0.4 |
||||||
|
param set FW_RR_FF 0.5 |
||||||
|
param set FW_RR_I 0.1 |
||||||
|
param set FW_RR_IMAX 0.2 |
||||||
|
param set FW_RR_P 0.08 |
||||||
|
|
||||||
|
param set MIS_LTRMIN_ALT 50 |
||||||
|
param set MIS_TAKEOFF_ALT 3 |
||||||
|
|
||||||
|
param set NAV_ACC_RAD 20 |
||||||
|
param set NAV_DLL_ACT 2 |
||||||
|
param set NAV_LOITER_RAD 100 |
||||||
|
|
||||||
|
param set RWTO_TKOFF 1 |
||||||
|
param set MAV_BROADCAST 1 |
||||||
|
|
||||||
|
param set FW_ARSP_SCALE_EN 0 |
||||||
|
|
||||||
|
param set FW_AIRSPD_MAX 35 |
||||||
|
param set FW_AIRSPD_MIN 7 |
||||||
|
param set FW_AIRSPD_TRIM 15 |
||||||
|
|
||||||
|
param set FW_P_LIM_MAX 25 |
||||||
|
param set FW_P_LIM_MIN -5 |
||||||
|
param set FW_R_LIM 30 |
||||||
|
|
||||||
|
param set FW_MAN_P_MAX 30.0 |
||||||
|
param set FW_MAN_R_MAX 30.0 |
||||||
|
|
||||||
|
param set FW_THR_CRUISE 0.8 |
||||||
|
param set FW_THR_IDLE 0 |
||||||
|
param set COM_DISARM_PRFLT 0 |
||||||
|
|
||||||
|
fi |
||||||
|
|
||||||
|
|
||||||
|
set MIXER_FILE etc/mixers-sitl/autogyro_sitl.main.mix |
||||||
|
set MIXER custom |
@ -0,0 +1,37 @@ |
|||||||
|
Mixer for SITL autogyro. |
||||||
|
========================================================= |
||||||
|
|
||||||
|
# 0 mixer for the rudder (Rotor roll) |
||||||
|
M: 1 |
||||||
|
O: 10000 10000 0 -10000 10000 |
||||||
|
S: 0 2 10000 10000 0 -10000 10000 |
||||||
|
|
||||||
|
# 1 mixer for the pusher/puller throttle |
||||||
|
M: 1 |
||||||
|
O: 10000 10000 0 -10000 10000 |
||||||
|
S: 0 3 0 20000 -10000 -10000 10000 |
||||||
|
|
||||||
|
# 2 mixer for the aileron |
||||||
|
M: 1 |
||||||
|
O: 10000 10000 0 -10000 10000 |
||||||
|
S: 0 0 -10000 -10000 0 -10000 10000 |
||||||
|
|
||||||
|
# 3 mixer for the elevator (Rotor pitch) |
||||||
|
M: 1 |
||||||
|
O: 10000 10000 0 -10000 10000 |
||||||
|
S: 0 1 10000 10000 0 -10000 10000 |
||||||
|
|
||||||
|
# 4 mixer for the prerotator AUX1 |
||||||
|
M: 1 |
||||||
|
O: 10000 10000 0 -10000 10000 |
||||||
|
S: 1 5 10000 10000 0 -10000 10000 |
||||||
|
|
||||||
|
# 5 mixer for the manual elevator AUX2 |
||||||
|
M: 1 |
||||||
|
O: 10000 10000 0 -10000 10000 |
||||||
|
S: 1 6 10000 10000 0 -10000 10000 |
||||||
|
|
||||||
|
# 6 mixer for the release device AUX3 |
||||||
|
M: 1 |
||||||
|
O: 10000 10000 0 -10000 10000 |
||||||
|
S: 1 7 10000 10000 0 -10000 10000 |
@ -0,0 +1,91 @@ |
|||||||
|
|
||||||
|
px4_add_board( |
||||||
|
PLATFORM posix |
||||||
|
VENDOR px4 |
||||||
|
MODEL sitl |
||||||
|
LABEL nolockstep |
||||||
|
TESTING |
||||||
|
DRIVERS |
||||||
|
#barometer # all available barometer drivers |
||||||
|
#batt_smbus |
||||||
|
camera_capture |
||||||
|
camera_trigger |
||||||
|
#differential_pressure # all available differential pressure drivers |
||||||
|
#distance_sensor # all available distance sensor drivers |
||||||
|
gps |
||||||
|
#imu # all available imu drivers |
||||||
|
#magnetometer # all available magnetometer drivers |
||||||
|
pwm_out_sim |
||||||
|
#telemetry # all available telemetry drivers |
||||||
|
tone_alarm |
||||||
|
#uavcan |
||||||
|
MODULES |
||||||
|
airspeed_selector |
||||||
|
attitude_estimator_q |
||||||
|
camera_feedback |
||||||
|
commander |
||||||
|
dataman |
||||||
|
ekf2 |
||||||
|
events |
||||||
|
fw_att_control |
||||||
|
fw_pos_control_l1 |
||||||
|
land_detector |
||||||
|
landing_target_estimator |
||||||
|
#load_mon |
||||||
|
local_position_estimator |
||||||
|
logger |
||||||
|
mavlink |
||||||
|
mc_att_control |
||||||
|
mc_hover_thrust_estimator |
||||||
|
mc_pos_control |
||||||
|
mc_rate_control |
||||||
|
navigator |
||||||
|
rc_update |
||||||
|
replay |
||||||
|
rover_pos_control |
||||||
|
sensors |
||||||
|
#sih |
||||||
|
simulator |
||||||
|
temperature_compensation |
||||||
|
vmount |
||||||
|
vtol_att_control |
||||||
|
uuv_att_control |
||||||
|
|
||||||
|
SYSTEMCMDS |
||||||
|
#config |
||||||
|
#dumpfile |
||||||
|
dyn |
||||||
|
esc_calib |
||||||
|
led_control |
||||||
|
mixer |
||||||
|
motor_ramp |
||||||
|
motor_test |
||||||
|
#mtd |
||||||
|
#nshterm |
||||||
|
param |
||||||
|
perf |
||||||
|
pwm |
||||||
|
reboot |
||||||
|
sd_bench |
||||||
|
shutdown |
||||||
|
tests # tests and test runner |
||||||
|
#top |
||||||
|
topic_listener |
||||||
|
tune_control |
||||||
|
ver |
||||||
|
work_queue |
||||||
|
EXAMPLES |
||||||
|
dyn_hello # dynamically loading modules example |
||||||
|
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||||
|
hello |
||||||
|
#hwtest # Hardware test |
||||||
|
#matlab_csv_serial |
||||||
|
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html |
||||||
|
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html |
||||||
|
rover_steering_control # Rover example app |
||||||
|
uuv_example_app |
||||||
|
) |
||||||
|
|
||||||
|
message(STATUS "Building without lockstep") |
||||||
|
set(ENABLE_LOCKSTEP_SCHEDULER no) |
||||||
|
|
Loading…
Reference in new issue