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

Add device classes #65

Merged
merged 12 commits into from
Aug 29, 2019
Merged
2 changes: 2 additions & 0 deletions brping/__init__.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
#'Ping python package'
from brping.definitions import *
from brping.pingmessage import *
from brping.device import PingDevice
from brping.ping1d import Ping1D
from brping.ping360 import Ping360
777 changes: 0 additions & 777 deletions brping/ping1d.py

This file was deleted.

16 changes: 13 additions & 3 deletions brping/pingmessage.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,8 @@
from brping import definitions
payload_dict = definitions.payload_dict_all
asciiMsgs = [definitions.COMMON_NACK, definitions.COMMON_ASCII_TEXT]
variable_msgs = [definitions.PING1D_PROFILE, ]
variable_msgs = [definitions.PING1D_PROFILE, definitions.PING360_DEVICE_DATA, ]


class PingMessage(object):
## header start byte 1
Expand Down Expand Up @@ -95,6 +96,7 @@ def __init__(self, msg_id=0, msg_data=None):

## The field names of this message
self.payload_field_names = payload_dict[self.message_id]["field_names"]
self.update_payload_length()

## Number of bytes in the message payload
self.update_payload_length()
Expand Down Expand Up @@ -151,9 +153,15 @@ def unpack_msg_data(self, msg_data):
print("error unpacking payload: %s" % e)
print("msg_data: %s, header: %s" % (msg_data, header))
print("format: %s, buf: %s" % (PingMessage.endianess + self.get_payload_format(), self.msg_data[PingMessage.headerLength:PingMessage.headerLength + self.payload_length]))
print(self.get_payload_format())
else: # only use payload if didn't raise exception
for i, attr in enumerate(payload_dict[self.message_id]["field_names"]):
setattr(self, attr, payload[i])
try:
setattr(self, attr, payload[i])
except IndexError as e:
if self.message_id in variable_msgs:
setattr(self, attr, bytearray())
pass

# Extract checksum
self.checksum = struct.unpack(PingMessage.endianess + PingMessage.checksum_format, self.msg_data[PingMessage.headerLength + self.payload_length: PingMessage.headerLength + self.payload_length + PingMessage.checksumLength])[0]
Expand Down Expand Up @@ -190,7 +198,7 @@ def get_payload_format(self):
if self.message_id in variable_msgs or self.message_id in asciiMsgs:
var_length = self.payload_length - payload_dict[self.message_id]["payload_length"] # Subtract static length portion from payload length
if var_length <= 0:
return "" # variable data portion is empty
return payload_dict[self.message_id]["format"] # variable data portion is empty

return payload_dict[self.message_id]["format"] + str(var_length) + "s"
else: # messages with a static (constant) length
Expand Down Expand Up @@ -325,6 +333,8 @@ def parse_byte(self, msg_byte):
self.parsed += 1
return PingParser.NEW_MESSAGE
else:
# TODO add/return error state
print("parse error")
self.errors += 1

return self.state
Expand Down
2 changes: 2 additions & 0 deletions ci/deploy-whitelist
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
brping/__init__.py
brping/definitions.py
brping/device.py
brping/ping1d.py
brping/ping360.py
brping/pingmessage.py
examples
tools
Expand Down
18 changes: 18 additions & 0 deletions generate/generate-python.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,3 +65,21 @@
f.write(")\n")

f.close()

definitionFile = "%s/common.json" % definitionPath
templateFile = "%s/device.py.in" % templatePath
f = open("%s/device.py" % args.output_directory, "w")
f.write(g.generate(definitionFile, templateFile, {"structToken": struct_token}))
f.close()

definitionFile = "%s/ping1d.json" % definitionPath
templateFile = "%s/ping1d.py.in" % templatePath
f = open("%s/ping1d.py" % args.output_directory, "w")
f.write(g.generate(definitionFile, templateFile, {"structToken": struct_token}))
f.close()

definitionFile = "%s/ping360.json" % definitionPath
templateFile = "%s/ping360.py.in" % templatePath
f = open("%s/ping360.py" % args.output_directory, "w")
f.write(g.generate(definitionFile, templateFile, {"structToken": struct_token}))
f.close()
193 changes: 193 additions & 0 deletions generate/templates/device.py.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,193 @@
#!/usr/bin/env python3

# device.py
# A device API for devices implementing Blue Robotics ping-protocol

# ~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!
# THIS IS AN AUTOGENERATED FILE
# DO NOT EDIT
# ~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!

from brping import definitions
from brping import pingmessage
from collections import deque
import serial
import time

class PingDevice(object):
{% for field in all_fields|sort %}
_{{field}} = None
{% endfor%}

_input_buffer = deque()
def __init__(self, device_name, baudrate=115200):
if device_name is None:
print("Device name is required")
return

try:
print("Opening %s at %d bps" % (device_name, baudrate))

## Serial object for device communication
self.iodev = serial.Serial(device_name, baudrate)
self.iodev.send_break()
self.iodev.write("U".encode("utf-8"))
jaxxzer marked this conversation as resolved.
Show resolved Hide resolved

