mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-01 21:07:40 +08:00
[python] add pprz_env with usable default IVY_BUS
- pprz_env.IVY_BUS is either the env variable IVY_BUS or appropriate default (checks for OSX) - some fixes for udp_link should fix #1495 and the python part of #204
This commit is contained in:
@@ -16,6 +16,7 @@ import messagepicker
|
||||
PPRZ_SRC = getenv("PAPARAZZI_SRC", path.normpath(path.join(path.dirname(path.abspath(__file__)), '../../../../')))
|
||||
sys.path.append(PPRZ_SRC + "/sw/lib/python")
|
||||
|
||||
import pprz_env
|
||||
from pprz_msg import messages_xml_map
|
||||
|
||||
|
||||
@@ -244,7 +245,7 @@ class PlotPanel(object):
|
||||
# is given ; this is performed by IvyStart (C)
|
||||
try:
|
||||
logging.getLogger('Ivy').setLevel(logging.WARN)
|
||||
IvyStart("")
|
||||
IvyStart(pprz_env.IVY_BUS)
|
||||
# binding to every message
|
||||
# IvyBindMsg(self.OnIvyMsg, "(.*)")
|
||||
except:
|
||||
|
||||
@@ -31,6 +31,8 @@ from ivy.std_api import *
|
||||
|
||||
PPRZ_HOME = os.getenv("PAPARAZZI_HOME")
|
||||
sys.path.append(PPRZ_HOME + "/sw/lib/python")
|
||||
|
||||
import pprz_env
|
||||
from pprz_msg import messages_xml_map
|
||||
|
||||
class Circular_Buffer:
|
||||
@@ -161,7 +163,7 @@ class Link_Combiner:
|
||||
|
||||
# starting the bus
|
||||
logging.getLogger('Ivy').setLevel(logging.WARN)
|
||||
IvyStart("")
|
||||
IvyStart(pprz_env.IVY_BUS)
|
||||
IvyBindMsg(self.onIvyMessage, "^([^ ]+) TELEMETRY_MESSAGE ([^ ]+) ([^ ]+) ([^ ]+)$")
|
||||
|
||||
def onIvyMessage(self, agent, *larg):
|
||||
|
||||
@@ -9,9 +9,14 @@ import sys
|
||||
import threading
|
||||
import time
|
||||
|
||||
sys.path.append(os.getenv("PAPARAZZI_HOME") + "/sw/lib/python")
|
||||
# if PAPARAZZI_SRC not set, then assume the tree containing this
|
||||
# file is a reasonable substitute
|
||||
PPRZ_SRC = os.getenv("PAPARAZZI_SRC", os.path.normpath(os.path.join(os.path.dirname(os.path.abspath(__file__)),
|
||||
'../../../../')))
|
||||
sys.path.append(PPRZ_SRC + "/sw/lib/python")
|
||||
|
||||
import messages_xml_map
|
||||
import pprz_env
|
||||
from pprz_msg import messages_xml_map
|
||||
|
||||
PING_PERIOD = 5.0
|
||||
STATUS_PERIOD = 1.0
|
||||
@@ -39,12 +44,13 @@ class DownLinkStatus():
|
||||
class IvyUdpLink():
|
||||
def __init__(self):
|
||||
self.InitIvy()
|
||||
self.ivy_id = 0
|
||||
self.status_timer = threading.Timer(STATUS_PERIOD, self.sendStatus)
|
||||
self.ping_timer = threading.Timer(STATUS_PERIOD, self.sendPing)
|
||||
self.ac_downlink_status = {}
|
||||
self.rx_err = 0
|
||||
|
||||
messages_xml_map.ParseMessages()
|
||||
messages_xml_map.parse_messages()
|
||||
self.data_types = {'float': ['f', 4],
|
||||
'uint8': ['B', 1],
|
||||
'uint16': ['H', 2],
|
||||
@@ -54,6 +60,15 @@ class IvyUdpLink():
|
||||
'int32': ['l', 4]
|
||||
}
|
||||
|
||||
def __del__(self):
|
||||
self.stop()
|
||||
|
||||
def stop(self):
|
||||
self.status_timer.cancel()
|
||||
self.ping_timer.cancel()
|
||||
IvyUnBindMsg(self.ivy_id)
|
||||
IvyStop()
|
||||
|
||||
def Unpack(self, data_fields, type, start, length):
|
||||
return struct.unpack(type, "".join(data_fields[start:start + length]))[0]
|
||||
|
||||
@@ -68,8 +83,8 @@ class IvyUdpLink():
|
||||
|
||||
# starting the bus
|
||||
logging.getLogger('Ivy').setLevel(logging.WARN)
|
||||
IvyStart("")
|
||||
IvyBindMsg(self.OnSettingMsg, "(^.* SETTING .*)")
|
||||
IvyStart(pprz_env.IVY_BUS)
|
||||
self.ivy_id = IvyBindMsg(self.OnSettingMsg, "(^.* SETTING .*)")
|
||||
|
||||
def calculate_checksum(self, msg):
|
||||
ck_a = 0
|
||||
@@ -227,14 +242,18 @@ class IvyUdpLink():
|
||||
self.server.bind(('0.0.0.0', DOWNLINK_PORT))
|
||||
self.status_timer.start()
|
||||
self.ping_timer.start()
|
||||
while True:
|
||||
(msg, address) = self.server.recvfrom(2048)
|
||||
self.ProcessPacket(msg, address)
|
||||
try:
|
||||
while True:
|
||||
(msg, address) = self.server.recvfrom(2048)
|
||||
self.ProcessPacket(msg, address)
|
||||
except KeyboardInterrupt:
|
||||
print("Stopping server on request")
|
||||
|
||||
|
||||
def main():
|
||||
udp_interface = IvyUdpLink()
|
||||
udp_interface.Run()
|
||||
udp_interface.stop()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
@@ -6,22 +6,20 @@ import logging
|
||||
import os
|
||||
import sys
|
||||
import re
|
||||
import pprz_env
|
||||
|
||||
# if PAPARAZZI_SRC not set, then assume the tree containing this
|
||||
# file is a reasonable substitute
|
||||
PPRZ_SRC = os.getenv("PAPARAZZI_SRC", os.path.normpath(os.path.join(os.path.dirname(os.path.abspath(__file__)),
|
||||
'../../../../')))
|
||||
sys.path.append(PPRZ_SRC + "/sw/lib/python")
|
||||
sys.path.append(pprz_env.PAPARAZZI_SRC + "/sw/lib/python")
|
||||
|
||||
from pprz_msg.message import PprzMessage
|
||||
from pprz_msg import messages_xml_map
|
||||
|
||||
|
||||
class IvyMessagesInterface(object):
|
||||
def __init__(self, callback=None, init=True, verbose=False, bind_regex='(.*)'):
|
||||
def __init__(self, callback=None, init=True, verbose=False, bind_regex='(.*)', ivy_bus=pprz_env.IVY_BUS):
|
||||
self.callback = callback
|
||||
self.ivy_id = 0
|
||||
self.verbose = verbose
|
||||
self.ivy_bus = ivy_bus
|
||||
# make sure all messages are parsed before we start creating them in callbacks
|
||||
messages_xml_map.parse_messages()
|
||||
self.init_ivy(init, bind_regex)
|
||||
@@ -36,7 +34,7 @@ class IvyMessagesInterface(object):
|
||||
except IvyIllegalStateError as e:
|
||||
print(e)
|
||||
|
||||
def __init__del__(self):
|
||||
def __del__(self):
|
||||
try:
|
||||
IvyUnBindMsg(self.ivy_id)
|
||||
except:
|
||||
@@ -46,7 +44,7 @@ class IvyMessagesInterface(object):
|
||||
if init:
|
||||
IvyInit("Messages %i" % os.getpid(), "READY", 0, lambda x,y: y, lambda x,y: y)
|
||||
logging.getLogger('Ivy').setLevel(logging.WARN)
|
||||
IvyStart("")
|
||||
IvyStart(self.ivy_bus)
|
||||
self.ivy_id = IvyBindMsg(self.on_ivy_msg, bind_regex)
|
||||
|
||||
def on_ivy_msg(self, agent, *larg):
|
||||
|
||||
@@ -0,0 +1,13 @@
|
||||
import os
|
||||
import platform
|
||||
|
||||
PAPARAZZI_SRC = os.getenv("PAPARAZZI_SRC", os.path.normpath(os.path.join(os.path.dirname(os.path.abspath(__file__)),
|
||||
'../../..')))
|
||||
PAPARAZZI_HOME = os.getenv("PAPARAZZI_HOME", PAPARAZZI_SRC)
|
||||
|
||||
if os.getenv('IVY_BUS') is not None:
|
||||
IVY_BUS = os.getenv('IVY_BUS')
|
||||
elif platform.system() == 'Darwin':
|
||||
IVY_BUS = "224.255.255.255:2010"
|
||||
else:
|
||||
IVY_BUS = ""
|
||||
@@ -39,7 +39,7 @@ class SerialMessagesInterface(threading.Thread):
|
||||
def shutdown(self):
|
||||
self.stop()
|
||||
|
||||
def __init__del__(self):
|
||||
def __del__(self):
|
||||
try:
|
||||
self.ser.close()
|
||||
except:
|
||||
|
||||
@@ -3,17 +3,17 @@
|
||||
from __future__ import absolute_import, print_function
|
||||
|
||||
from ivy.std_api import *
|
||||
import os
|
||||
import logging
|
||||
import sys
|
||||
import pprz_env
|
||||
|
||||
sys.path.append(pprz_env.PAPARAZZI_SRC + "/sw/lib/python")
|
||||
|
||||
PPRZ_SRC = os.getenv("PAPARAZZI_SRC", os.path.normpath(os.path.join(os.path.dirname(os.path.abspath(__file__)),
|
||||
'../../..')))
|
||||
sys.path.append(PPRZ_SRC + "/sw/lib/python")
|
||||
from settings_xml_parse import PaparazziACSettings
|
||||
|
||||
_SHOW_IVY_MSGS_ = False
|
||||
|
||||
|
||||
class IvySettingsInterface(PaparazziACSettings):
|
||||
def __init__(self, ac_ids):
|
||||
PaparazziACSettings.__init__(self, ac_ids[0])
|
||||
@@ -68,7 +68,7 @@ class IvySettingsInterface(PaparazziACSettings):
|
||||
|
||||
# starting the bus
|
||||
logging.getLogger('Ivy').setLevel(logging.WARN)
|
||||
IvyStart("")
|
||||
IvyStart(pprz_env.IVY_BUS)
|
||||
IvyBindMsg(self.OnValueMsg, "(^.* DL_VALUE .*)")
|
||||
IvyBindMsg(self.OnSettingMsg, "dl DL_SETTING (.*)")
|
||||
|
||||
|
||||
Reference in New Issue
Block a user