mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
When running in HITL mode, pwm_out_sim publishes actuator_outputs. px4io unconditionally publishes the uOrb actuator_outputs. When HITL is configured, the px4io copy of the uOrb has all zeros. The result is that there are two publications, one valid, and one all-zeros. This causes the HIL_ACTUATOR_CONTROLS mavlink message to be incorrect (all-zeros) and the SERVO_OUTPUTS_RAW mavlink message to be inconsistent, as it takes the data from one or the other uOrb randomly each cycle. The fix is to let px4io know that HITL is in effect when it is started, and modify px4io to suppress publication in this case. This is a bigger more complicated fix than I would like, but I think it is conceptually correct. Signed-off-by: Nik Langrind <langrind@gmail.com>
27 lines
541 B
Io
27 lines
541 B
Io
#!/bin/sh
|
|
#
|
|
# PX4IO interface init script.
|
|
#
|
|
|
|
# If $OUTPUT_MODE indicated Hardware-int-the-loop simulation, px4io should not publish actuator_outputs,
|
|
# instead, pwm_out_sim will publish that uORB
|
|
if [ $OUTPUT_MODE = hil ]
|
|
then
|
|
set HIL_ARG $OUTPUT_MODE
|
|
fi
|
|
|
|
if [ $USE_IO = yes -a $IO_PRESENT = yes ]
|
|
then
|
|
if px4io start $HIL_ARG
|
|
then
|
|
# Allow PX4IO to recover from midair restarts.
|
|
px4io recovery
|
|
|
|
# Adjust PX4IO update rate limit.
|
|
px4io limit 400
|
|
else
|
|
echo "PX4IO start failed" >> $LOG_FILE
|
|
tune_control play -t 20
|
|
fi
|
|
fi
|