Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed Errors! #1209

Open
wants to merge 19 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
39 changes: 39 additions & 0 deletions .github/workflows/python-publish.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
# This workflow will upload a Python Package using Twine when a release is created
# For more information see: https://docs.github.com/en/actions/automating-builds-and-tests/building-and-testing-python#publishing-to-package-registries

# This workflow uses actions that are not certified by GitHub.
# They are provided by a third-party and are governed by
# separate terms of service, privacy policy, and support
# documentation.

name: Upload Python Package

on:
release:
types: [published]

permissions:
contents: read

jobs:
deploy:

runs-on: ubuntu-latest

steps:
- uses: actions/checkout@v3
- name: Set up Python
uses: actions/setup-python@v3
with:
python-version: '3.x'
- name: Install dependencies
run: |
python -m pip install --upgrade pip
pip install build
- name: Build package
run: python -m build
- name: Publish package
uses: pypa/gh-action-pypi-publish@27b31702a0e7fc50959f5ad993c78deac1bdfc29
with:
user: __token__
password: ${{ secrets.PYPI_API_TOKEN }}
97 changes: 31 additions & 66 deletions dronekit/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,7 @@
----
"""

import sys
import collections

# Python3.10 removed MutableMapping from collections:
if sys.version_info.major == 3 and sys.version_info.minor >= 10:
from collections.abc import MutableMapping
else:
from collections import MutableMapping

import copy
import logging
import math
Expand Down Expand Up @@ -228,25 +220,6 @@ def __str__(self):
return "GPSInfo:fix=%s,num_sat=%s" % (self.fix_type, self.satellites_visible)


class Wind(object):
"""
Wind information

An object of this type is returned by :py:attr: `Vehicle.wind`.

:param wind_direction: Wind direction in degrees
:param wind_speed: Wind speed in m/s
:param wind_speed_z: vertical wind speed in m/s
"""
def __init__(self, wind_direction, wind_speed, wind_speed_z):
self.wind_direction = wind_direction
self.wind_speed = wind_speed
self.wind_speed_z = wind_speed_z

def __str__(self):
return "Wind: wind direction: {}, wind speed: {}, wind speed z: {}".format(self.wind_direction, self.wind_speed, self.wind_speed_z)


class Battery(object):
"""
System battery information.
Expand Down Expand Up @@ -1084,19 +1057,6 @@ def listener(_, msg):
self._vy = None
self._vz = None


self._wind_direction = None
self._wind_speed = None
self._wind_speed_z = None

@self.on_message('WIND')
def listener(self,name, m):
""" WIND {direction : -180.0, speed : 0.0, speed_z : 0.0} """
self._wind_direction = m.direction
self._wind_speed = m.speed
self._wind_speed_z = m.speed_z


@self.on_message('STATUSTEXT')
def statustext_listener(self, name, m):
# Log the STATUSTEXT on the autopilot logger, with the correct severity
Expand Down Expand Up @@ -1182,17 +1142,21 @@ def listener(vehicle, name, m):
# All keys are strings.
self._channels = Channels(self, 8)

@self.on_message(['RC_CHANNELS_RAW', 'RC_CHANNELS'])
@self.on_message('RC_CHANNELS_RAW')
def listener(self, name, m):
def set_rc(chnum, v):
'''Private utility for handling rc channel messages'''
# use port to allow ch nums greater than 8
port = 0 if name == "RC_CHANNELS" else m.port
self._channels._update_channel(str(port * 8 + chnum), v)

for i in range(1, (18 if name == "RC_CHANNELS" else 8)+1):
set_rc(i, getattr(m, "chan{}_raw".format(i)))

self._channels._update_channel(str(m.port * 8 + chnum), v)

set_rc(1, m.chan1_raw)
set_rc(2, m.chan2_raw)
set_rc(3, m.chan3_raw)
set_rc(4, m.chan4_raw)
set_rc(5, m.chan5_raw)
set_rc(6, m.chan6_raw)
set_rc(7, m.chan7_raw)
set_rc(8, m.chan8_raw)
self.notify_attribute_listeners('channels', self.channels)

self._voltage = None
Expand Down Expand Up @@ -1249,7 +1213,7 @@ def listener(self, name, m):
@self.on_message('HEARTBEAT')
def listener(self, name, m):
# ignore groundstations
if m.type == mavutil.mavlink.MAV_TYPE_GCS or (not self._handler.master.probably_vehicle_heartbeat(m)):
if m.type == mavutil.mavlink.MAV_TYPE_GCS:
return
self._armed = (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED) != 0
self.notify_attribute_listeners('armed', self.armed, cache=True)
Expand Down Expand Up @@ -1279,14 +1243,19 @@ def listener(self, name, msg):
if not self._wp_loaded:
self._wploader.clear()
self._wploader.expected_count = msg.count
self._master.waypoint_request_send(0)
# self._master.waypoint_request_send(0)
self._master.mav.mission_request_int_send(
target_system=self._master.target_system,
target_component=self._master.target_component,
seq=0 # Sequence number of the mission item to request
)

@self.on_message(['HOME_POSITION'])
def listener(self, name, msg):
self._home_location = LocationGlobal(msg.latitude / 1.0e7, msg.longitude / 1.0e7, msg.altitude / 1000.0)
self.notify_attribute_listeners('home_location', self.home_location, cache=True)

