1 在SITL仿真下,使用QGC设置多机任务路径,会出现QGC中路径设置显示正常,但是开始任务时所有飞机都按照最后设置那个任务航迹飞。
1.1 解决此问题需要修改SITL的配置参数:
gedit ~/PX4_Firmware/ROMFS/px4fmu_common/init.d-posix/rcS
1.2 为不同机体创建不同的任务数据文件,需添加瑞如下代码:
dataman start -f dataman$((px4_instance+1))
具体添加位置如下:
1.3 防止QGC连接丢失后自动返航,需添加以下命令用于修改与自动返航相关的参数:
param set NAV_DLL_ACT 0
param set NAV_RCL_ACT 0
具体添加位置如下:
修改后的rcS文件(可直接复制粘贴)
#!/bin/sh
set -e
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
# shellcheck disable=SC1091
. px4-alias.sh
#search path for sourcing px4-rc.*
PATH="$PATH:${R}etc/init.d-posix"
#
# Main SITL startup script
#
# check for ekf2 replay
# shellcheck disable=SC2154
if [ "$replay_mode" = "ekf2" ]
then
. ${R}etc/init.d-posix/rc.replay
exit 0
fi
# initialize script variables
set IO_PRESENT no
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
set OUTPUT_MODE sim
set EXTRA_MIXER_MODE none
set PWM_OUT none
set SDCARD_MIXERS_PATH etc/mixers
set USE_IO no
set VEHICLE_TYPE none
set LOGGER_ARGS ""
set LOGGER_BUF 1000
set RUN_MINIMAL_SHELL no
# Use the variable set by sitl_run.sh to choose the model settings.
if [ "$PX4_SIM_MODEL" = "shell" ]; then
set RUN_MINIMAL_SHELL yes
else
# Find the matching Autostart ID (file name has the form: [0-9]+_${PX4_SIM_MODEL})
# TODO: unify with rc.autostart generation
# shellcheck disable=SC2012
REQUESTED_AUTOSTART=$(ls "${R}etc/init.d-posix/airframes" | sed -n 's/^\([0-9][0-9]*\)_'${PX4_SIM_MODEL}'$/\1/p')
if [ -z "$REQUESTED_AUTOSTART" ]; then
echo "ERROR [init] Unknown model $PX4_SIM_MODEL (not found by name on ${R}etc/init.d-posix/airframes)"
exit 1
else
echo "INFO [init] found model autostart file as SYS_AUTOSTART=$REQUESTED_AUTOSTART"
fi
fi
# Load parameters
set PARAM_FILE eeprom/parameters_"$REQUESTED_AUTOSTART"
param select $PARAM_FILE
if [ -f $PARAM_FILE ]
then
if param load
then
echo "[param] Loaded: $PARAM_FILE"
else
echo "[param] FAILED loading $PARAM_FILE"
fi
else
echo "[param] parameter file not found, creating $PARAM_FILE"
fi
# exit early when the minimal shell is requested
[ $RUN_MINIMAL_SHELL = yes ] && exit 0
# Use environment variable PX4_ESTIMATOR to choose estimator.
if [ "$PX4_ESTIMATOR" = "q" ]; then
param set SYS_MC_EST_GROUP 3
elif [ "$PX4_ESTIMATOR" = "ekf2" ]; then
param set SYS_MC_EST_GROUP 2
elif [ "$PX4_ESTIMATOR" = "lpe" ]; then
param set SYS_MC_EST_GROUP 1
elif [ "$PX4_ESTIMATOR" = "inav" ]; then
param set SYS_MC_EST_GROUP 0
fi
if param compare SYS_AUTOSTART $REQUESTED_AUTOSTART
then
set AUTOCNF no
else
set AUTOCNF yes
param set SYS_AUTOCONFIG 1
fi
if param compare SYS_AUTOCONFIG 1
then
set AUTOCNF yes
# Wipe out params except RC*, flight modes, total flight time, accel cal, gyro cal, next flight UUID
param reset_all SYS_AUTO* RC* COM_FLTMODE* LND_FLIGHT* TC_* CAL_ACC* CAL_GYRO* COM_FLIGHT*
fi
# multi-instance setup
# shellcheck disable=SC2154
param set MAV_SYS_ID $((px4_instance+1))
dataman start -f dataman$((px4_instance+1)) # 为不同机体创建不同的任务数据文件
if [ $AUTOCNF = yes ]
then
param set SYS_AUTOSTART $REQUESTED_AUTOSTART
param set CAL_ACC0_ID 1310988 # 1310988: DRV_IMU_DEVTYPE_SIM, BUS: 1, ADDR: 1, TYPE: SIMULATION
param set CAL_GYRO0_ID 1310988 # 1310988: DRV_IMU_DEVTYPE_SIM, BUS: 1, ADDR: 1, TYPE: SIMULATION
param set CAL_ACC1_ID 1310996 # 1310996: DRV_IMU_DEVTYPE_SIM, BUS: 2, ADDR: 1, TYPE: SIMULATION
param set CAL_GYRO1_ID 1310996 # 1310996: DRV_IMU_DEVTYPE_SIM, BUS: 2, ADDR: 1, TYPE: SIMULATION
param set CAL_ACC2_ID 1311004 # 1311004: DRV_IMU_DEVTYPE_SIM, BUS: 3, ADDR: 1, TYPE: SIMULATION
param set CAL_GYRO2_ID 1311004 # 1311004: DRV_IMU_DEVTYPE_SIM, BUS: 3, ADDR: 1, TYPE: SIMULATION
param set CAL_MAG0_ID 197388
param set CAL_MAG1_ID 197644
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
##############
## XTDrone ##
##############
# GPS used
param set EKF2_AID_MASK 1
# Vision used and GPS denied
#param set EKF2_AID_MASK 24
# Barometer used for hight measurement
param set EKF2_HGT_MODE 0
# Barometer denied and vision used for hight measurement
#param set EKF2_HGT_MODE 3
fi
param set-default BAT1_N_CELLS 4
param set-default CBRK_AIRSPD_CHK 0
param set-default CBRK_SUPPLY_CHK 894281
# disable check, no CPU load reported on posix yet
param set-default COM_CPU_MAX -1
# Don't require RC calibration and configuration
param set-default COM_RC_IN_MODE 1
# Speedup SITL startup
param set-default EKF2_REQ_GPS_H 0.5
# Multi-EKF
param set-default EKF2_MULTI_IMU 3
param set-default SENS_IMU_MODE 0
param set-default EKF2_MULTI_MAG 2
param set-default SENS_MAG_MODE 0
param set-default IMU_GYRO_FFT_EN 1
param set-default -s MC_AT_EN 1
# By default log from boot until first disarm.
param set-default SDLOG_MODE 1
# enable default, estimator replay and vision/avoidance logging profiles
param set-default SDLOG_PROFILE 131
param set-default SDLOG_DIRS_MAX 7
param set-default TRIG_INTERFACE 3
# Adapt timeout parameters if simulation runs faster or slower than realtime.
if [ -n "$PX4_SIM_SPEED_FACTOR" ]; then
COM_DL_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 10" | bc)
echo "COM_DL_LOSS_T set to $COM_DL_LOSS_T_LONGER"
param set COM_DL_LOSS_T $COM_DL_LOSS_T_LONGER
COM_RC_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 0.5" | bc)
echo "COM_RC_LOSS_T set to $COM_RC_LOSS_T_LONGER"
param set COM_RC_LOSS_T $COM_RC_LOSS_T_LONGER
COM_OF_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 0.5" | bc)
echo "COM_OF_LOSS_T set to $COM_OF_LOSS_T_LONGER"
param set COM_OF_LOSS_T $COM_OF_LOSS_T_LONGER
COM_OBC_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 5.0" | bc)
echo "COM_OBC_LOSS_T set to $COM_OBC_LOSS_T_LONGER"
param set COM_OBC_LOSS_T $COM_OBC_LOSS_T_LONGER
fi
# Autostart ID
autostart_file=''
# shellcheck disable=SC2231
for f in ${R}etc/init.d-posix/airframes/"$(param show -q SYS_AUTOSTART)"_*
do
filename=$(basename "$f")
case "$filename" in
*\.*)
# ignore files that contain a dot (e.g. <vehicle>.post)
;;
*)
autostart_file="$f"
;;
esac
done
if [ ! -e "$autostart_file" ]; then
echo "Error: no autostart file found ($autostart_file)"
exit 1
fi
. "$autostart_file"
#
# If autoconfig parameter was set, reset it and save parameters.
#
if [ $AUTOCNF = yes ]
then
param set SYS_AUTOCONFIG 0
fi
# Simulator IMU data provided at 250 Hz
param set IMU_INTEG_RATE 250
#user defined params for instances can be in PATH
. px4-rc.params
# 防止QGC连接丢失后自动返航
param set NAV_DLL_ACT 0
param set NAV_RCL_ACT 0
dataman start
# only start the simulator if not in replay mode, as both control the lockstep time
if ! replay tryapplyparams
then
. px4-rc.simulator
fi
load_mon start
battery_simulator start
tone_alarm start
rc_update start
manual_control start
sensors start
commander start
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
navigator start
# Try to start the micrortps_client with UDP transport if module exists
if px4-micrortps_client status > /dev/null 2>&1
then
. px4-rc.rtps
fi
if param greater -s MNT_MODE_IN -1
then
gimbal start
fi
if param greater -s TRIG_MODE 0
then
camera_trigger start
camera_feedback start
fi
if param compare -s IMU_GYRO_FFT_EN 1
then
gyro_fft start
fi
if param compare -s IMU_GYRO_CAL_EN 1
then
gyro_calibration start
fi
#user defined mavlink streams for instances can be in PATH
. px4-rc.mavlink
# execute autostart post script if any
[ -e "$autostart_file".post ] && . "$autostart_file".post
# Run script to start logging
if param compare SYS_MC_EST_GROUP 2
then
set LOGGER_ARGS "-p ekf2_timestamps"
else
set LOGGER_ARGS "-p vehicle_attitude"
fi
. ${R}etc/init.d/rc.logging
mavlink boot_complete
replay trystart
修改完成后记得保存!!!
2 多机SITL配置文件的生成
2.1 启动python脚本生成多机launch文件(本次配置以3架iris四旋翼无人机为例)
cd ~/XTDrone/coordination/launch_generator
python3 generator.py
进入到launch生成脚本界面,输入0-7选择机型,enter确认后输入该机型的数量,之后输入该机型占据的行数(这样可以构成矩形阵列)。添加结束后输入f进行launch文件的生成。
2.2 将生成出来的launch文件复制到PX4固件的launch文件夹
cp ~/XTDrone/coordination/launch_generator/multi_vehicle.launch ~/PX4_Firmware/launch/
2.3 启动多机仿真程序
cd ~/PX4_Firmware/
roslaunch px4 multi_vehicle.launch
启动仿真后的效果:
3 打开一个新窗口,输入如下命令进入你所安装QGC的文件夹,并打开QGC地面站
注意:QGC地面站的语言要设置为英文,不然没办法打航点。这应该ia是一个bug吧...
cd QGC/ # 根据你的安装位置来修改
./QGroundControl.AppImage
QGC打开后的正常界面如下:
a. 点击红色框1中位置的图标进行机体的切换,比如此时我们切换到了vehicle3
b. 然后点击红色框2中位置的图表进入任务规划界面,如下图所示
c. 在此界面可以通过左侧边栏手动添加航点,也可以选择一些预设图案(Pattren),比如本例中选择测绘(Survey)图案。(注意:要先选择takeoff之后才能进行航点规划)
d.选中Survey后会弹出红空中的选项,本配置选择Basic,而后自动加载出了下图所示的航线。
e. 右侧边栏列出了一些参数设置,比如飞行高度、转弯距离等。(不修改的话选择默认参数即可)
f. 设置完毕后点屏幕上方的Upload Required进行任务上传,显示“Done”即上传成功
g. 点击左上角紫色小飞机图标回到控制台,切换机体(重复a-e的操作)直到所有飞机的搜索路径设置完成。
设置航迹时,先点击清除飞机任务,再根据需要进行设置。可做到新航点不与之前的相连
具体做法,切换新无人机后,进入Plan模式,而后选择File,再选择Clear即可
全部规划完航点之后的效果如下图所示
启动任务
点击右上角的“Multi-Vehicle”进入多机指令模式
滑动屏幕上方的Start Mssion,地面战将给所有飞机发送解锁和切换到任务模式的指令,运行效果如下:
开始后出现如下报错:
以下是查阅的无法切换Mission模式的原因,由于本次配置时GPS的状态显示Disabled,因此没有办法切换到Mission模式。
QGC地面站无法切换到Mission模式可能由多种原因引起,以下是一些常见的检查点和解决方案:
1. 检查飞行器状态
确保飞行器处于允许切换到Mission模式的状态。通常需要以下条件:
- GPS信号良好
- 起飞前的所有预检通过
- 电池电量充足
2. 参数设置
确保相关参数设置正确:
- COM_RCL_EXCEPT:设置为1以允许即使没有遥控器输入也能执行任务。
- NAV_DLL_ACT和NAV_RCL_ACT:确保这些参数已被正确设置为0,以防止自动返航干扰任务模式。
3. 任务规划
确保任务规划正确,并且上传到飞行器成功。任务规划应包含起点、若干航点和终点,并且这些航点的高度和其他设置都合理。
4. 飞行模式
确保飞行器当前处于可切换到Mission模式的飞行模式,比如手动模式、位置保持模式等。某些模式下无法直接切换到Mission模式。
5. 系统日志
查看系统日志以获取详细信息。日志中可能会显示为什么无法切换到Mission模式的具体原因。
6. 固件版本
确保你使用的PX4固件和QGC版本是兼容的。有时候不同版本之间可能存在兼容性问题。
7. 校准传感器
确保所有传感器(如IMU、磁力计、气压计等)已正确校准。传感器未校准可能导致飞行器无法进入自动模式。
———————————————————————————————————————————
关于Not Ready 的解决方法
进入你的QGC地面站的安装位置,然后在该文件在中打开终端,输入以下命令即可打开地面站。
./QGroundControl.AppImage
如果进去的界面如下:
这可有能是你的rcS文件中的参数未正确设置,详见PX4飞控EKF配置 · 语雀 ,检查你的rcS文件的参数是否设置如下:
# GPS used
param set EKF2_AID_MASK 1
# Vision used and GPS denied
#param set EKF2_AID_MASK 24
# Barometer used for hight measurement
param set EKF2_HGT_MODE 0
# Barometer denied and vision used for hight measurement
#param set EKF2_HGT_MODE 3
修改并保存后,再次重启gazebo仿真和QGC地面站。
正常打开后的界面如下: