Hello there.
Can anyone provide a working example of olympe working with mavlink or at least some resources to begin with?
Hi there,
I created a file “test.mavlink” that contains a take off, 2 waypoints and a landing:
QGC WPL 120
0 1 3 22 15.000000 0.000000 0.000000 nan 48.878601 2.366549 15.000000 1
1 0 3 16 0.000000 0.000000 0.000000 0.000000 48.879000 2.366549 20.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 48.879139 2.367296 10.000000 1
3 0 3 21 0.000000 0.000000 0.000000 nan 48.879139 2.367296 0.000000 1
Considering that you have already launched Sphinx and an anafi firmware, you can start a flightplan as follows:
import olympe
from olympe.messages.common.Mavlink import Start
from olympe.messages.common.MavlinkState import (
MavlinkFilePlayingStateChanged,
MissionItemExecuted,
)
import requests
import os
drone_ip = "10.202.0.1"
headers = {
"Accept": "application/json, text/javascript, text/plain */*; q=0.01",
"X-Requested-With": "XMLHttpRequest",
"Content-type": "application/json; charset=UTF-8; application/gzip",
}
drone = olympe.Drone(drone_ip)
drone.connect()
# Upload mavlink file
with open("test.mavlink", "rb") as data:
resp = requests.put(
url=os.path.join("http://", drone_ip, "api/v1/upload", "flightplan"),
headers=headers,
data=data,
)
# Start flightplan
expectation = drone(
Start(resp.json(), type="flightPlan")
>> MissionItemExecuted(idx=0.0)
>> MissionItemExecuted(idx=1.0)
>> MissionItemExecuted(idx=2.0)
>> MissionItemExecuted(idx=3.0)
>> MavlinkFilePlayingStateChanged(state="stopped")
).wait(_timeout=200)
assert expectation
FlightPlan documentation is available here: GroundSdk FlightPlan Documentation — MAVLink-flightplan 1.2.1 documentation
Olympe/ARSDK messages documentation is available here: Home - Olympe 1.8.0 documentation
Best regards
Dear priols
Thank you very much for your example, it gives a very good insight/starting point for the mavlink usage.
Although, I don’t if this is irrelevant can you also use mavlink to get the telemetry data of the drone?
Thanks a lot
Hi @iou,
If you are using Sphinx, there are several tools for telemetry recording/visualization. You can take a look here: How to watch flight information — Parrot-Sphinx 1.2.1 documentation
Also some ARSDK messages are telemetry oriented: AltitudeChanged, SpeedChanged…
Example below:
import olympe
from olympe.messages.ardrone3.Piloting import (
TakeOff,
Landing)
from olympe.messages.ardrone3.PilotingState import (
FlyingStateChanged, AltitudeChanged)
drone_ip = "10.202.0.1"
drone = olympe.Drone(drone_ip)
drone.connect()
# Start flightplan
expectation = drone(
TakeOff()
>> FlyingStateChanged(state="hovering")
>> AltitudeChanged(altitude=1.0, _float_tol=(1e-7, 0.2))
>> Landing()
>> FlyingStateChanged(state="landed")
).wait(_timeout=20)
assert expectation
Dear @priols,
Thank you again for your immideate and very usefull response.
You have been very helpfull
Actually, I was also looking for a real-drone implementation
Best regards
This topic was automatically closed 2 days after the last reply. New replies are no longer allowed.