mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-14 06:27:34 +08:00
Multi-Vehicle Ignition Gazebo Simulation (#20154)
This commit is contained in:
committed by
GitHub
parent
7bbdc220f5
commit
a56f654651
@@ -1,80 +0,0 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Ignition Gazebo X4
|
||||
#
|
||||
# @type Quadrotor
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
PX4_SIMULATOR=${PX4_SIMULATOR:=ignition}
|
||||
PX4_SIM_MODEL=${PX4_SIM_MODEL:=x4}
|
||||
PX4_SIM_WORLD=${PX4_SIM_WORLD:=default}
|
||||
|
||||
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_IGN_FUNC1 101
|
||||
param set-default SIM_IGN_FUNC2 102
|
||||
param set-default SIM_IGN_FUNC3 103
|
||||
param set-default SIM_IGN_FUNC4 104
|
||||
param set-default SIM_IGN_FUNC5 105
|
||||
param set-default SIM_IGN_FUNC6 106
|
||||
|
||||
param set-default SIM_IGN_MIN1 150
|
||||
param set-default SIM_IGN_MIN2 150
|
||||
param set-default SIM_IGN_MIN3 150
|
||||
param set-default SIM_IGN_MIN4 150
|
||||
param set-default SIM_IGN_MIN5 150
|
||||
param set-default SIM_IGN_MIN6 150
|
||||
|
||||
param set-default SIM_IGN_MAX1 1000
|
||||
param set-default SIM_IGN_MAX2 1000
|
||||
param set-default SIM_IGN_MAX3 1000
|
||||
param set-default SIM_IGN_MAX4 1000
|
||||
param set-default SIM_IGN_MAX5 1000
|
||||
param set-default SIM_IGN_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
|
||||
@@ -79,7 +79,6 @@ px4_add_romfs_files(
|
||||
17002_tf-g2
|
||||
2507_cloudship
|
||||
|
||||
6001_x4
|
||||
6011_typhoon_h480
|
||||
6011_typhoon_h480.post
|
||||
)
|
||||
|
||||
@@ -20,7 +20,10 @@ elif [ "$PX4_SIMULATOR" = "ignition" ]; then
|
||||
. ../gazebo_env.sh
|
||||
fi
|
||||
|
||||
if ! ign service --info --service /world/${PX4_SIM_WORLD}/create | grep "ignition.msgs.EntityFactory"; then
|
||||
ign_world=$( ign topic -l | grep -m 1 -e "/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' )
|
||||
|
||||
if [ -z $ign_world ]; then
|
||||
|
||||
# starting ign gazebo with ${PX4_SIM_WORLD} world
|
||||
echo "INFO [init] starting ign gazebo"
|
||||
|
||||
@@ -31,16 +34,37 @@ elif [ "$PX4_SIMULATOR" = "ignition" ]; then
|
||||
ign gazebo --verbose=1 -r -s "${PX4_IGN_GAZEBO_WORLDS}/${PX4_SIM_WORLD}.sdf" &
|
||||
fi
|
||||
else
|
||||
echo "INFO [init] ign gazebo already running"
|
||||
echo "INFO [init] ign gazebo already running world: $ign_world"
|
||||
PX4_SIM_WORLD=$ign_world
|
||||
fi
|
||||
|
||||
if simulator_ignition_bridge start -m "${PX4_SIM_MODEL}" -w "${PX4_SIM_WORLD}"; then
|
||||
sensor_baro_sim start
|
||||
sensor_gps_sim start
|
||||
sensor_mag_sim start
|
||||
if [ -z $PX4_IGN_MODEL_POSE ]; then
|
||||
# start ignition bridge without pose arg.
|
||||
echo "WARN [init] PX4_IGN_MODEL_POSE not set, spawning at origin."
|
||||
if simulator_ignition_bridge start -m "${PX4_SIM_MODEL}" -w "${PX4_SIM_WORLD}"; then
|
||||
sensor_baro_sim start
|
||||
sensor_gps_sim start
|
||||
sensor_mag_sim start
|
||||
else
|
||||
echo "ERROR [init] ign gazebo failed to start"
|
||||
exit 1
|
||||
fi
|
||||
else
|
||||
echo "ERROR [init] ign gazebo failed to start"
|
||||
exit 1
|
||||
|
||||
# Clean potential input line formatting.
|
||||
model_pose="$( echo ${PX4_IGN_MODEL_POSE} | sed -e 's/^[ \t]*//; s/[ \t]*$//; s/,/ /g; s/ / /g; s/ /,/g' )"
|
||||
echo "INFO [init] PX4_IGN_MODEL_POSE set, spawning at: ${model_pose}"
|
||||
|
||||
# start ignition bridge with pose arg.
|
||||
if simulator_ignition_bridge start -p "${model_pose}" -m "${PX4_SIM_MODEL}" -w "${PX4_SIM_WORLD}"; then
|
||||
sensor_baro_sim start
|
||||
sensor_gps_sim start
|
||||
sensor_mag_sim start
|
||||
else
|
||||
echo "ERROR [init] ign gazebo failed to start"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
fi
|
||||
|
||||
else
|
||||
|
||||
Reference in New Issue
Block a user