Reading of MAV_LANDED_STATE from MAVLink

Hey to all,

Im working on the PhotoGrammetry solution device for PixHawk, and fighting with MAVLink (or maybe more with my PixHawk 2.4.8 (china clone) running on FW 3.3.3 (latest FW does not work properly at all)

I need to get the current status of the drone, like “ON_GROUND” or “IN_FLIGHT” from Telem1/2 port via MAVLink protocol.

Only MSG_ID which should contain this info is:
EXTENDED_SYS_STATE message with MAV_LANDED_STATE enum, but I’m not able to get these messages to be sent via Telem1/2 port.

Requesting of data stream does not work (ACK returns 3 - UNSUPPORTED), and in the manual configuration, I did not find any item which will enable sending of this message ID → did I miss something?

Code I tried to request data_stream:

#1)

mavlink_message_t command;
mavlink_command_long_t c;

c.param1 = EXTENDED_SYS_STATE;
c.param2 = 1000;
c.command = MAV_CMD_SET_MESSAGE_INTERVAL;
c.target_system = 1;
c.target_component = 0;

mavlink_msg_command_long_encode(255, 0, &command, &c);
write(uartA_strm, &command, sizeof(command));

#2)
mavlink_message_t command;
mavlink_request_data_stream_t rq;

rq.req_message_rate=1;
rq.req_stream_id = EXTENDED_SYS_STATE;
rq.start_stop = 1;

mavlink_msg_request_data_stream_encode(255, 0, &command, &rq);
write(uartA_strm, &command, sizeof(command));

Can somebody give some hint on how to recognize that drone is flying or on the ground?

I would go with #1):

mavlink_message_t message;
mavlink_command_long_t c;

c.param1 = EXTENDED_SYS_STATE;
c.param2 = 1000;
c.command = MAV_CMD_SET_MESSAGE_INTERVAL;
c.target_system = 1;
c.target_component = MAV_COMP_ID_AUTOPILOT1;

mavlink_msg_command_long_encode(255, MAV_COMP_ID_UART_BRIDGE, &message, &c);

uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t  send_len = mavlink_msg_to_send_buffer(buffer, &message);
write(uartA_strm, &message, send_len);

So what I changed is:

  • Send message to component 1!
  • Set your own component ID != 0, e.g. 241 for a UART_BRIDGE.
  • Make sure to serialize message for buffer.
  • Send correct len of buffer over wire.

If you don’t want to deal with all this MAVLink pain, just use the Dronecode SDK:
https://sdk.dronecode.org/en/

You need this method:
https://sdk.dronecode.org/en/api_reference/classdronecode__sdk_1_1_telemetry.html#classdronecode__sdk_1_1_telemetry_1a2f22522ddfde00b97dbfad84864a1730

FW3.3.3 is an old Arducopter firmware. DroneCode SDK won’t work with that firmware, although DroneKit will.
For help with ArduPilot/Arducopter better to visit discuss.ardupilot.org

1 Like

Thanks for reply to both of you. I have already solved a communication issue remarked by Julian (missing target system & component was the issue).

Unfortunately, I still did not found any way to receive the EXTENDED_SYS_STATE message with MAV_LANDED_STATE enum. Any suggestion?
Now I’m reading the state of drone from HeartBeat packets, however, it’s bit confusing, because PixHawk sends system_status as 4 - active -> motors active, few seconds after startup even it’s not active, then it turns to 3 - StandBy.

I think you’ll find that EXTENDED_SYS_STATE isn’t supported in the firmware you’re using: you won’t receive it because it will never be sent