except Exception as e:
print("Failed to open the given serial port")
print("\t", e)
exit(1)

## A helper class to take care of decoding the input stream
self.parser = pingmessage.PingParser()

## device id of this Ping1D object, used for dst_device_id in outgoing messages
self.my_id = 255

##
# @brief Consume rx buffer data until a new message is successfully decoded
#
# @return A new PingMessage: as soon as a message is parsed (there may be data remaining in the buffer to be parsed, thus requiring subsequent calls to read())
# @return None: if the buffer is empty and no message has been parsed
def read(self):
bytes = self.iodev.read(self.iodev.in_waiting)
self._input_buffer.extendleft(bytes)

while len(self._input_buffer):
b = self._input_buffer.pop()

if self.parser.parse_byte(b) == pingmessage.PingParser.NEW_MESSAGE:
self.handle_message(self.parser.rx_msg)
return self.parser.rx_msg
return None

##
# @brief Write data to device
#
# @param data: bytearray to write to device
#
# @return Number of bytes written
def write(self, data):
return self.iodev.write(data)

##
# @brief Make sure there is a device on and read some initial data
#
# @return True if the device replies with expected data, False otherwise
def initialize(self):
if (self.request(definitions.COMMON_PROTOCOL_VERSION) is None):
return False
return True

##
# @brief Request the given message ID
#
# @param m_id: The message ID to request from the device
# @param timeout: The time in seconds to wait for the device to send
# the requested message before timing out and returning
#
# @return PingMessage: the device reply if it is received within timeout period, None otherwise
#
# @todo handle nack to exit without blocking
jaxxzer marked this conversation as resolved.
Show resolved Hide resolved
def request(self, m_id, timeout=0.5):
msg = pingmessage.PingMessage(definitions.COMMON_GENERAL_REQUEST)
msg.requested_id = m_id
msg.pack_msg_data()
self.write(msg.msg_data)

# uncomment to return nacks in addition to m_id
# return self.wait_message([m_id, definitions.COMMON_NACK], timeout)
jaxxzer marked this conversation as resolved.
Show resolved Hide resolved

return self.wait_message([m_id], timeout)

##
# @brief Wait until we receive a message from the device with the desired message_id for timeout seconds
#
# @param message_id: The message id to wait to receive from the device
# @param timeout: The timeout period in seconds to wait
#
# @return PingMessage: the message from the device if it is received within timeout period, None otherwise
def wait_message(self, message_ids, timeout=0.5):
tstart = time.time()
while time.time() < tstart + timeout:
msg = self.read()
if msg is not None:
if msg.message_id in message_ids:
return msg
time.sleep(0.005)
return None

##
# @brief Handle an incoming message from the device.
# Extract message fields into self attributes.
#
# @param msg: the PingMessage to handle.
def handle_message(self, msg):
if msg.message_id in pingmessage.payload_dict:
jaxxzer marked this conversation as resolved.
Show resolved Hide resolved
for attr in pingmessage.payload_dict[msg.message_id]["field_names"]:
setattr(self, "_" + attr, getattr(msg, attr))
else:
print("Unrecognized message: %d", msg)

##
# @brief Dump object into string representation.
#
# @return string: a string representation of the object
def __repr__(self):
representation = "---------------------------------------------------------\n~Ping1D Object~"

attrs = vars(self)
for attr in sorted(attrs):
try:
if attr != 'iodev':
representation += "\n - " + attr + "(hex): " + str([hex(item) for item in getattr(self, attr)])
if attr != 'data':
representation += "\n - " + attr + "(string): " + str(getattr(self, attr))
# TODO: Better filter this exception
except:
representation += "\n - " + attr + ": " + str(getattr(self, attr))
return representation

{% for msg in messages["get"]|sort %}
##
# @brief Get a {{msg|replace("get_", "")}} message from the device\n
# Message description:\n
# {{messages["get"][msg].description}}
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
{% for field in messages["get"][msg].payload %}
# {{field.name}}: {% if field.units %}Units: {{field.units}}; {% endif %}{{field.description}}\n
{% endfor%}
def get_{{msg}}(self):
if self.request(definitions.COMMON_{{msg|upper}}) is None:
return None
data = ({
{% for field in messages["get"][msg].payload %}
"{{field.name}}": self._{{field.name}}, # {% if field.units %}Units: {{field.units}}; {% endif %}{{field.description}}
{% endfor %}
})
return data

{% endfor %}

if __name__ == "__main__":
import argparse

parser = argparse.ArgumentParser(description="Ping python library example.")
parser.add_argument('--device', action="store", required=True, type=str, help="Ping device port.")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="Ping device baudrate.")
args = parser.parse_args()

p = PingDevice(args.device, args.baudrate)

print("Initialized: %s" % p.initialize())

{% for msg in messages["get"]|sort %}
print("\ntesting get_{{msg}}")
result = p.get_{{msg}}()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))

{% endfor %}

print(p)
Loading