Mavlink land command to Parrot Anafi or Sphinx not working

Hi,
I’ve set up a tool to send mavlink messages to an ip with ports (ie it can work with the parrot anafi or the parrot sphinx simulator). I can arm the autopilot and make either successfully take off, but the land command does nothing, even if the command ack is returned with value 0 (command accepted). What might I be doing wrong? Anyone had experience getting this to land using mavlink commands?

Do you have some log ?

@Jerome do you need a log of the messages? Or something from the drone/sim (you’d have to tell me how to get that in that case)

I’ve also encountered this problem when using Mavlink, besides the problems mentioned here, with both the Sphinx and real ANAFI 4K drone. This happens with both custom implementation and QGroundControl app (both mobile and desktop versions).

I can also provide logs, if necessary. But I need to know where to get them from.

Hello,
MAV_CMD_LAND and MAV_CMD_TAKEOFF are mission commands and are not taken into account by anafi in its live messages (still “accepting” the land).
takeoff is done either by issuing some manual gaz commands or changing the flight mode to
PX4_CUSTOM_MAIN_MODE_AUTO | PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF
symetrically, the landing is performed using:
PX4_CUSTOM_MAIN_MODE_AUTO | PX4_CUSTOM_SUB_MODE_AUTO_LAND

1 Like

Just finished testing. Looks like it works.

For reference, this is how I did it:

    // constants not available to me, so I hardcoded them
    // feel free to replace these with the ones from mavlink
    const uint32_t PX4_CUSTOM_MAIN_MODE_AUTO = 4;
    const uint32_t PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF = 2;
    const uint32_t PX4_CUSTOM_SUB_MODE_AUTO_LAND = 6;

    const uint8_t base_mode = 0;

    // use either PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF for takeoff
    // or PX4_CUSTOM_SUB_MODE_AUTO_LAND for landing
    const uint32_t custom_mode =
        (PX4_CUSTOM_MAIN_MODE_AUTO << 16) |
        (PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF << 24);

    mavlink_message_t msg{};
    mavlink_msg_set_mode_pack(
        system_id,
        MAV_COMP_ID_AUTOPILOT1,
        &msg,
        target_system_id,
        base_mode,
        custom_mode);

    connection->send(&msg);

Thanks lbanda!

2 Likes

This topic was automatically closed after 30 days. New replies are no longer allowed.