new Ignition Gazebo simulation interface architecture (#20057)

- much simpler direct interface using Ignition Transport 
 - in tree models and worlds
 - control allocation output configuration, no more magic actuator mapping to mavlink and back
 - currently requires no custom Gazebo plugins (keeping things as lightweight and simple as possible)

Co-authored-by: Jaeyoung-Lim <jalim@ethz.ch>
This commit is contained in:
Daniel Agar
2022-08-22 10:58:19 -04:00
committed by GitHub
parent 889a2fddea
commit cfc579542e
58 changed files with 29260 additions and 220 deletions
@@ -0,0 +1,46 @@
#!/bin/sh
#
# @name Ignition Gazebo X3
#
# @type Quadrotor
#
. ${R}etc/init.d/rc.mc_defaults
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.13
param set-default CA_ROTOR0_PY 0.22
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.13
param set-default CA_ROTOR1_PY -0.20
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.13
param set-default CA_ROTOR2_PY -0.22
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.13
param set-default CA_ROTOR3_PY 0.20
param set-default CA_ROTOR3_KM -0.05
param set-default SIM_GZ_FUNC1 101
param set-default SIM_GZ_FUNC2 102
param set-default SIM_GZ_FUNC3 103
param set-default SIM_GZ_FUNC4 104
param set-default SIM_GZ_MIN1 150
param set-default SIM_GZ_MIN2 150
param set-default SIM_GZ_MIN3 150
param set-default SIM_GZ_MIN4 150
param set-default SIM_GZ_MAX1 1000
param set-default SIM_GZ_MAX2 1000
param set-default SIM_GZ_MAX3 1000
param set-default SIM_GZ_MAX4 1000
param set-default MPC_THR_HOVER 0.60
@@ -0,0 +1,76 @@
#!/bin/sh
#
# @name Ignition Gazebo X4
#
# @type Quadrotor
#
. ${R}etc/init.d/rc.mc_defaults
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 6
param set-default CA_ROTOR0_PX 0.25
param set-default CA_ROTOR0_PY -0.15
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX 0.00
param set-default CA_ROTOR1_PY -0.29
param set-default CA_ROTOR1_KM -0.05
param set-default CA_ROTOR2_PX -0.25
param set-default CA_ROTOR2_PY -0.15
param set-default CA_ROTOR2_KM 0.05
param set-default CA_ROTOR3_PX -0.25
param set-default CA_ROTOR3_PY 0.15
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR4_PX 0.00
param set-default CA_ROTOR4_PY 0.29
param set-default CA_ROTOR4_KM 0.05
param set-default CA_ROTOR5_PX 0.25
param set-default CA_ROTOR5_PY 0.15
param set-default CA_ROTOR5_KM -0.05
param set-default SIM_GZ_FUNC1 101
param set-default SIM_GZ_FUNC2 102
param set-default SIM_GZ_FUNC3 103
param set-default SIM_GZ_FUNC4 104
param set-default SIM_GZ_FUNC5 105
param set-default SIM_GZ_FUNC6 106
param set-default SIM_GZ_MIN1 150
param set-default SIM_GZ_MIN2 150
param set-default SIM_GZ_MIN3 150
param set-default SIM_GZ_MIN4 150
param set-default SIM_GZ_MIN5 150
param set-default SIM_GZ_MIN6 150
param set-default SIM_GZ_MAX1 1000
param set-default SIM_GZ_MAX2 1000
param set-default SIM_GZ_MAX3 1000
param set-default SIM_GZ_MAX4 1000
param set-default SIM_GZ_MAX5 1000
param set-default SIM_GZ_MAX6 1000
param set-default MC_PITCHRATE_D 0.0016
param set-default MC_PITCHRATE_I 0.2500
param set-default MC_PITCHRATE_P 0.1831
param set-default MC_PITCH_P 5.216
param set-default MC_ROLLRATE_D 0.0022
param set-default MC_ROLLRATE_I 0.2095
param set-default MC_ROLLRATE_P 0.1570
param set-default MC_ROLL_P 6.081
param set-default MC_YAWRATE_D 0.0009
param set-default MC_YAWRATE_I 0.1800
param set-default MC_YAWRATE_P 0.1773
param set-default MC_YAW_P 5.386490
param set-default MPC_THR_HOVER 0.61
@@ -72,9 +72,14 @@ px4_add_romfs_files(
1070_boat
3010_quadrotor_x
3011_hexarotor_x
4001_x3
17001_tf-g1
17002_tf-g2
2507_cloudship
6001_x4
6011_typhoon_h480
6011_typhoon_h480.post
)
@@ -1,20 +1,43 @@
#!/bin/sh
# shellcheck disable=SC2154
simulator_tcp_port=$((4560+px4_instance))
PX4_SIM_WORLD="${PX4_SIM_WORLD:="empty"}" # default to empty world?
echo "PX4_SIM_MODEL: ${PX4_SIM_MODEL}"
echo "PX4_SIM_WORLD: ${PX4_SIM_WORLD}"
# TODO: verify if world exists
ign service --info --service /world/${PX4_SIM_WORLD}/create
echo $?
ign service -s /world/${PX4_SIM_WORLD}/create --reqtype ignition.msgs.EntityFactory --reptype ignition.msgs.Boolean --timeout 1000 --req "sdf_filename: \"${PX4_SIM_MODEL}/model.sdf\""
if ignition_simulator start -m "${PX4_SIM_MODEL}" -w "${PX4_SIM_WORLD}"
then
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
# Check if PX4_SIM_HOSTNAME environment variable is empty
# If empty check if PX4_SIM_HOST_ADDR environment variable is empty
# If both are empty use localhost for simulator
if [ -z "${PX4_SIM_HOSTNAME}" ]; then
if [ -z "${PX4_SIM_HOST_ADDR}" ]; then
echo "PX4 SIM HOST: localhost"
simulator start -c $simulator_tcp_port
else
echo "PX4 SIM HOST: $PX4_SIM_HOST_ADDR"
simulator start -t $PX4_SIM_HOST_ADDR $simulator_tcp_port
fi
else
echo "PX4 SIM HOST: $PX4_SIM_HOSTNAME"
simulator start -h $PX4_SIM_HOSTNAME $simulator_tcp_port
simulator_tcp_port=$((4560+px4_instance))
# Check if PX4_SIM_HOSTNAME environment variable is empty
# If empty check if PX4_SIM_HOST_ADDR environment variable is empty
# If both are empty use localhost for simulator
if [ -z "${PX4_SIM_HOSTNAME}" ]; then
if [ -z "${PX4_SIM_HOST_ADDR}" ]; then
echo "PX4 SIM HOST: localhost"
simulator start -c $simulator_tcp_port
else
echo "PX4 SIM HOST: $PX4_SIM_HOST_ADDR"
simulator start -t $PX4_SIM_HOST_ADDR $simulator_tcp_port
fi
else
echo "PX4 SIM HOST: $PX4_SIM_HOSTNAME"
simulator start -h $PX4_SIM_HOSTNAME $simulator_tcp_port
fi
fi
+1
View File
@@ -212,6 +212,7 @@ elif ! replay tryapplyparams
then
. px4-rc.simulator
fi
load_mon start
battery_simulator start
tone_alarm start