Skip to content

Commit

Permalink
mavutil is imported from pymavlink and not dronekit
Browse files Browse the repository at this point in the history
  • Loading branch information
maxlou05 committed Aug 22, 2024
1 parent 1c001ea commit 5606c91
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 11 deletions.
7 changes: 4 additions & 3 deletions mavlink/modules/flight_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import time

from .. import dronekit
from pymavlink import mavutil

from . import drone_odometry

Expand All @@ -16,9 +17,9 @@ class FlightController:

__create_key = object()

__MAVLINK_LANDING_FRAME = dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL
__MAVLINK_LANDING_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_LAND
__MAVLINK_WAYPOINT_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_WAYPOINT
__MAVLINK_LANDING_FRAME = mavutil.mavlink.MAV_FRAME_GLOBAL
__MAVLINK_LANDING_COMMAND = mavutil.mavlink.MAV_CMD_NAV_LAND
__MAVLINK_WAYPOINT_COMMAND = mavutil.mavlink.MAV_CMD_NAV_WAYPOINT

@classmethod
def create(cls, address: str, baud: int = 57600) -> "tuple[bool, FlightController | None]":
Expand Down
9 changes: 5 additions & 4 deletions mavlink/test_mission_ended.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import time

from mavlink import dronekit
from pymavlink import mavutil

from mavlink.modules import flight_controller

Expand All @@ -13,10 +14,10 @@
MISSION_PLANNER_ADDRESS = "tcp:127.0.0.1:14550"
TIMEOUT = 1.0 # seconds

MAVLINK_TAKEOFF_FRAME = dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT
MAVLINK_TAKEOFF_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_TAKEOFF
MAVLINK_FRAME = dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT
MAVLINK_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_WAYPOINT
MAVLINK_TAKEOFF_FRAME = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT
MAVLINK_TAKEOFF_COMMAND = mavutil.mavlink.MAV_CMD_NAV_TAKEOFF
MAVLINK_FRAME = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT
MAVLINK_COMMAND = mavutil.mavlink.MAV_CMD_NAV_WAYPOINT

ALTITUDE = 10 # metres
ACCEPT_RADIUS = 10 # metres
Expand Down
11 changes: 7 additions & 4 deletions requirements.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,18 @@ pytest
opencv-python
numpy

# Module lte
# Module image-encoding
Pillow

# Module qr
pyzbar

# Module kml
simplekml

# Module mavlink
pymavlink

# Module qr
pyzbar

# Linters and formatters are explicitly versioned
black==24.2.0
flake8-annotations==3.0.1
Expand Down

0 comments on commit 5606c91

Please sign in to comment.