@self.on_message(['WAYPOINT', 'MISSION_ITEM'])
@self.on_message(['WAYPOINT', 'MISSION_ITEM', 'MISSION_ITEM_INT'])
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There is a bug if It is a mission item int then you should divide to 1e7

def listener(self, name, msg):
if not self._wp_loaded:
if msg.seq == 0:
Expand All @@ -1303,13 +1272,18 @@ def listener(self, name, msg):
self._wploader.add(msg)

if msg.seq + 1 < self._wploader.expected_count:
self._master.waypoint_request_send(msg.seq + 1)
# self._master.waypoint_request_send(msg.seq + 1)
self._master.mav.mission_request_int_send(
target_system=self._master.target_system,
target_component=self._master.target_component,
seq=msg.seq + 1 # Sequence number of the mission item to request
)
else:
self._wp_loaded = True
self.notify_attribute_listeners('commands', self.commands)

# Waypoint send to master
@self.on_message(['WAYPOINT_REQUEST', 'MISSION_REQUEST'])
@self.on_message(['WAYPOINT_REQUEST', 'MISSION_REQUEST', 'MISSION_REQUEST_INT'])
def listener(self, name, msg):
if self._wp_uploaded is not None:
wp = self._wploader.wp(msg.seq)
Expand Down Expand Up @@ -1413,7 +1387,7 @@ def listener(_):
@self.on_message(['HEARTBEAT'])
def listener(self, name, msg):
# ignore groundstations
if msg.type == mavutil.mavlink.MAV_TYPE_GCS or (not self._handler.master.probably_vehicle_heartbeat(msg)):
if msg.type == mavutil.mavlink.MAV_TYPE_GCS:
return
self._heartbeat_system = msg.get_srcSystem()
self._heartbeat_lastreceived = monotonic.monotonic()
Expand Down Expand Up @@ -1718,15 +1692,6 @@ def listener(self, attr_name, value):
"""
return self._location

@property
def wind(self):
"""
Current wind status (:pu:class: `Wind`)
"""
if self._wind_direction is None or self._wind_speed is None or self._wind_speed_z is None:
return None
return Wind(self._wind_direction, self._wind_speed, self._wind_speed_z)

@property
def battery(self):
"""
Expand Down Expand Up @@ -2233,7 +2198,7 @@ def simple_goto(self, location, airspeed=None, groundspeed=None):
else:
raise ValueError('Expecting location to be LocationGlobal or LocationGlobalRelative.')

self._master.mav.mission_item_send(0, 0, 0, frame,
self._master.mav.mission_item_int_send(0, 0, 0, frame,
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2, 0, 0,
0, 0, 0, location.lat, location.lon,
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

conversion issu int(location.lat * 1e7), int(location.lon * 1e7)

alt)
Expand Down Expand Up @@ -2589,7 +2554,7 @@ def listener(vehicle, name, m):

@vehicle.on_message('MOUNT_ORIENTATION')
def listener(vehicle, name, m):
self._pitch = m.pitch
self._pitch = m.pitch
self._roll = m.roll
self._yaw = m.yaw
vehicle.notify_attribute_listeners('gimbal', vehicle.gimbal)
Expand Down Expand Up @@ -2731,7 +2696,7 @@ def __str__(self):
return "Gimbal: pitch={0}, roll={1}, yaw={2}".format(self.pitch, self.roll, self.yaw)


class Parameters(MutableMapping, HasObservers):
class Parameters(collections.abc.MutableMapping, HasObservers):
"""
This object is used to get and set the values of named parameters for a vehicle. See the following links for information about
the supported parameters for each platform: `Copter Parameters <http://copter.ardupilot.com/wiki/configuration/arducopter-parameters/>`_,
Expand Down Expand Up @@ -2917,7 +2882,7 @@ def decorated_thr_min_callback(self, attr_name, value):
return super(Parameters, self).on_attribute(attr_name, *args, **kwargs)


class Command(mavutil.mavlink.MAVLink_mission_item_message):
class Command(mavutil.mavlink.MAVLink_mission_item_int_message):
"""
A waypoint object.

Expand Down
6 changes: 5 additions & 1 deletion dronekit/mavlink.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,10 @@ def recv(self, n=None):
if e.errno in [errno.EAGAIN, errno.EWOULDBLOCK, errno.ECONNREFUSED]:
return ""
if self.udp_server:
self.addresses.add(new_addr)
try:
self.addresses.add(new_addr)
except:
return ""
ShafiqSadat marked this conversation as resolved.
Show resolved Hide resolved
elif self.broadcast:
self.addresses = {new_addr}
return data
Expand Down Expand Up @@ -246,6 +249,7 @@ def mavlink_thread_in():

except APIException as e:
self._logger.exception('Exception in MAVLink input loop')
self._logger.error('%s' % str(e))
self._alive = False
self.master.close()
self._death_error = e
Expand Down
4 changes: 2 additions & 2 deletions setup.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
import setuptools
import os

version = '2.9.2'
version = '2.9.3.1'

with open(os.path.join(os.path.dirname(__file__), 'README.md')) as f:
with open(os.path.join(os.path.dirname(__file__), 'README.md'), encoding="utf-8") as f:
LongDescription = f.read()

setuptools.setup(
Expand Down