RockBLOCK (Iridium SBD) and Mission Planner

I’ve been attempting to set up the RockBLOCK Iridium modem with a Cube Orange running ArduPilot 4.4 as per this page from the documentation and the Github repo from @stephendade :
https://ardupilot.org/copter/docs/common-telemetry-rockblock.html

From what I can see, the connections to Rock7 and Adafruit IO are being made, and the flight controller is in fact transmitting over the RockBLOCK when it has a connection to the satellite network. However, I haven’t been able to get any ground control software to connect. I’ve tried Mission Planner and QGroundControl, both of which time out even if the Python script is sending data in that very moment. “High latency” is checked in QGC, and I don’t see such an option in MP. Occasionally, in the terminal window where I’m running rockblock2mav.py, I’ll see several duplicates of the “Checking for GCS packets” message while the GCS tries to connect, but the connection never succeeds. Otherwise, the output looks like this:
image

I’ve tried modifying the Python script to remove the checks for new data, so that the script is constantly sending the old data as if it were new, but this only helps me connect on MAVProxy. QGC and Mission Planner still refuse to read the received packets. Has anyone encountered this issue with the RockBLOCK, or otherwise been able to connect over Iridium SBD?

So you can see the data changing in adafruit.io?

Also: Is the correct time and timezone set on your system?

That’s correct, the data updates in Adafruit IO.

I verified that the time and timezone are correct on my computer and also tried switching to UTC as that’s the format in which the script displays the time. Now I am receiving a new error in Mission Planner and no change in QGC:

I’ve added a patch to the GitHub - stephendade/rockblock2mav: RockBlock to MAVLink gateway repo to output additional debugging text for the packet time check. Could you give it a run and post the output?

Here’s the output. The first “Got new packet” line is without a GCS application connected. The second one corresponds to the same error in Mission planner I posted earlier, when that error is thrown.

Checking for new packet at 2023-06-23, 13:44:45
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:44:49
Got new packet, coords 28.019,-81.749. Received at 2023-06-23 13:44:41 UTC
HIGH_LATENCY2 {timestamp : 481688, type : 2, autopilot : 3, custom_mode : 0, latitude : 0, longitude : 0, altitude : 0, target_altitude : 0, heading : 168, target_heading : 0, target_distance : 0, throttle : 0, airspeed : 0, airspeed_sp : 0, groundspeed : 0, windspeed : 0, wind_heading : 0, eph : 0, epv : 0, temperature_air : 35, climb_rate : 0, battery : 99, wp_num : 0, failure_flags : 65, custom0 : 1, custom1 : 0, custom2 : 0}
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:44:53
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:44:58
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:02
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:05
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:08
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:11
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:14
Got new packet, coords 28.0023,-81.7548. Received at 2023-06-23 13:45:05 UTC
HIGH_LATENCY2 {timestamp : 501789, type : 2, autopilot : 3, custom_mode : 0, latitude : 0, longitude : 0, altitude : 0, target_altitude : 0, heading : 168, target_heading : 0, target_distance : 0, throttle : 0, airspeed : 0, airspeed_sp : 0, groundspeed : 0, windspeed : 0, wind_heading : 0, eph : 0, epv : 0, temperature_air : 35, climb_rate : 0, battery : 99, wp_num : 0, failure_flags : 65, custom0 : 1, custom1 : 0, custom2 : 0}
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:18
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:21
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:24
Checking for GCS packets
Sleeping 2
Checking for new packet at 2023-06-23, 13:45:27
Got new packet, coords 28.019,-81.749. Received at 2023-06-23 13:45:22 UTC
HIGH_LATENCY2 {timestamp : 521794, type : 2, autopilot : 3, custom_mode : 0, latitude : 0, longitude : 0, altitude : 0, target_altitude : 0, heading : 168, target_heading : 0, target_distance : 0, throttle : 0, airspeed : 0, airspeed_sp : 0, groundspeed : 0, windspeed : 0, wind_heading : 0, eph : 0, epv : 0, temperature_air : 35, climb_rate : 0, battery : 99, wp_num : 0, failure_flags : 65, custom0 : 1, custom1 : 0, custom2 : 0}
Checking for GCS packets
Traceback (most recent call last):
  File "C:\Users\Kevin\Desktop\rockblock2mav_debug\rockblock2mav\rockblock2mav.py", line 136, in <module>
    data, addr = UDPClientSocket.recvfrom(UDP_MAX_PACKET_LEN)
                 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
ConnectionResetError: [WinError 10054] An existing connection was forcibly closed by the remote host

I’ve done some tests with GQC and Mission Planner. Unfortunately, the rockblock2mav.py script was not working with either. It only worked with MAVProxy.

Mission Planner expects HEARTBEAT packets when establishing a new link. As there’s none of these packets sent over the Rockblock link, Mission Planner bugs out.

QGC only does udpin links, not udpout. I’ve now fixed this.

So, try it with QGC and let me know if you’re still having issues.

the lastest version should accept high latency as well. it does nothing to limit traffic however

I was able to connect briefly with QGC when the transmission interval is 30s, but QGC seems to give up after a few of those intervals are missed. I could receive data in that moment, but commands sent to change the flight mode had no effect. The MT message from QGC to Rock7 was confirmed through Rock7’s control panel, so I assume it has something to do with how that message is being translated on the flight controller end.
Additionally, it’s worth noting that any missing parameters or hardware will cause QGC to refuse a connection. I was initially trying to test this setup without a fully assembled drone, but that did not work. Just a side note if anyone else is trying to do something similar.
I appreciate your help, @stephendade ! I don’t know however if I would rely on this setup in its current state.

Thanks for the report. I’ve added this to the 4.4 issues list for tracking purposes.

@stephendade, hopefully we can get this resolved but if not, we probably need to add a warning to the wiki.

Did you check the “High Latency mode” option in the QGC connection settings?

Also, I’ve found the Rockblock doesn’t work well indoors. It does need to be outside with a good view of the sky to work reliably.

Turns out QGC uses a different MAVLink message for flight mode changes. I’ve put in a patch for this at AP_Scripting: Add SET_MODE support for Rockblock lua script by stephendade · Pull Request #24172 · ArduPilot/ardupilot · GitHub

What was the exact message QGC gave you when it refused the connection?

Try setting the RCK_DEBUG parameter to 1. That will give you debugging information over a (normal) MAVLink connection.

I’ve fixed the QGC modes in the above PR. Mission Planner is definitely a no-go at this point in time. QGC also doesn’t show the correct arm/disarm status.

These issues are on the GCS-side, as Mission Planner, QGC and MAVProxy have all slightly different implementations of High Latency connections :frowning:

1 Like

High Latency mode was enabled in QGC for all of this testing, and all of it took place outdoors, with clear skies. I will have to try the patched version of QGC.
Pardon the poor phrasing. When I say “refuse a connection”, I just mean that the connection attempt timed out. Setting RCK_DEBUG allowed me to confirm that messages were being sent from the Rockblock, but gave me no information on the GCS end as to why this prevented the establishment of a connection.
Again, I appreciate the support!

I’m using QGC 4.2.6.

With the High Latency connection, I get a “Vehicle did not respond to command: MAV_CMD_CONTROL_HIGH_LATENCY” message after a few minutes. I just click “OK” to dismiss.

During this time, QGC is definitely getting packets. I’m getting the vehicle’s position on the map and the correct flight mode.