Open MariusBeul opened 2 years ago
Second part, after @, is a remote address, so it should be like that: udp://:14555@<ap>:14550
.
/mavlink/to
will be silent if you don't use gcs_proxy node. Plugins directly talks to fcu link on ROS 1.
Hello vooon, thank you for the comment. I tried
udp://:14555@<ap>:14550
, but no connection could be established. However, when I tried
udp://:14550@<ap>:14555
(ports changed) at least data from the drone to MAVROSwas transmitted. No heartbeat arrived at the drone from MAVROS though.
Is there a proven technique how I can check if (and which) UDP packets are sent from the PC running MAVROS?
I have an update on this topic: Indeed a connection is established and data is send from MAVROS to Rosettadrone 2 , but it does not contain valid fields. When I bytewise decode the message that arrives at Rosettadrone 2 from QGroundcontrol, they look as follows: 254,9,182,255,190,0,0,0,0,0,6,8,192,4,3,75,225 with the structure (startbyte, length, sequence, sysid, compid, msgid, 9 byte payload, 2 byte checksum) which corresponds to a heartbeat message with #0. If I do the same with MAVROS, messages look like 253,9,0,0,10,240,0,0,0,0,0,0,0,0,18,8,192,4,3,226,167 with an unknown structure. My insights (with zero-based counting): Byte 4 is continually increasing so I suspect it to be a sequence. Bytes 19 and 20 are supposedly a checksum again since they change with every message. The remaining bytes stay constant. The last 5 bytes before the checksum are the same in both messages and part of the payload. Bytes 5 and 6 are sysid and compid. I wonder why the Startbyte is different. Also why is the message 4 bytes longer although byte 1 says 9?
First byte 0xFD is a framing marker of MAVLink version 1, 0xFE - MAVLink version 2. Version 2 has bigger header: https://mavlink.io/en/guide/serialization.html
MAVLink 2 was in all major APs for a while, so mavros just defaults to it.
But as i see, you use some older implementation, which only speaks v1, so i suggest to set fcu_protocol: "v1"
in your params file.
Thank you for the answer! Apparently, setting fcu_protocol: "v1.0"
doesn't change anything. Still MAVLINK 2 packets arrive at the AP. After some research, I think this issue refers to the same problem.
Somehow the fcu_protocol
parameter doesn't work.
https://github.com/mavlink/mavros/blob/master/mavros/src/lib/mavros.cpp#L58 code still there. Could you please check again that you set /mavros/fcu_protocol := "v1.0"
before node startup?
I correctly set the parameter. Also I could confirm that the flag is correctly set here (flag == 0 || 2, depending on the version). MAVLINK 2 messages are sent to the AP independently of the flag. Rolling back to versions
mavros: release 0.32.0
mavlink: release 2020.2.2-1
as suggested in the other thread resolved the issue. However, switching to MAVLINK 1 in the current master implementation doesn't work for me.
Issue details
My connection looks like this: Rosettadrone 2 <-UDP-> MAVROS I can receive data from the drone but cannot publish anything with MAVROS. No heartbeat arrives at the drone. If I use Qgroundcontrol instead of MAVROS (Rosettadrone 2 <-UDP-> QGroundcontrol), the bidirectional UDP connection works and also the heartbeat comes through. The telemetry port in Rosettadrone 2 is set to 14550. I tried many different fcu_urls and receiving data works for example with
fcu_url:=udp://:14550@:14555/?ids=255,1" fcu_url:=udp://:14550@ fcu_url:=udp://:14550@:33749
The gcs_url is empty. Many messages arrive on the "/mavlink/from" topic, but on "/mavlink/to" nothing is published. Shouldn't I see the heartbeat from MAVROS here?
Am I doing something wrong connectionwise? Thank you for your support!
MAVROS version and platform
Mavros: The version that comes with ros-melodic-mavros and the current master branch. ROS: Melodic Ubuntu: 18.04
Autopilot type and version
[X] ArduPilot [ ] PX4
Version: ?3.7.1?
Node logs
Diagnostics
Check ID