Mavlink ACKs "Access Denied" for MAV_CMD_LONG

Hi Folks -

I’m using Copter 3.4.2 on a PixHawk clone and communicating with an embedded platform via MavLink. I’m presently utilizing the binary C MavLink release from GitHub. (BTW oddly MP reports both v3.4.2 and 3.4.1. If I connect briefly to QGC, however it reports 3.4.1…)

Anyway connection to the pixhawk is on Serial4 at 38400 and have verified proper bitrate (within 1%).

I am able to turn on and off the “legacy” datastreams OK (MAVLINK_MSG_ID_REQUEST_DATA_STREAM). However I am unable to set individual stream ID rates: the pixhawk is responding with a MAV_ACK result of 0x3, which from my interpretation of the headers, is a MAV_CMD_ACK_ERR_ACCESS_DENIED, assuming the results are indexed started at 1 (and not zero).

This is the command I am using (PIX_ both set to 1):

mavlink_msg_command_long_send(MAVLINK_COMM_0, PIX_SYSID, PIX_CMPID, MAV_CMD_SET_MESSAGE_INTERVAL, 1, MAVLINK_MSG_ID_GPS_RAW_INT, 500000, 0,0,0,0,0); // 500000uS interval

In my mavlink_bridge_header.h file I have defined:

mavlink_system_t mavlink_system;

And in the main program (where I’m sending the command):

mavlink_system.sysid = 255;
mavlink_system.compid = 1;

On the bus I see (outgoing):

#FE#21#05#FF#01#4C#00#00#C0#41#00#24#F4#48#00#00#00#00#00#00#00#00#00#00#00#00#00#00#00#00#00#00#00#00#FF#01#01#01#01#A8#A1

And response from Pixhawk:

#FE#03#B0#01#01#4D#FF#01#03#44#51

Both of which, if you break down the packets, seem to be in accordance with the header packet structure.

Here is a Pixhawk heartbeat if that offers any clues (sys status etc). I’m bench testing with only pixhawk powered from USB, all sensors/etc connected. However, no RC receiver, GPS only has 5 sats, and prearm error of GPS speed (1.5ish).

#09#3E#01#01#00#11#00#00#00#02#03#59#03#03#B3#D8#FE

A few general questions that I haven’t been able to determine by the MavLink code alone:

  1. When is a heartbeat from the GCS absolutely required (the microcontroller in my case)? My intention is only to monitor streams and initiate a RTL. I have tried the above SET_MESSAGE_INTERVAL with a heartbeat sent from the micro at the same rate of heartbeat receipt (from pixhawk), format below. No change.
  2. What are the recommended MAV_TYPE, MAV_AUTOPILOT, MAV_MODE_FLAG, and MAV_STATE fields in my case? My best guess is (and was):

mavlink_msg_heartbeat_send(MAVLINK_COMM_0, MAV_TYPE_ONBOARD_CONTROLLER, MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_STABILIZE_ENABLED, 0, MAV_STATE_ACTIVE);

3… I know there were more but I’m drawing a blank the moment so I’ll post back!

Thanks for taking the time to read and any insight you may be able to offer. I’ve been at this for longer than I want to admit. :relaxed:

Hi Jamie,

You wrote a lot of information but unfortunately the answer is very simple: ArduPilot doesn’t support the SET_MESSAGE_INTERVAL command (and, as far as I’m aware, no autopilot supports it actually, not even the one who inserted that message into MAVLink and marked the previous method as deprecated).
And this is the answer you are getting back, a 3 corresponding to MAV_CMD_ACK_ERR_NOT_SUPPORTED.

Regarding your other questions:

  1. A heartbeat is mainly necessary if you have enabled GCS failsafe in your vehicle. It is what tells the vehicle that the GCS is still there.
  2. You can look at what other GCS do. For example, MAVProxy, https://github.com/ArduPilot/MAVProxy/blob/master/MAVProxy/mavproxy.py#L699

Hi Francisco -

I’m relieved that I wasn’t doing anything “wrong” however a little frustrating also. I think I’m seeing now that the forks to each individual flight stack can have their own implementations and quirks. I have been using the official MavLink C v1 libraries. A few follow-up questions:

  1. What can you recommend as the most accurate source of protocol information for my situation?
  2. Are the DATA_STREAMs the only way to request sensor data? I though i was being efficient by only requesting streams for the data I needed.
    3)I have been using the binary builds because even though I could get the mavlinkgenerator python script to execute, it seemed to have problem parsing nested defines in the header files (my GCC linker could not resolve large “chunks” of definitions in the generated includes). I didn’t see (at quick glance) any binary builds in the ardupilot git?
    4)I’m a little confused because in the mavlink common.h, the MAV_CMD_ACK defines a 3 as “Access Denied”…? Mavlink: common.h : MAV_CMD_ACK

Thanks again for your time! Onward!

Yes, you always have to check what each flight stack supports. There are many messages, some replacing older ones, others intended to replace older ones but not really doing it, messages that are only present in each of the autopilots dialects, etc.

Trying to answer your questions the best I can:

  1. If you are just looking to support ArduPilot, definitely check our MAVLink repo (https://github.com/ArduPilot/mavlink), it has the most recent message definitions used by ArduPilot (both common.xml and ardupilotmega.xml)
  2. Yes, that’s the way. The issue with the SET_MESSAGE_INTERVAL is that the autopilot would need to maintain a different data rate for each message - not only that wastes memory, but it also means the scheduler has then to follow all those data rates. So although it looks more efficient it isn’t necessarily true.
  3. The ArduPilot build system automatically generates the C library from the message definitions present in the repo I mentioned above.
  4. Well, another MAVLink mess. Sorry about my confusion. What we use is the MAV_RESULT enum.

Thanks for the response - however I fail to see how even the ArduPilot MAVLink repo would have helped - there are still claims that ‘DATA_STREAM’ has been depreciated and that ‘SET_MESSAGE_INTERVAL’ should be used. Considering this is a fork, why do these definitions remain, or why no documentation to alert to this? As a developer who wishes to interface with a device running ArduCopter this is terribly frustrating.

The MAVLink ArduPilot repository original intent was to allow ArduPilot to add new messages to our XML file without having to wait for them to be merged upstream.
The point of having a common XML and one XML file for each autopilot is that not everyone has the same features and sometimes it is hard to get a message in common that suits the needs of all autopilots. Unfortunately in the last few months collaboration in MAVLink has gone lower and lower and one team just adds messages to common whenever they want (deprecating and duplicating stuff). We try to keep common XML file in our fork updated as that is used by all GCS in an equal way. When I said that it has the most recent message definitions I was referring to ardupilotmega.xml, although ArduPilot also uses messages from common.xml.

I understand this is frustrating, but it isn’t ArduPilot’s fault that the DATA_STREAM message was marked as deprecated.

Fair point, and I suspected that this was probably the case, a side effect of forking from an official repo. Thanks for the explanation!

Maybe I didn’t explain properly, but it has nothing to do with ArduPilot having a fork. It has to do with one group of people adding messages (and deprecating others) to a common file without the agreement of the other groups.