rc.io is called from 2 places in rc.interface:
- if [ $OUTPUT_MODE = io -o $OUTPUT_MODE = uavcan_esc ]:
- 'set OUTPUT_MODE io' is only set within USE_IO=yes, so removing
the check in rc.io has no effect.
- in case of UAVCAN, we also want the IO for RC, now covered in the next
case.
- Further down ('Start IO for RC input if needed.').
This is intended to start IO for RC only, when fmu is already started.
However the previous check '$USE_IO = yes' in rc.io prevented that.
In addition we don't start rc_input in case of $USE_IO = no.
Fixes no RC on Pixhawk 2 with SYS_USE_IO=0.
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>