PX4-Autopilot
PX4-Autopilot copied to clipboard
uxrce_dds_client: refactor init to retry indefinitely
- move init from UxrceddsClient to init() method so that retry is possible for both serial and UDP init
- init from main loop instead of constructor so we can retry indefinitely
For example if using USB CDCACM on NuttX we need to be more lenient waiting for /dev/ttyACM0.
I'm seeing serial dds disconnecting after some time and requiring a reboot to connect again. Could this handle reconnection?
So far it looks like this is working and staying connected.
INFO [uxrce_dds_client] Running, connected
INFO [uxrce_dds_client] Using transport: serial
INFO [uxrce_dds_client] Payload tx: 50321 B/s
INFO [uxrce_dds_client] Payload rx: 8038 B/s
INFO [uxrce_dds_client] timesync converged: true
uxrce_dds_client: cycle: 173013 events, 877674757us elapsed, 5072.88us avg, min 70us max 39835us 4203.281us rms
uxrce_dds_client: cycle interval: 173014 events, 5074.21us avg, min 71us max 39835us 4203.388us rms
nsh>
This is working for a few minutes until TX gets stuck.
These commits need to be reverted. PX4/NuttX@ed4814f PX4/NuttX@3dc3cf5
see https://github.com/PX4/PX4-Autopilot/issues/22558#issuecomment-1864754034
With TX DMA turned off on the serial port, this is working now.
With all due respect, could we create a unit test that would keep this failure from ongoing? sertest.txt
Or, libserial, with full unit test coverage: https://libserial.sourceforge.net/
Ran it overnight and it was still working in the morning. A few hours later I stopped getting data.
dmesg showed this
ERROR [uxrce_dds_client] create entities failed: rt/fmu/out/vehicle_command_ack, topic: 255 publisher: 255 datawriter: 255
Restarting the agent on the companion computer got it working again. dmesg after restarting the agent
INFO [uxrce_dds_client] synchronized with time offset 1705208740419528us
INFO [uxrce_dds_client] successfully created rt/fmu/out/battery_status data writer, topic id: 19
INFO [uxrce_dds_client] successfully created rt/fmu/out/estimator_status_flags data writer, topic id: 86
INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 92
INFO [uxrce_dds_client] successfully created rt/fmu/out/manual_control_setpoint data writer, topic id: 138
INFO [uxrce_dds_client] successfully created rt/fmu/out/position_setpoint_triplet data writer, topic id: 169
INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 190
INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 213
INFO [uxrce_dds_client] successfully created rt/fmu/out/vehicle_attitude data writer, topic id: 229
INFO [uxrce_dds_client] successfully created rt/fmu/out/vehicle_control_mode data writer, topic id: 236
INFO [uxrce_dds_client] successfully created rt/fmu/out/vehicle_command_ack data writer, topic id: 233
INFO [uxrce_dds_client] successfully created rt/fmu/out/vehicle_local_position data writer, topic id: 243
INFO [uxrce_dds_client] successfully created rt/fmu/out/vehicle_odometry data writer, topic id: 248
INFO [uxrce_dds_client] successfully created rt/fmu/out/vehicle_status data writer, topic id: 253```
@AlexKlimaj is this working now on current main with the Nuttx H7 serial DMA change?
@davids5 looks like this is working well now.
Maybe time to bring this in now that issues where addressed elsewhere @dagar?
Rebased on main and pushed. Have it running on the jetson now.
INFO [uxrce_dds_client] Running, connected
INFO [uxrce_dds_client] Using transport: serial
INFO [uxrce_dds_client] Payload tx: 57600 B/s
INFO [uxrce_dds_client] Payload rx: 8910 B/s
INFO [uxrce_dds_client] timesync converged: true
uxrce_dds_client: cycle: 15696 events, 68066836us elapsed, 4336.57us avg, min 76us max 52028us 3382.906us rms
uxrce_dds_client: cycle interval: 15698 events, 4337.80us avg, min 77us max 52029us 3382.670us rms
nsh>
nsh>
nsh> uxrce_dds_client status
INFO [uxrce_dds_client] Running, connected
INFO [uxrce_dds_client] Using transport: serial
INFO [uxrce_dds_client] Payload tx: 57263 B/s
INFO [uxrce_dds_client] Payload rx: 7962 B/s
INFO [uxrce_dds_client] timesync converged: true
uxrce_dds_client: cycle: 21180 events, 90000808us elapsed, 4249.33us avg, min 76us max 52028us 3296.924us rms
uxrce_dds_client: cycle interval: 21181 events, 4250.67us avg, min 77us max 52029us 3297.117us rms
nsh>
nsh>
nsh>
nsh> uxrce_dds_client status
INFO [uxrce_dds_client] Running, connected
INFO [uxrce_dds_client] Using transport: serial
INFO [uxrce_dds_client] Payload tx: 57617 B/s
INFO [uxrce_dds_client] Payload rx: 6526 B/s
INFO [uxrce_dds_client] timesync converged: true
uxrce_dds_client: cycle: 156017 events, 644598981us elapsed, 4131.59us avg, min 70us max 52028us 3334.504us rms
uxrce_dds_client: cycle interval: 156021 events, 4133.33us avg, min 71us max 52029us 3334.712us rms
nsh>