Local position estimation and fine-control not available on either Mavlink or ARSDK

Hello,

I am trying to use either Mavlink or ARSDK to control the drone and fetch the local position (not GPS) on both Linux and Windows, but without success.

What we tried and what we managed to discover:

  • Mavlink – was the first thing we tried since it was advertised as being available on multiple operating systems, including Linux and Windows

    1. We were able to connect to the drone, receive data and send data (on Windows, probably works on Linux too)
    2. The drone was controllable, albeit not in a precise way (!)
    3. Position of the drone in local coordinates is available, based on internal calculation
  • ARSDK – I booted up a virtual machine with Ubuntu where I managed to make a wrapper over ARSDK

    1. We were able to connect to the drone, receive data and send data
    2. The drone was controllable in a precise way, exactly like we wanted
    3. No local position, unfortunately, only GPS available (!)

Our problem is that, since we want to control the drone indoors, we need both local position (no GPS) and the ability to control the drone in a precise manner. We could not do both using any of the SDKs. Since each SDK can do only one of them, we deduced that it should be possible to achieve what we want. Since it should be possible, I thought I am missing something in regards to both SDKs so that was the reason why I asked about Mavlink on the developer forum (linked below).

Looking at the Olympe documentation (which, as far as I understand, is a wrapper over ARSDK) I could not see anything in regards to a local position that we could receive and use. Using both ARSDK and Mavlink in parallel to use what we need from each one seems also impossible, based on the discussions on the developer forum.

Also, to estimate the position ourselves we would need access to IMU and the camera which is oriented downards. Reading on the forum, the front camera also has a small delay, which might make it difficult to use for position estimation. And, I’ve seen no messages with IMU data on both Mavlink and ARSDK, so that is also unavailable to us.

Our questions from us would be:

  1. Is there a way to receive local position (which is available on Mavlink already) on ARSDK?
  2. Is there a way to send commands that can control the drone in a precise manner? For details, you can check this thread: Unable to fine-control (simulated) ANAFI 4K drone using Mavlink

If not, is there any chance that one of these will be available in a future (hopefully soon) release? The Mavlink way of command as it is now seems odd to me.

Thanks.

Hello,
this is the list of MAVLink live piloting command we support : [MAVLINK] List of supported commands - Live piloting

Could you post some code sample of what you are trying to do? This is still not very clear on our side …
.

  • Mavlink

    1. how do you achieve that ? did you write some script?
    2. what does that mean?
    3. what is “local coordinates”? Internal calculation?
  • ARSDK – I booted up a virtual machine with Ubuntu where I managed to make a wrapper over ARSDK → please post some sample code.

    1. OK
    2. Ok
    3. again, what is "local position ?

The only framework we officially support are GroundSDK (for mobile apps) and OLYMPE (python framework for Linux only).

Hello,

this is the list of MAVLink live piloting command we support : [MAVLINK] List of supported commands - Live piloting

That’s what I used as a reference for my implementation of Mavlink wrapper.

  • Mavlink
    1. how do you achieve that ? did you write some script?
    2. what does that mean?
    3. what is “local coordinates”? Internal calculation?

Using mavgen from the official site of Mavlink, I generated the C headers for an implementation. Using these headers, I built a C++ wrapper where I receive, parse and use the LOCAL_POSITION_NED packet, which contains the local coordinates I am referring to, and which is based on internal calculations made on the drone (by Parrot, since I just read and use them). This works.

Regarding 2nd point, I made the thread Unable to fine-control (simulated) ANAFI 4K drone using Mavlink. The code which I use to command the drone looks like this:

void move3D(int16_t vx, int16_t vy, int16_t vz, int16_t vr)
{
    // No buttons supported yet.
    const uint16_t buttons = 0;

    mavlink_message_t message;
    mavlink_msg_manual_control_pack(
        m_system_id,
        MAV_COMP_ID_AUTOPILOT1,
        &message,
        m_target_system_id,
        vx,
        vy,
        vz,
        vr,
        buttons);

    // Send packet to drone using mavlink
    connection->send(&message);
}

The code above sends the supported (as per the thread you mentioned) command MANUAL_CONTROL.

To explain again the issue, let’s take for example the z axis since it’s the easiest (it is the same for every axis). On z axis, a value between 350 and 650 for vz keeps the drone hovering. I was expecting only a value of 500 to do that, and a value of 501 to make the drone ascend as slow as possible, which is not the case. Only a value of 651 makes the drone ascend, but the speed at which the drone does that is about 0.6m/s, which is a lot and this is our issue. Using ARSDK (or FreeFlight6/the controller), I can command the drone to start to ascend at way lower speeds, so it is possible physically.

Basically, we want to be able to use those values between 501 and 651 to command the drone at lower speeds (lower than 0.6m/s on z, for example). Or, the value 651 should command the drone to start ascending at a way lower speed.

  1. again, what is "local position ?

I was referring to the position available on Mavlink as LOCAL_POSITION_NED. It is a set of coordinates on all 3 axis, which has the origin where the drone starts. I could not find anything similar in ARSDK, but I am not certain it does not exists. This is why I asked about it.

The only framework we officially support are GroundSDK (for mobile apps) and OLYMPE (python framework for Linux only).

I also tried to write a simple script in Python using Olympe to try and command the drone, and it worked. I read the documentation available for it. Again, I could not find how to read the local position mentioned above. Looking at the source code, I can see it uses ARSDK, so I assumed I could also use ARSDK and not make a binding to the python API (as I’ve seen suggested in another threads).

If there’s still things that are unclear, I can try to explain them further.
Thanks.

1 Like

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