Open KyleJewiss opened 11 months ago
If you could add the mavlink log output as well that would be great. From memory, there were no mentions of AP_DDS showing in the log if the AP initialised with a hot GPS lock.
I had a look through the code and could not see any conditionals, especially anything that would prevent the output such as "DDS initialised" - could something be crashing?
So I have connected to the cubeorange using the mavlink terminal console. This is the output when the device instantly find geofix. Note that the mavlink never receives anything more than what is in this picture:
This is the output when it doesn't. As you can see it calls the AP_DDS this time:
Thanks for the detailed report. I have most of the similar hardware, I will try to reproduce it ASAP. Sorry for the trouble!
Which commit hash are you currently testing?
Hey @Ryanf55, so we are now on trunk. Our configuration is:
# project configured on Thu Nov 16 12:52:45 2023 by
# waf 2.0.9 (abi 20, python 30a0cf0 on linux)
# using /home/kyle/dev/test/ardupilot/ardupilot/modules/waf/waf-light configure --board CubeOrange --enable-dds
So we think we have narrowed the issue down to the AP_DDS_client.cpp file. Specifically the "APP_DDS_Client::init_session function.
bool AP_DDS_Client::init_session()
{
// init session
uxr_init_session(&session, comm, key);
// Register topic callbacks
uxr_set_topic_callback(&session, AP_DDS_Client::on_topic_trampoline, this);
// ROS-2 Service : Register service request callbacks
uxr_set_request_callback(&session, AP_DDS_Client::on_request_trampoline, this);
while (!uxr_create_session(&session)) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Initialization waiting...", msg_prefix);
hal.scheduler->delay(1000);
}
Using mavlink messages we can see that everything upto the "while (!uxr_create_session(&session))" executes, but it appears to get stuck in "uxr_create_session(&session))" which is from "session.c". NOTE: The "initialization waiting..." msg does not execute and nor does anything beyond this point (when GPS has instant geofix, it does when it had no geofix first).
Hi,
Sorry it appears that it actually gets stuck earlier in the AP_DDS_client.cpp code but I had it commented out and forgotten about it:
// check ping
const uint64_t ping_timeout_ms{1000};
const uint8_t ping_max_attempts{10};
if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: No ping response, exiting");
// return;
}
The return is commented out because otherwise the hardware will stop trying to connect to the DDS client after 10 seconds. This has no bearing on the current issue. The code appears to get stuck in "uxr_ping_agent_attempts". We are theorising that it could be something to do with the locking transport stuff within the "uxr_ping_agent_attempts" function.
Hi,
Sorry it appears that it actually gets stuck earlier in the AP_DDS_client.cpp code but I had it commented out and forgotten about it:
// check ping const uint64_t ping_timeout_ms{1000}; const uint8_t ping_max_attempts{10}; if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: No ping response, exiting"); // return; }
The return is commented out because otherwise the hardware will stop trying to connect to the DDS client after 10 seconds. This has no bearing on the current issue. The code appears to get stuck in "uxr_ping_agent_attempts". We are theorising that it could be something to do with the locking transport stuff within the "uxr_ping_agent_attempts" function.
Is there any way to reproduce this in SITL?
I dont know exactly. That code should still execute regardless. I'll test a bit later
Hi, Sorry it appears that it actually gets stuck earlier in the AP_DDS_client.cpp code but I had it commented out and forgotten about it:
// check ping const uint64_t ping_timeout_ms{1000}; const uint8_t ping_max_attempts{10}; if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: No ping response, exiting"); // return; }
The return is commented out because otherwise the hardware will stop trying to connect to the DDS client after 10 seconds. This has no bearing on the current issue. The code appears to get stuck in "uxr_ping_agent_attempts". We are theorising that it could be something to do with the locking transport stuff within the "uxr_ping_agent_attempts" function.
Is there any way to reproduce this in SITL?
It works fine in SITL when configured normally, we are unsure how to simulate a cold GPS fix with SITL.
Hi, Sorry it appears that it actually gets stuck earlier in the AP_DDS_client.cpp code but I had it commented out and forgotten about it:
// check ping const uint64_t ping_timeout_ms{1000}; const uint8_t ping_max_attempts{10}; if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: No ping response, exiting"); // return; }
The return is commented out because otherwise the hardware will stop trying to connect to the DDS client after 10 seconds. This has no bearing on the current issue. The code appears to get stuck in "uxr_ping_agent_attempts". We are theorising that it could be something to do with the locking transport stuff within the "uxr_ping_agent_attempts" function.
Is there any way to reproduce this in SITL?
It works fine in SITL when configured normally, we are unsure how to simulate a cold GPS fix with SITL.
My only suspicion is that time is frozen on the FC, and the loops don't advance on device without GPS. I worked with CubePilot last night on setting up the debugger to reproduce locally on my Cube Orange but ran out of time. I've seen it in https://github.com/eProsima/Micro-XRCE-DDS-Client/issues/350
Hi, Sorry it appears that it actually gets stuck earlier in the AP_DDS_client.cpp code but I had it commented out and forgotten about it:
// check ping const uint64_t ping_timeout_ms{1000}; const uint8_t ping_max_attempts{10}; if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: No ping response, exiting"); // return; }
The return is commented out because otherwise the hardware will stop trying to connect to the DDS client after 10 seconds. This has no bearing on the current issue. The code appears to get stuck in "uxr_ping_agent_attempts". We are theorising that it could be something to do with the locking transport stuff within the "uxr_ping_agent_attempts" function.
Is there any way to reproduce this in SITL?
It works fine in SITL when configured normally, we are unsure how to simulate a cold GPS fix with SITL.
My only suspicion is that time is frozen on the FC, and the loops don't advance on device without GPS. I worked with CubePilot last night on setting up the debugger to reproduce locally on my Cube Orange but ran out of time. I've seen it in eProsima/Micro-XRCE-DDS-Client#350
Okay we will look into that, thankyou for putting your time into this issue!
I've tried reproducing on 6X, and fail to get serial working. 6X has nothing connected except USB. This looks like a hardware-only regression. Sorry, we don't really have automated testing on hardware yet; and despite the current SITL testing that is done, it doesn't cover any of the ChibiOS stuff.
Here's some info on what I've done so far.
./waf configure --enable-dds --board Pixhawk6X
./waf plane --upload
# parameters for mavproxy
DDS_ENABLE 1
SERIAL1_BAUD 115
SERIAL1_PROTOCOL 45
AND
ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -r dds_xrce_profile.xml -D /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02
Result in autopilot:
AP: DDS Client: No ping response, exiting
And, no apparent data in the micro ros agent:
$ ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -r dds_xrce_profile.xml -D /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02
[1700291849.324354] info | TermiosAgentLinux.cpp | init | running... | fd: 3
[1700291849.324839] info | Root.cpp | set_verbose_level | logger setup | verbose_level: 4
[1700291872.071255] info | TermiosAgentLinux.cpp | fini | server stopped | fd: 3
[1700291872.081351] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700291873.089339] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700291874.097161] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700291875.104609] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700291876.112400] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700291877.119291] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700291877.860837] info | TermiosAgentLinux.cpp | init | running... | fd: 3
[1700292086.799159] info | TermiosAgentLinux.cpp | fini | server stopped | fd: 3
[1700292086.809247] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700292087.817031] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700292088.824711] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700292089.832190] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700292090.839454] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700292091.846572] info | TermiosAgentLinux.cpp | init | Serial port not found. | device: /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02, error 2, waiting for connection...
[1700292092.658736] info | TermiosAgentLinux.cpp | init | running... | fd: 3
Also tested back on the following hashes and observed failure:
ef6105c5e0e1265f9f5d5711c17ce2eca1a9f5b4
so it wasn't injected during the recent networking work.fc924857d3949bf26a1cfc4e18ca594a4d1c6a72
which was before Rhys added auto-reconnect
c057cc548576b2003be25aec96403951dc48b5bb
before DDS_ENABLE was default 104ec39eb9f
which is right after the initial merge. At this point, I have a strong suspicion something else is broken aside from the code for me, because I spent time testing (successfully) in hardware then. What's left to test.
$ git log --oneline | grep AP_DDS
47efaf9c62 AP_DDS: Added ROS 2 service support
be5d846af0 AP_DDS: Switch topic to cmd_vel
9b0f485fee AP_DDS: Add velocity control DDS subscriber
01c5f44556 AP_DDS: Add dynamic TF subscriber support
3bb6fb460e AP_DDS: fix reliable stream buffer size
f3a6c71c6b AP_DDS: Update docs for supported topics
2b906bc714 AP_DDS: Fix typo with pts serial port when in UDP
da2beb1ec1 AP_DDS: Improve subscriber safety
8cf855970d AP_DDS: Fix unitialized memory
5168f39463 AP_DDS: Add Subscriber support with Joy
a53cac8241 AP_DDS: Add UDP instructions to README
fd775bf08d AP_DDS: update README
56ed76f479 AP_DDS: add publisher for rosgraph_msgs/msg/Clock
371c19bb32 AP_DDS: rename topic name for builtin_interfaces/msg/Time
c60796a0df AP_DDS: add IDL for rosgraph_msgs/msg/Clock
c044ba67cc AP_DDS: Support single precision hw
57c2753bdd AP_DDS: Add GeoPose support
fbc7a6dd9b AP_DDS: support UDP transport
a654027a45 AP_DDS: update topic names
2298048079 AP_DDS: Add local velocity publisher
171e09d28c AP_DDS: Add local pose publisher
5c696cf18d AP_DDS: Switch to master instead of develop tag
bb6c872138 AP_DDS: Publish NavSatFix as soon as its available
edde5d2e48 AP_DDS: Add developer recommended steps for pre-commit
7ff2a9eec3 AP_DDS: Use mirror of DDS Gen
81bdf40d1f .pre-commit: Enfore code style for AP_DDS
72a693e68e AP_DDS: Switch BatteryState topic to sensor data QOS Resolves #23365 for the BatteryState topic
e1b06a1b99 AP_DDS: Integrate AP_BattMonitor to work with AP_DDS * Edit BatteryState.idl * Add BatteryState to AP_DDS_Topic_table.h * Add BatteryState to the DDS Client * Add voltage * Add temperature * Add current * Add charge * Add capacity with NAN value * Add design_capacity * Add percentage * Add power_supply_status * Add power_supply_health * Add power_supply_technology with 0 value * Add present * Cell_voltage and Serial_number need to be implemented in the future * Did not add cell_temperature as AP_BattMonitor doesn't support it * Did not add location as this is a generic implementation * Parameterize battery instance number
9e9d487442 AP_DDS: Consume covariance implementation in AP_DDS
06d9a08d16 AP_DDS: Remove unused commented code
63ed2c646e AP_DDS: Preserve folder structure and includes for IDL files
80ed6125aa AP_DDS: Add support for static transforms
cdb4012886 Tools: enforce astyle formatting in AP_DDS
ffed6e0f26 AP_DDS: Switch NavSatFix topic to sensor data QOS * Change Reliability to BEST_EFFORT * Change Durability to VOLATILE * Change to smaller queue size on NavSatFix QOS
9633950098 AP_DDS: Use GPS semaphore
a610474cdc AP_DDS: Parametrize the GPS instance number
ee59d527e8 AP_DDS: Fix spelling in participant name
863656b037 AP_DDS: Add multi-topic support with NavSatFix
c983c856d0 .pre-commit: Add xmllint for AP_DDS xml file
80a0373717 AP_DDS: Bump to using latest MicroXRCEDDSGen
cb628e6875 AP_DDS: update readme headers overhaul
dfdd7cde1b AP_DDS: update readme with feedback provided
3c09a9e8aa AP_DDS: update readme bash scripts and tutorial order
04ec39eb9f AP_DDS: Use python3 shebang
0905ffa438 AP_DDS: Add initial DDS Client support
@Ryanf55 running tests on MatekH743-WING (v1) installed into a tilt-rotor VTOL.
Vehicle on bench, has
SERIAL0
mapped to /dev/cu.usbmodem142401
SERIAL2
(TX1/RX1) mapped to /dev/cu.usbserial-0001
SERIAL5
(TX8/RX8) mapped to /dev/cu.usbserial-4
Config and install:
./waf configure --board MatelH743 --enable-dds
./waf plane --upload
SERIAL2_BAUD 57 # 57600
SERIAL2_PROTOCOL 2.0 # MAVLink2
SERIAL5_BAUD 57 # 57600
SERIAL5_PROTOCOL 45.0
./install/micro_ros_agent/lib/micro_ros_agent/micro_ros_agent serial --dev /dev/cu.usbserial-4 --baudrate 57600 --verbose 6 --refs /Users/rhys/Code/ros2/humble/ros2-ardupilot/install/ardupilot_sitl/share/ardupilot_sitl/config/dds_xrce_profile.xml
Connection successful.
Flip the roles of SERIAL2
and SERIAL5
:
SERIAL2_BAUD 57 # 57600
SERIAL2_PROTOCOL 45.0
SERIAL5_BAUD 57 # 57600
SERIAL5_PROTOCOL 2.0 # MAVLink2
./install/micro_ros_agent/lib/micro_ros_agent/micro_ros_agent serial --dev /dev/cu.usbserial-0001 --baudrate 57600 --verbose 6 --refs /Users/rhys/Code/ros2/humble/ros2-ardupilot/install/ardupilot_sitl/share/ardupilot_sitl/config/dds_xrce_profile.xml
correction: initial ping is ok, creation requests fail.
AP: DDS: Init complete
AP: DDS: Participant session request failure
AP: DDS Client: Creation Requests failed
I suspect there may be a timeout in the second case.
Do you see the initial ping in a terminal for the 6x?
Run the below instead of the micro-ROS agent (the line breaks after each ping request are mine):
python -m serial.tools.miniterm /dev/cu.usbserial-0001 57600 --echo --encoding hexlify
--- Miniterm on /dev/cu.usbserial-0001 57600,8,N,1 ---
--- Quit: Ctrl+] | Menu: Ctrl+T | Help: Ctrl+T followed by Ctrl+H ---
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
7E 00 00 10 00 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00 CF 12
Update
I suspect there may be a timeout in the second case.
Confirmed for SiK radio serial connection:
- constexpr uint8_t maxTimeMsPerRequestMs = 250;
+ constexpr uint16_t maxTimeMsPerRequestMs = 500;
Solves the issue of the DDS participant creation failing when using a telemetry radio for the connection.
I did some more testing. Despite having SERIAL1_PROTOCOL set to 45, I still see some GCS status message texts coming out the port. Even if DDS_ENABLE to 0, there is still data being shoved out the port.
Mavlink is hogging the port:
$ mavproxy.py --master /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02
Connect /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02 source_system=255
Log Directory:
Telemetry log: mav.tlog
Waiting for heartbeat from /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02
MAV> Detected vehicle 1:1 on link 0
online system 1
MANUAL> Mode MANUAL
AP: ArduPlane V4.5.0-dev (d625a1b1)
AP: ChibiOS: 3ef1657d
AP: Pixhawk6X 00280021 31325101 39313731
AP: IOMCU: 410 2003 412FC231
AP: RCOut: PWM:1-16
AP: IMU0: fast sampling enabled 2.0kHz
Received 1005 parameters (ftp)
Saved 1005 parameters to mav.parm
Flight battery warning
Can you repeat the same test as Rhys and I?
master
firmware on your Cube orange ./waf configure --board CubeOrange --enable-dds
and ./waf copter --upload
Set the following params to enable DDS at 57K (try this instead of 115k for now), and replace x
number with the serial port you are using for DDS serial traffic on your Cube.
/dev/ttyX
with the serial port that your companion computer uses to talk ROS 2.
python3 -m serial.tools.miniterm /dev/ttyX 57600 --echo --encoding hexlify
Paste the output of 3. If it's what we expect, there should be 10 ping attemps. What I see is Mavlink stomping on the serial traffic and interleaving data which corrupts the stream.
Thanks for all the work on this. Yep, I'll do this and get back to you in 2 hours or so.
@KyleJewiss, if you have a TTL to USB serial adapter another test would be to use a different UART (not one of the ones usually assigned to Telem or GPS) for the DDS data. That may give you a temporary workaround while we determine what is causing the issue Ryan is observing with the USB assigned to SERIAL1.
Tagged this for dev call to ask the team if there is any known reason that SERIAL1_PROTOCOL would be ignored.
Alright, so I rebased to master and I tested both of the serial ports available on the CubeOrange, and when the here3+ gets a hot geofix there is NOTHING at all coming across the DDS Serial port.
➜ ardupilot git:(gama) ✗ python3 -m serial.tools.miniterm /dev/ttyUSB0 57600 --echo --encoding hexlify
--- Miniterm on /dev/ttyUSB0 57600,8,N,1 ---
--- Quit: Ctrl+] | Menu: Ctrl+T | Help: Ctrl+T followed by Ctrl+H ---
When it doesn't get hot geofix it does.
python3 -m serial.tools.miniterm /dev/ttyUSB0 57600 --echo --encoding hexlify
--- Miniterm on /dev/ttyUSB0 57600,8,N,1 ---
--- Quit: Ctrl+] | Menu: Ctrl+T | Help: Ctrl+T followed by Ctrl+H ---
7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58 52 43 45 01 00 01 0F AA AA BB BB 81 00 FC 01 3D 01 7E 00 00 18 00 80 00 00 00 00 01 10 00 58
We have figured out a SUCCESSFUL work around for now. We have added this 5 second delay in AP_DDS_Client.cpp
main_loop.
void AP_DDS_Client::main_loop(void)
{
// Work around to stop DDS & mavlink conflict
hal.scheduler->delay(5000);
if (!init_transport()) {
return;
}
This seems to avoid the mavlink/transport conflict and I get data with GPS hotfix.
One other thing I wanted to mention in case it is important is that we do not have radio connect to the CubeOrange as we do not need it for what we are doing. I don't think it is contributing to the issue but just in case.
On CubeOrange, serial0 and serial6. The first and last are USB. Check the hwdef.daf (see otg and otg2). 2nd one defaults to SLCAN on Orange, but others default to mavlink.
On CubeOrange, serial0 and serial6. The first and last are USB. Check the hwdef.daf (see otg and otg2). 2nd one defaults to SLCAN on Orange, but others default to mavlink.
Sorry, what are you recommending we change the values to?
Sorry, for more context, that was notes from today's dev call.
One reason I couldn't get DDS working over serial was because SERIAL1_PROTOCOL
on most boards is not the 2nd USB interface.
See here for CubeOrange: https://github.com/ArduPilot/ardupilot/blob/69bfe9b8375feb94e657cf99ba3f2809dbfd9f8e/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc#L30-L31
The defaults are MavLink on the second USB because it's configured so: https://github.com/ArduPilot/ardupilot/blob/69bfe9b8375feb94e657cf99ba3f2809dbfd9f8e/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm#L10-L11
Cube Orange+ inherits the hwconfig from CubeOrange: https://github.com/ArduPilot/ardupilot/blob/69bfe9b8375feb94e657cf99ba3f2809dbfd9f8e/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef-bl.dat#L8 https://github.com/ArduPilot/ardupilot/blob/69bfe9b8375feb94e657cf99ba3f2809dbfd9f8e/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat#L9
BUT, it then sets SERIAL5_PROTOCOL to mavlink https://github.com/ArduPilot/ardupilot/blob/69bfe9b8375feb94e657cf99ba3f2809dbfd9f8e/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm#L10-L11
There is no USB serial available for DDS on CubeOrange+ as I was expecting. I was chasing the wrong issue. On Pixhawk6X, I use a different port, but I don't have the connector kit for that board yet (it's shipping since Saturday).
I need to make a cable to test your exact setup. Can you upload your params file and I'll copy wiring from that?
Thank you for that. Here is the parameter file. parameters.zip
@KyleJewiss did you solve this? If not then please ping me on discord and we can look at it together
what is causing the issue Ryan is observing with the USB assigned to SERIAL1.
USB is never assigned to SERIAL1
Bug report
AP_DDS: MicroROS agent doesn't publish topics when GPS automatically gets GPS lock.
We have Ardupilot running on a PX4 with a CubeOrange and a Here3+ GPS. We followed the documentation in the AP_DDS library to setup DDS/MicroROS: https://github.com/ArduPilot/ardupilot/tree/master/libraries/AP_DDS
We got it all working, where the data from the Here3+ could be published as topics to a ROS domain, however this is only the case when the Here3+ starts in a flashing blue "Disarmed with no GPS lock" state. When it is outside it automatically achieves GPS lock and flashes green "Disarmed (ready to arm), GPS lock acquired". See documentation here: https://docs.cubepilot.org/user-guides/here-3/here-3-manual
When the GPS starts without GPS lock the console output looks like the following:
When the GPS starts with GPS lock the console output looks stops as this point. It never publishes any of the topics:
Version 4.5 dev version
Platform [ ] All [ ] AntennaTracker [ ] Copter [ ] Plane [ X ] Rover [ ] Submarine
Hardware type Pixhawk4 with CubeOrange and a Here3+
Logs