Echosounder S500 - ping-python implementation ?
Hello,
I'm trying to use the functions you are defining in this api related to the S500 echosounder.
From what I understood the ping-python library is "general" but I tried to make some modifications in the definitions.py and ping1D.py to add these functions for the api:
I tried to manually add the definitions and functions in the library: definitions.py:
PING1D_DISTANCE2 = 1223
PING1D_PROFILE6_T = 1308
PING1D_SET_PING_PARAMETERS = 1015
PING1D_SET_PING_PARAMETERS: {
"name": "set_ping_params",
"format": "IIhhHHHBB",
"field_names": (
"start_mm",
"length_mm",
"gain_index",
"msec_per_ping",
"pulse_len_usec",
"report_id",
"reserved",
"chirp",
"decimation",
),
"payload_length": 20
},
PING1D_DISTANCE2: {
"name": "distance2",
"format": "IIHBBI",
"field_names": (
"this_ping_distance_mm",
"averaged_distance_mm",
"reserved",
"this_ping_confidence",
"confidence_of_averaged_distance",
"timestamp",
),
"payload_length": 16
},
PING1D_PROFILE6_T: {
"name": "profile6_t",
"format": "IIIIIIIIfffffffBBBBHH",
"field_names": (
"ping_number",
"start_mm",
"length_mm",
"start_ping_hz",
"end_ping_hz",
"adc_sample_hz",
"timestamp_msec",
"spare2",
"pulse_duration_sec",
"analog_gain",
"max_pwr_db",
"min_pwr_db",
"this_ping_depth_m",
"smooth_depth_m",
"fspare2",
"this_ping_depth_measurement_confidence",
"gain_index",
"decimation",
"smoothed_depth_measurement_confidence",
"num_results",
"pwr_results",
),
"payload_length": 68
},
and pind1D.py:
def get_distance2(self):
if self.legacyRequest(definitions.PING1D_DISTANCE2) is None:
return None
data = ({
"this_ping_distance_mm": self._this_ping_distance_mm, # Units: mm; Distance to the target in this ping.
"averaged_distance_mm": self._averaged_distance_mm, # Units: mm; Averaged distance across multiple pings.
"reserved": self._reserved, # Reserved field, not used.
"this_ping_confidence": self._this_ping_confidence, # Units: %; Confidence in this ping's distance measurement.
"confidence_of_averaged_distance": self._confidence_of_averaged_distance, # Units: %; Confidence in the averaged distance measurement.
"timestamp": self._timestamp, # Units: ms; Timestamp of the measurement.
})
return data
def get_profile6_t(self):
if self.legacyRequest(definitions.PING1D_PROFILE6_T) is None:
return None
data = ({
"ping_number": self._ping_number, # Units: N/A; The ping number.
"start_mm": self._start_mm, # Units: mm; Start position for the ping.
"length_mm": self._length_mm, # Units: mm; Length of the ping measurement.
"start_ping_hz": self._start_ping_hz, # Units: Hz; Starting frequency of the ping.
"end_ping_hz": self._end_ping_hz, # Units: Hz; Ending frequency of the ping.
"adc_sample_hz": self._adc_sample_hz, # Units: Hz; ADC sampling frequency.
"timestamp_msec": self._timestamp_msec, # Units: ms; Timestamp in milliseconds.
"spare2": self._spare2, # Units: N/A; Spare field, not used.
"pulse_duration_sec": self._pulse_duration_sec, # Units: sec; Duration of the pulse.
"analog_gain": self._analog_gain, # Units: N/A; Gain used in the analog signal processing.
"max_pwr_db": self._max_pwr_db, # Units: dB; Maximum power level measured.
"min_pwr_db": self._min_pwr_db, # Units: dB; Minimum power level measured.
"this_ping_depth_m": self._this_ping_depth_m, # Units: m; Depth measurement for this ping.
"smooth_depth_m": self._smooth_depth_m, # Units: m; Smoothed depth measurement.
"fspare2": self._fspare2, # Units: N/A; Spare field, not used.
"this_ping_depth_measurement_confidence": self._this_ping_depth_measurement_confidence, # Units: %; Confidence in this ping's depth measurement.
"gain_index": self._gain_index, # Units: N/A; Index of the gain setting used.
"decimation": self._decimation, # Units: N/A; Decimation factor used.
"smoothed_depth_measurement_confidence": self._smoothed_depth_measurement_confidence, # Units: %; Confidence in the smoothed depth measurement.
"num_results": self._num_results, # Units: N/A; Number of results returned.
"pwr_results": self._pwr_results, # Units: N/A; Array of power results.
})
return data
def set_ping_params(self, start_mm, length_mm, gain_index, msec_per_ping,
pulse_len_usec, report_id, reserved, chirp, decimation,
verify=True):
# Create and pack the message
m = pingmessage.PingMessage(definitions.PING1D_SET_PING_PARAMETERS)
m.start_mm = start_mm
m.length_mm = length_mm
m.gain_index = gain_index
m.msec_per_ping = msec_per_ping
m.pulse_len_usec = pulse_len_usec
m.report_id = report_id
m.reserved = reserved
m.chirp = chirp
m.decimation = decimation
m.pack_msg_data()
self.write(m.msg_data)
if self.legacyRequest(definitions.PING1D_SET_PING_PARAMETERS) is None:
return False
if (verify and (
self._start_mm != start_mm or
self._length_mm != length_mm or
self._gain_index != gain_index or
self._msec_per_ping != msec_per_ping or
self._pulse_len_usec != pulse_len_usec or
self._report_id != report_id or
self._reserved != reserved or
self._chirp != chirp or
self._decimation != decimation)):
return False
return True # Success
Then I made a basic test with my S500:
from brping.ping1d import Ping1D
import time
# Create class object
myPing = Ping1D()
# Connect via UDP (Ethernet for example)
myPing.connect_udp("192.168.3.51", 51200)
if not myPing.initialize():
print("Failed to initialize Ping!")
exit(1)
test_0 = myPing.get_distance()
print(test_0)
print("")
test = myPing.get_distance2()
print(test)
print("")
test2 = myPing.get_profile6_t()
print(test2)
myPing.set_ping_params(start_mm=0, length_mm=0, gain_index=-1, msec_per_ping=-1,
pulse_len_usec=0, report_id=1308, reserved=0, chirp=0, decimation=0,verify=True)
And got theses output:
Opening 192.168.3.51:51200
{'distance': 0, 'confidence': 0, 'transmit_duration': 50, 'ping_number': 0, 'scan_start': 0, 'scan_length': 1000, 'gain_setting': 0}
{'this_ping_distance_mm': 352, 'averaged_distance_mm': 0, 'reserved': 0, 'this_ping_confidence': 0, 'confidence_of_averaged_distance': 0, 'timestamp': 29833152}
error unpacking payload: unpack requires a buffer of 68 bytes
msg_data: bytearray(b'BRB\x08\x1c\x05\x00\x00=\x00\x00\x00\x00\x00\x00\x00\xe8\x03\x00\x00 \xa1\x07\x00 \xa1\x07\x00\x80\x84\x1e\x00\xf87\xc7\x01\x00\x00\x00\x00\x17\xb7Q8R\xb8~@VQ\xa2B\xae\xef\x04B\x00\x80\xb4>\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x04\xeba\t\x8a\xeb\xb0\xd5\xc9t\xd6\xba\xe1\x92\xe8C\xf3\xa6\xf6\x1e\xfa#\xff\xe7\xff\xff\xff\n\xfe\x13\xfc(\xfa\xf9\xf6\xe1\xed\x9a\xe7\xc0\xdf&\xcbB\xbb\xda\xa1\xf3\xa0\x9f\xb0\x06\xb9-\xc5\xa7\xd2\x1c\xd9\xeb\xde\xbd\xe2\xa5\xe4\x18\xe5\xb7\xe1\xc1\xde\xfc\xdaS\xd3c\xcc\x17\xbf,\xb2\xc3\x97j\x1e\x8f\x84\x8b\xa4\x8f\xb9\xf5\xcd\xc1\xd4\xc4\xd6\xd8\xd8S\xd8\xb0\xd9V\xd3B\xd1\x08\xc90\xc0\x16\xae\xda\x9a(\x87>\x831uQeWj\xa9f\xedh\xe7P\xeap\xe5\x95M\x9d\xfb\xa4?\xaa\xe9\xa4$\xa3g\xa1\x83\xb2\x1f\xb7\xa3\xbc\xf5\xba\xc0\xbb3\xb8+\xb6\xca\xb2\x84\xb4)\xb5\xad\xb9\xb5\xbaA\xbd\x0e\xc0\x1c\xc5\xfa\xcd5\xd2\xba\xd3L\xd6>\xd6\x11\xd3\xa0\xcd\xb7\xcai\xc7L\xc3\xac\xbbY\xb6\xd1\xb1\xa0\xa5W\xa1\x9e\x9cf\x83\x05kPU\xd3o(\x9a\xb1\xa5@\xacE\xb7T\xb9\x17\xba\xc1\xb6A\xb4\x02\xb2H\xae\x19\xa7\x81\xa3\xd0\xa0\xa0\x9c \x9e\xfa\xa4u\xad[\xb2Y\xb7\xfb\xba\xd1\xc0\xec\xc1v\xc3\xc5\xc4\xc6\xc4"\xc4\xa7\xc1\x17\xc0\xed\xbd\x17\xbce\xb7\xdb\xb4\xf9\xb2\xc6\xb0\xc0\xb0\x04\xb0\t\xb0+\xb0&\xb0\xf5\xaf\x19\xb0\xcb\xb3\xe9\xb5d\xb7\x93\xbe\xcc\xc1P\xc4h\xc7;\xce\xa0\xd08\xd3\xe6\xd7\xe1\xd9\xf6\xdbI\xdf\xb7\xe0E\xe2\x98\xe3\xc9\xe5\xb5\xe6\x8c\xe7\xab\xe8\x0b\xe9Q\xe9\x88\xe9\x86\xe91\xe9\xe4\xe8\xf9\xe7w\xe7\xdf\xe6c\xe5\x91\xe4t\xe3\x1b\xe1\xae\xdf)\xdem\xdct\xd8/\xd6\x9b\xd3\x9c\xcd\xee\xc9\xfb\xc5\x90\xbc\xd1\xb6D\xb0\xba\xa8\x17\x96X\x85\x13o\x13Qwj\xa1\x80\xcd\x97v\x9f\x8b\xa7\xc3\xae\xd4\xb1*\xb5\xa3\xb6\x18\xb7\x9f\xb7\xf5\xb6\x17\xb4i\xb2l\xafa\xaa,\xa7b\xa0(\x9b(\x93\xe8\x86w~Xr4g\\P\x7f<\xf80iE\x85M>W<f\x83leq\x86u\xa4{\xf7~o\x82\xb8\x89\xd4\x8dr\x91\x9d\x98\x1b\x9ct\x9f\x90\xa2\xd3\xa8\xd0\xabm\xae3\xb3H\xb5\xe7\xb7"\xbb\x93\xbc%\xbf\x99\xc0g\xc1\xe4\xc3\x91\xc4\x87\xc3\xa7\xc5\xe4\xc5\xda\xc4\xab\xc5\x06\xc8q\xc8\xa9\xc9+\xcc\x83\xcd\xe3\xce\xa7\xd1\x1d\xd3\xd1\xd4\x14\xd6\x9f\xd7\xf0\xd8p\xd9\x84\xd9\x9a\xd9\xdd\xd9\x08\xd9t\xd8\xdd\xd7\x18\xd7\xbc\xd5\xe6\xd4M\xd4|\xd3\t\xd3\xb8\xd2 \xd2\xde\xd1\x8a\xd1+\xd1\xfd\xcf\x1a\xcf\x1b\xce\xa7\xcb \xca\x99\xc7k\xc3\xa0\xc0\xda\xbb\xdf\xb7\xb8\xb0\xb6\xa8n\xa2\xf3\x96\x01\x8f\xb2\x8a\xec\x85\x1c\x8c\x90\x9c\x01\xa3\x1c\xa9|\xb3\x04\xb8\xde\xbb>\xc1B\xc31\xc5I\xc6\x1b\xc7\x86\xc7J\xc7v\xc6\xe2\xc5!\xc5\x8c\xc4%\xc4\xbd\xc3\xe2\xc3d\xc5\x1b\xc6G\xc7\x97\xc9\x80\xcaf\xcbV\xcc\x84\xccQ\xcc\xf5\xcb:\xca\xd2\xc8-\xc7\xec\xc2\x84\xc0\xac\xbd\xaf\xb7\xab\xb4\x17\xb2\xab\xaf\x1b\xab2\xae,\xb0\x9e\xb2C\xb7 \xc1\x00\xc6\xa2\xca^\xd2\xc1\xd5V\xd9\xd5\xdd\xf2\xdff\xe2\x05\xe4\t\xe6\x82\xe76\xe8\xd8\xe8<\xe9\xae\xe9a\xe9C\xe9T\xe9\x9a\xe8d\xe8\x97\xe8f\xe8\x8a\xe7\xd6\xe7\xa7\xe7\xc2\xe6q\xe6v\xe6\x02\xe5-\xe4(\xe3\xf2\xe1\x93\xdfj\xdd\xac\xdb8\xd9\x83\xd7\x0c\xd4K\xd2\x98\xd0\xf5\xcb\xff\xc9\x0c\xcaa\xc5l\xc4J\xc5H\xc4\x0f\xc2\xe1\xc1\x02\xc13\xc0\\\xbf\xc6\xbbZ\xbb\xd3\xb9\xc9\xb4\r\xb3\xa9\xb2x\xae\xa9\xad\x0e\xad\x04\xacK\xab\xcc\xa9\x9e\xa9\x1b\xaa\xb6\xa9#\xa8\xa8\xa8\x85\xa8\x01\xa8*\xa8\xcd\xa77\xa7\xbd\xa6\x82\xa5\x15\xa5@\xa4N\xa2\x90\xa2\xd7\xa5\xfa\xa7A\xab\x0f\xb1 \xb4\xa8\xb74\xbce\xbe\xc2\xc0X\xc2&\xc4\xa7\xc5h\xc6Y\xc7\xfb\xc7\xe2\xc8k\xc9\xbd\xc94\xca3\xca>\xca\x17\xca\xe4\xc9\x8f\xc96\xc9P\xc89\xc77\xc6[\xc4\xfe\xc2\xa2\xc0\xf8\xbd\x01\xbc\xda\xb7\x01\xb5\x8a\xb1\xbc\xaa\xb5\xa6]\xa2\xae\x9dp\x92\xfc\x8b}\x84\xe5r\x85g\x8ac\xecd\x17r\x8d\x899\x93\xa8\x9b\x87\xa9\x9c\xaf\xf4\xb5\x9f\xbe\xb2\xc2\xa4\xc7\x11\xcbl\xcfI\xd3|\xd5\xa9\xd7=\xd9\x04\xdc\xfe\xdc\xf7\xdd\xb9\xdfT\xe0\xc1\xe0\xeb\xe1n\xe2%\xe3\xd3\xe3\x06\xe5%\xe6\xef\xe6F\xe8\t\xe9\xa9\xe9\x8f\xea\xc9\xea\x93\xeau\xea{\xea\x9f\xe93\xe9\x8b\xe8\xcc\xe7r\xe6\xd0\xe4~\xe3\x85\xe1\xcf\xdf\xcc\xdb\xf2\xd8#\xd6w\xcf\x98\xcbh\xc7J\xbe\x81\xb9G\xb5O\xb18\xa9\x08\xab\xd5\xaa\x10\xaac\xaek\xaf\xcb\xafb\xb0\xfd\xaf\x10\xaf\xfd\xad\xdd\xa9\xa4\xa7/\xa6\\\xa0\x8c\x9e\x16\xa0K\xa0\x93\x9f1\xa5r\xa7+\xaa\x97\xac\x0c\xb1\xd5\xb2h\xb4\x92\xb6\x05\xb7\x98\xb7\x91\xb6\xb8\xb5\x06\xb6\xf1\xb4\xa0\xafo\xb0\xfa\xae\xd1\xab3\xac\x87\xab\xde\xaeL\xb0\xbd\xafp\xb1.\xb6\xb5\xb6\xb0\xb8&\xbdC\xbfI\xc1&\xc6\x81\xc8\xc8\xca\xf3\xcc(\xd0\x19\xd2X\xd3N\xd4\xc1\xd4p\xd5\xc1\xd4\x86\xd4\xae\xd4A\xd4h\xd4d\xd56\xd6\x94\xd7A\xda\xf2\xdbz\xdd\n\xdf\xda\xe2v\xe3\xc6\xe4\xe2\xe7\xac\xe8\x9e\xe8\xdb\xe9\xcc\xe9{\xe9\x16\xe9_\xe7d\xe6\x08\xe5\x8d\xe1\xba\xdf\xc9\xdd\x95\xd9q\xd7\x1d\xd5\xcb\xd2\xbc\xcd\xca\xca\xae\xc7C\xc1\xc1\xbdp\xb9\x10\xb2\xba\xad)\xa8\x1f\xa4 \x9f\x98\x9c#\x9c\xac\x9d\xb1\x9e\x15\xa0\xa7\xa1\xfb\xa1b\xa2\xf5\xa1\xce\x9f\xac\x9e1\x9d\x05\x9a\xb3\x97x\x96U\x97%\x99\x82\x9b!\xa2\x81\xa5\xc7\xa8\x98\xab\xfd\xaf\x81\xb1\x85\xb2H\xb3\x03\xb3Z\xb2%\xb0\xbe\xae\x97\xad\xc7\xac\xe3\xab\xe3\xae5\xb1\x8a\xb4\xde\xb7m\xbd5\xc1\xe0\xc3\\\xc7$\xc9i\xcb\x07\xcd\xe2\xcd\xdb\xce<\xcf\x81\xcf_\xcf\x0b\xcfr\xce\xbe\xcd\xf2\xcb\xb4\xcaz\xc9\xe1\xc6\x93\xc5\xb5\xc4\xd1\xc2Y\xc2\xb5\xc2\xb5\xc2\x97\xc2\xfa\xc2\xea\xc2\xa8\xc2 \xc2\xd7\xbf&\xbe\x15\xbc\xca\xb6\xca\xb3|\xb0;\xa9\x1a\xa6Q\xa5\xd6\xa1\xd0\xa2\x17\xa8\xa2\xaa\xa0\xadw\xb3U\xb6\xc6\xb9g\xbc\x08\xc0\xe4\xc2\x9f\xc4h\xc6g\xc7\xf2\xc8\xd7\xc8\xcf\xc8\xfd\xc8W\xc8d\xc6\xbe\xc4\x02\xc3\xd5\xbf\x96\xbdi\xb9\x1a\xb5\xad\xb1\x04\xab\x9c\xa6\xec\xa0\xcd\x97\x7f\x92\xdd\x8cr\x88\x04\x82\xe5\x81\x7f\x82\x89\x85\x16\x88Q\x8b\xc7\x8f\x08\x92n\x94<\x96;\x99\xd5\x9a%\x9cf\x9ep\x9f\x86\xa0\xd9\xa1r\xa2B\xa3\x19\xa3\xe1\xa2\x01\xa3B\xa2\x81\x9f\xe5\x9d\x97\x9bQ\x97T\x94\x8c\x8e+\x8a\xa2\x86{\x7f\x1b} \x7f^~,\x81~\x89}\x8d\x1c\x91\xac\x99h\x9d\xc3\xa0\x06\xa4\xb4\xa9\x1e\xacN\xae\xb4\xb1&\xb3\xc3\xb4\xab\xb6\xae\xb7\xe1\xb8\xae\xb9\xc6\xba\xd1\xbb\x86\xbc\x88\xbd9\xbe0\xbf\xe9\xbfn\xc0T\xc1\xb3\xc1\xa9\xc1;\xc2"\xc29\xc1\xd1\xc0l\xc0\xd9\xbe\xf4\xbd\x0c\xbd\x02\xbc\xd1\xb9\x8f\xb8A\xb7\x8b\xb4\xc8\xb2\x05\xb1\xec\xad\xf3\xab\x8e\xa8j\xa5\x06\xa3\xdf\x9d\xde\x9a\n\x98\x89\x91]\x8e\xbd\x8b\xb2\x88\xc5\x81h\x80D~py\x17y%{P{\x14}\'\x80\xf3\x81\xc0\x84I\x86J\x87~\x89\xfd\x89\xc4\x88\xb0\x89\x19\x89\x9b\x86\xb4\x85"\x85\xe2\x82\x1f\x82\x83\x81;\x81\x80\x82\xe3\x81\xa1\x82\xd5\x86#\x88\xb9\x87\xbc\x8b\xbc\x8c\xef\x8c\xfa\x8d\x1b\x90\xd4\x90\x91\x91\xe3\x92\x86\x93\xb7\x94\xf7\x95\xa7\x96\xd8\x97\xf0\x98\xba\x99\xb7\x9aT\x9b\xe8\x9bO\x9cT\x9c\xba\x9b6\x9b\x1f\x9a\t\x98\x8d\x96D\x94F\x92W\x8eF\x8b\x93\x88#\x83\xd9\x7f\xe6{\xdes\x9an?h\xf4`TN\xbd=\xea\'\x00\x00J\x1d;5TP\xb5Ylb\x08i\xd4r\xd4w\xba{\xb5\x81\x8e\x84!\x88\xcc\x8b\xce\x8d\xc8\x90o\x92\x0f\x94U\x96M\x97\xcd\x97I\x98^\x99\xb2\x98{\x98\xce\x98{\x97\x0e\x97\xd1\x961\x96\xe8\x94k\x94\xd1\x93\xd3\x92W\x92"\x91z\x90\xd9\x8f\x9e\x8d\xe8\x8c\x83\x8dc\x8bp\x8b&\x8d\x8f\x8d\xe7\x8c\xc8\x8f\xdb\x90 \x91q\x92\x15\x95\x9a\x95i\x96\xfa\x97\x88\x98\xe8\x98\x9a\x99\xd7\x99?\x9aF\x9a\xe0\x99"\x9a\xd4\x99\xed\x98o\x98?\x98%\x97\x84\x96\x86\x960\x96\xc8\x95\xed\x95\xf5\x95\x85\x96\xd4\x96\x8c\x97\xe4\x98\xc3\x99t\x9a>\x9b\xa6\x9c[\x9d\x14\x9e1\x9f\x0b\xa0\xab\xa0\xe4\xa1\xb4\xa2\x98\xa3\xe2\xa4j\xa5e\xa6\xea\xa6w\xa7\x04\xa8\x1d\xa8\xc3\xa7a\xa7U\xa7;\xa6\x85\xa5\xaf\xa4\xd5\xa3e\xa2\xfd\xa0\x00\xa0Y\x9eL\x9d\\\x9bh\x99@\x98K\xd3'), header: (66, 82, 2114, 1308, 0, 0)
format: <IIIIIIIIfffffffBBBBHH, buf: bytearray(b'=\x00\x00\x00\x00\x00\x00\x00\xe8\x03\x00\x00 \xa1\x07\x00 \xa1\x07\x00\x80\x84\x1e\x00\xf87\xc7\x01\x00\x00\x00\x00\x17\xb7Q8R\xb8~@VQ\xa2B\xae\xef\x04B\x00\x80\xb4>\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x04\xeba\t\x8a\xeb\xb0\xd5\xc9t\xd6\xba\xe1\x92\xe8C\xf3\xa6\xf6\x1e\xfa#\xff\xe7\xff\xff\xff\n\xfe\x13\xfc(\xfa\xf9\xf6\xe1\xed\x9a\xe7\xc0\xdf&\xcbB\xbb\xda\xa1\xf3\xa0\x9f\xb0\x06\xb9-\xc5\xa7\xd2\x1c\xd9\xeb\xde\xbd\xe2\xa5\xe4\x18\xe5\xb7\xe1\xc1\xde\xfc\xdaS\xd3c\xcc\x17\xbf,\xb2\xc3\x97j\x1e\x8f\x84\x8b\xa4\x8f\xb9\xf5\xcd\xc1\xd4\xc4\xd6\xd8\xd8S\xd8\xb0\xd9V\xd3B\xd1\x08\xc90\xc0\x16\xae\xda\x9a(\x87>\x831uQeWj\xa9f\xedh\xe7P\xeap\xe5\x95M\x9d\xfb\xa4?\xaa\xe9\xa4$\xa3g\xa1\x83\xb2\x1f\xb7\xa3\xbc\xf5\xba\xc0\xbb3\xb8+\xb6\xca\xb2\x84\xb4)\xb5\xad\xb9\xb5\xbaA\xbd\x0e\xc0\x1c\xc5\xfa\xcd5\xd2\xba\xd3L\xd6>\xd6\x11\xd3\xa0\xcd\xb7\xcai\xc7L\xc3\xac\xbbY\xb6\xd1\xb1\xa0\xa5W\xa1\x9e\x9cf\x83\x05kPU\xd3o(\x9a\xb1\xa5@\xacE\xb7T\xb9\x17\xba\xc1\xb6A\xb4\x02\xb2H\xae\x19\xa7\x81\xa3\xd0\xa0\xa0\x9c \x9e\xfa\xa4u\xad[\xb2Y\xb7\xfb\xba\xd1\xc0\xec\xc1v\xc3\xc5\xc4\xc6\xc4"\xc4\xa7\xc1\x17\xc0\xed\xbd\x17\xbce\xb7\xdb\xb4\xf9\xb2\xc6\xb0\xc0\xb0\x04\xb0\t\xb0+\xb0&\xb0\xf5\xaf\x19\xb0\xcb\xb3\xe9\xb5d\xb7\x93\xbe\xcc\xc1P\xc4h\xc7;\xce\xa0\xd08\xd3\xe6\xd7\xe1\xd9\xf6\xdbI\xdf\xb7\xe0E\xe2\x98\xe3\xc9\xe5\xb5\xe6\x8c\xe7\xab\xe8\x0b\xe9Q\xe9\x88\xe9\x86\xe91\xe9\xe4\xe8\xf9\xe7w\xe7\xdf\xe6c\xe5\x91\xe4t\xe3\x1b\xe1\xae\xdf)\xdem\xdct\xd8/\xd6\x9b\xd3\x9c\xcd\xee\xc9\xfb\xc5\x90\xbc\xd1\xb6D\xb0\xba\xa8\x17\x96X\x85\x13o\x13Qwj\xa1\x80\xcd\x97v\x9f\x8b\xa7\xc3\xae\xd4\xb1*\xb5\xa3\xb6\x18\xb7\x9f\xb7\xf5\xb6\x17\xb4i\xb2l\xafa\xaa,\xa7b\xa0(\x9b(\x93\xe8\x86w~Xr4g\\P\x7f<\xf80iE\x85M>W<f\x83leq\x86u\xa4{\xf7~o\x82\xb8\x89\xd4\x8dr\x91\x9d\x98\x1b\x9ct\x9f\x90\xa2\xd3\xa8\xd0\xabm\xae3\xb3H\xb5\xe7\xb7"\xbb\x93\xbc%\xbf\x99\xc0g\xc1\xe4\xc3\x91\xc4\x87\xc3\xa7\xc5\xe4\xc5\xda\xc4\xab\xc5\x06\xc8q\xc8\xa9\xc9+\xcc\x83\xcd\xe3\xce\xa7\xd1\x1d\xd3\xd1\xd4\x14\xd6\x9f\xd7\xf0\xd8p\xd9\x84\xd9\x9a\xd9\xdd\xd9\x08\xd9t\xd8\xdd\xd7\x18\xd7\xbc\xd5\xe6\xd4M\xd4|\xd3\t\xd3\xb8\xd2 \xd2\xde\xd1\x8a\xd1+\xd1\xfd\xcf\x1a\xcf\x1b\xce\xa7\xcb \xca\x99\xc7k\xc3\xa0\xc0\xda\xbb\xdf\xb7\xb8\xb0\xb6\xa8n\xa2\xf3\x96\x01\x8f\xb2\x8a\xec\x85\x1c\x8c\x90\x9c\x01\xa3\x1c\xa9|\xb3\x04\xb8\xde\xbb>\xc1B\xc31\xc5I\xc6\x1b\xc7\x86\xc7J\xc7v\xc6\xe2\xc5!\xc5\x8c\xc4%\xc4\xbd\xc3\xe2\xc3d\xc5\x1b\xc6G\xc7\x97\xc9\x80\xcaf\xcbV\xcc\x84\xccQ\xcc\xf5\xcb:\xca\xd2\xc8-\xc7\xec\xc2\x84\xc0\xac\xbd\xaf\xb7\xab\xb4\x17\xb2\xab\xaf\x1b\xab2\xae,\xb0\x9e\xb2C\xb7 \xc1\x00\xc6\xa2\xca^\xd2\xc1\xd5V\xd9\xd5\xdd\xf2\xdff\xe2\x05\xe4\t\xe6\x82\xe76\xe8\xd8\xe8<\xe9\xae\xe9a\xe9C\xe9T\xe9\x9a\xe8d\xe8\x97\xe8f\xe8\x8a\xe7\xd6\xe7\xa7\xe7\xc2\xe6q\xe6v\xe6\x02\xe5-\xe4(\xe3\xf2\xe1\x93\xdfj\xdd\xac\xdb8\xd9\x83\xd7\x0c\xd4K\xd2\x98\xd0\xf5\xcb\xff\xc9\x0c\xcaa\xc5l\xc4J\xc5H\xc4\x0f\xc2\xe1\xc1\x02\xc13\xc0\\\xbf\xc6\xbbZ\xbb\xd3\xb9\xc9\xb4\r\xb3\xa9\xb2x\xae\xa9\xad\x0e\xad\x04\xacK\xab\xcc\xa9\x9e\xa9\x1b\xaa\xb6\xa9#\xa8\xa8\xa8\x85\xa8\x01\xa8*\xa8\xcd\xa77\xa7\xbd\xa6\x82\xa5\x15\xa5@\xa4N\xa2\x90\xa2\xd7\xa5\xfa\xa7A\xab\x0f\xb1 \xb4\xa8\xb74\xbce\xbe\xc2\xc0X\xc2&\xc4\xa7\xc5h\xc6Y\xc7\xfb\xc7\xe2\xc8k\xc9\xbd\xc94\xca3\xca>\xca\x17\xca\xe4\xc9\x8f\xc96\xc9P\xc89\xc77\xc6[\xc4\xfe\xc2\xa2\xc0\xf8\xbd\x01\xbc\xda\xb7\x01\xb5\x8a\xb1\xbc\xaa\xb5\xa6]\xa2\xae\x9dp\x92\xfc\x8b}\x84\xe5r\x85g\x8ac\xecd\x17r\x8d\x899\x93\xa8\x9b\x87\xa9\x9c\xaf\xf4\xb5\x9f\xbe\xb2\xc2\xa4\xc7\x11\xcbl\xcfI\xd3|\xd5\xa9\xd7=\xd9\x04\xdc\xfe\xdc\xf7\xdd\xb9\xdfT\xe0\xc1\xe0\xeb\xe1n\xe2%\xe3\xd3\xe3\x06\xe5%\xe6\xef\xe6F\xe8\t\xe9\xa9\xe9\x8f\xea\xc9\xea\x93\xeau\xea{\xea\x9f\xe93\xe9\x8b\xe8\xcc\xe7r\xe6\xd0\xe4~\xe3\x85\xe1\xcf\xdf\xcc\xdb\xf2\xd8#\xd6w\xcf\x98\xcbh\xc7J\xbe\x81\xb9G\xb5O\xb18\xa9\x08\xab\xd5\xaa\x10\xaac\xaek\xaf\xcb\xafb\xb0\xfd\xaf\x10\xaf\xfd\xad\xdd\xa9\xa4\xa7/\xa6\\\xa0\x8c\x9e\x16\xa0K\xa0\x93\x9f1\xa5r\xa7+\xaa\x97\xac\x0c\xb1\xd5\xb2h\xb4\x92\xb6\x05\xb7\x98\xb7\x91\xb6\xb8\xb5\x06\xb6\xf1\xb4\xa0\xafo\xb0\xfa\xae\xd1\xab3\xac\x87\xab\xde\xaeL\xb0\xbd\xafp\xb1.\xb6\xb5\xb6\xb0\xb8&\xbdC\xbfI\xc1&\xc6\x81\xc8\xc8\xca\xf3\xcc(\xd0\x19\xd2X\xd3N\xd4\xc1\xd4p\xd5\xc1\xd4\x86\xd4\xae\xd4A\xd4h\xd4d\xd56\xd6\x94\xd7A\xda\xf2\xdbz\xdd\n\xdf\xda\xe2v\xe3\xc6\xe4\xe2\xe7\xac\xe8\x9e\xe8\xdb\xe9\xcc\xe9{\xe9\x16\xe9_\xe7d\xe6\x08\xe5\x8d\xe1\xba\xdf\xc9\xdd\x95\xd9q\xd7\x1d\xd5\xcb\xd2\xbc\xcd\xca\xca\xae\xc7C\xc1\xc1\xbdp\xb9\x10\xb2\xba\xad)\xa8\x1f\xa4 \x9f\x98\x9c#\x9c\xac\x9d\xb1\x9e\x15\xa0\xa7\xa1\xfb\xa1b\xa2\xf5\xa1\xce\x9f\xac\x9e1\x9d\x05\x9a\xb3\x97x\x96U\x97%\x99\x82\x9b!\xa2\x81\xa5\xc7\xa8\x98\xab\xfd\xaf\x81\xb1\x85\xb2H\xb3\x03\xb3Z\xb2%\xb0\xbe\xae\x97\xad\xc7\xac\xe3\xab\xe3\xae5\xb1\x8a\xb4\xde\xb7m\xbd5\xc1\xe0\xc3\\\xc7$\xc9i\xcb\x07\xcd\xe2\xcd\xdb\xce<\xcf\x81\xcf_\xcf\x0b\xcfr\xce\xbe\xcd\xf2\xcb\xb4\xcaz\xc9\xe1\xc6\x93\xc5\xb5\xc4\xd1\xc2Y\xc2\xb5\xc2\xb5\xc2\x97\xc2\xfa\xc2\xea\xc2\xa8\xc2 \xc2\xd7\xbf&\xbe\x15\xbc\xca\xb6\xca\xb3|\xb0;\xa9\x1a\xa6Q\xa5\xd6\xa1\xd0\xa2\x17\xa8\xa2\xaa\xa0\xadw\xb3U\xb6\xc6\xb9g\xbc\x08\xc0\xe4\xc2\x9f\xc4h\xc6g\xc7\xf2\xc8\xd7\xc8\xcf\xc8\xfd\xc8W\xc8d\xc6\xbe\xc4\x02\xc3\xd5\xbf\x96\xbdi\xb9\x1a\xb5\xad\xb1\x04\xab\x9c\xa6\xec\xa0\xcd\x97\x7f\x92\xdd\x8cr\x88\x04\x82\xe5\x81\x7f\x82\x89\x85\x16\x88Q\x8b\xc7\x8f\x08\x92n\x94<\x96;\x99\xd5\x9a%\x9cf\x9ep\x9f\x86\xa0\xd9\xa1r\xa2B\xa3\x19\xa3\xe1\xa2\x01\xa3B\xa2\x81\x9f\xe5\x9d\x97\x9bQ\x97T\x94\x8c\x8e+\x8a\xa2\x86{\x7f\x1b} \x7f^~,\x81~\x89}\x8d\x1c\x91\xac\x99h\x9d\xc3\xa0\x06\xa4\xb4\xa9\x1e\xacN\xae\xb4\xb1&\xb3\xc3\xb4\xab\xb6\xae\xb7\xe1\xb8\xae\xb9\xc6\xba\xd1\xbb\x86\xbc\x88\xbd9\xbe0\xbf\xe9\xbfn\xc0T\xc1\xb3\xc1\xa9\xc1;\xc2"\xc29\xc1\xd1\xc0l\xc0\xd9\xbe\xf4\xbd\x0c\xbd\x02\xbc\xd1\xb9\x8f\xb8A\xb7\x8b\xb4\xc8\xb2\x05\xb1\xec\xad\xf3\xab\x8e\xa8j\xa5\x06\xa3\xdf\x9d\xde\x9a\n\x98\x89\x91]\x8e\xbd\x8b\xb2\x88\xc5\x81h\x80D~py\x17y%{P{\x14}\'\x80\xf3\x81\xc0\x84I\x86J\x87~\x89\xfd\x89\xc4\x88\xb0\x89\x19\x89\x9b\x86\xb4\x85"\x85\xe2\x82\x1f\x82\x83\x81;\x81\x80\x82\xe3\x81\xa1\x82\xd5\x86#\x88\xb9\x87\xbc\x8b\xbc\x8c\xef\x8c\xfa\x8d\x1b\x90\xd4\x90\x91\x91\xe3\x92\x86\x93\xb7\x94\xf7\x95\xa7\x96\xd8\x97\xf0\x98\xba\x99\xb7\x9aT\x9b\xe8\x9bO\x9cT\x9c\xba\x9b6\x9b\x1f\x9a\t\x98\x8d\x96D\x94F\x92W\x8eF\x8b\x93\x88#\x83\xd9\x7f\xe6{\xdes\x9an?h\xf4`TN\xbd=\xea\'\x00\x00J\x1d;5TP\xb5Ylb\x08i\xd4r\xd4w\xba{\xb5\x81\x8e\x84!\x88\xcc\x8b\xce\x8d\xc8\x90o\x92\x0f\x94U\x96M\x97\xcd\x97I\x98^\x99\xb2\x98{\x98\xce\x98{\x97\x0e\x97\xd1\x961\x96\xe8\x94k\x94\xd1\x93\xd3\x92W\x92"\x91z\x90\xd9\x8f\x9e\x8d\xe8\x8c\x83\x8dc\x8bp\x8b&\x8d\x8f\x8d\xe7\x8c\xc8\x8f\xdb\x90 \x91q\x92\x15\x95\x9a\x95i\x96\xfa\x97\x88\x98\xe8\x98\x9a\x99\xd7\x99?\x9aF\x9a\xe0\x99"\x9a\xd4\x99\xed\x98o\x98?\x98%\x97\x84\x96\x86\x960\x96\xc8\x95\xed\x95\xf5\x95\x85\x96\xd4\x96\x8c\x97\xe4\x98\xc3\x99t\x9a>\x9b\xa6\x9c[\x9d\x14\x9e1\x9f\x0b\xa0\xab\xa0\xe4\xa1\xb4\xa2\x98\xa3\xe2\xa4j\xa5e\xa6\xea\xa6w\xa7\x04\xa8\x1d\xa8\xc3\xa7a\xa7U\xa7;\xa6\x85\xa5\xaf\xa4\xd5\xa3e\xa2\xfd\xa0\x00\xa0Y\x9eL\x9d\\\x9bh\x99@\x98')
IIIIIIIIfffffffBBBBHH
attribute error while handling msg 1308 (profile6_t): bytearray(b'BRB\x08\x1c\x05\x00\x00=\x00\x00\x00\x00\x00\x00\x00\xe8\x03\x00\x00 \xa1\x07\x00 \xa1\x07\x00\x80\x84\x1e\x00\xf87\xc7\x01\x00\x00\x00\x00\x17\xb7Q8R\xb8~@VQ\xa2B\xae\xef\x04B\x00\x80\xb4>\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x04\xeba\t\x8a\xeb\xb0\xd5\xc9t\xd6\xba\xe1\x92\xe8C\xf3\xa6\xf6\x1e\xfa#\xff\xe7\xff\xff\xff\n\xfe\x13\xfc(\xfa\xf9\xf6\xe1\xed\x9a\xe7\xc0\xdf&\xcbB\xbb\xda\xa1\xf3\xa0\x9f\xb0\x06\xb9-\xc5\xa7\xd2\x1c\xd9\xeb\xde\xbd\xe2\xa5\xe4\x18\xe5\xb7\xe1\xc1\xde\xfc\xdaS\xd3c\xcc\x17\xbf,\xb2\xc3\x97j\x1e\x8f\x84\x8b\xa4\x8f\xb9\xf5\xcd\xc1\xd4\xc4\xd6\xd8\xd8S\xd8\xb0\xd9V\xd3B\xd1\x08\xc90\xc0\x16\xae\xda\x9a(\x87>\x831uQeWj\xa9f\xedh\xe7P\xeap\xe5\x95M\x9d\xfb\xa4?\xaa\xe9\xa4$\xa3g\xa1\x83\xb2\x1f\xb7\xa3\xbc\xf5\xba\xc0\xbb3\xb8+\xb6\xca\xb2\x84\xb4)\xb5\xad\xb9\xb5\xbaA\xbd\x0e\xc0\x1c\xc5\xfa\xcd5\xd2\xba\xd3L\xd6>\xd6\x11\xd3\xa0\xcd\xb7\xcai\xc7L\xc3\xac\xbbY\xb6\xd1\xb1\xa0\xa5W\xa1\x9e\x9cf\x83\x05kPU\xd3o(\x9a\xb1\xa5@\xacE\xb7T\xb9\x17\xba\xc1\xb6A\xb4\x02\xb2H\xae\x19\xa7\x81\xa3\xd0\xa0\xa0\x9c \x9e\xfa\xa4u\xad[\xb2Y\xb7\xfb\xba\xd1\xc0\xec\xc1v\xc3\xc5\xc4\xc6\xc4"\xc4\xa7\xc1\x17\xc0\xed\xbd\x17\xbce\xb7\xdb\xb4\xf9\xb2\xc6\xb0\xc0\xb0\x04\xb0\t\xb0+\xb0&\xb0\xf5\xaf\x19\xb0\xcb\xb3\xe9\xb5d\xb7\x93\xbe\xcc\xc1P\xc4h\xc7;\xce\xa0\xd08\xd3\xe6\xd7\xe1\xd9\xf6\xdbI\xdf\xb7\xe0E\xe2\x98\xe3\xc9\xe5\xb5\xe6\x8c\xe7\xab\xe8\x0b\xe9Q\xe9\x88\xe9\x86\xe91\xe9\xe4\xe8\xf9\xe7w\xe7\xdf\xe6c\xe5\x91\xe4t\xe3\x1b\xe1\xae\xdf)\xdem\xdct\xd8/\xd6\x9b\xd3\x9c\xcd\xee\xc9\xfb\xc5\x90\xbc\xd1\xb6D\xb0\xba\xa8\x17\x96X\x85\x13o\x13Qwj\xa1\x80\xcd\x97v\x9f\x8b\xa7\xc3\xae\xd4\xb1*\xb5\xa3\xb6\x18\xb7\x9f\xb7\xf5\xb6\x17\xb4i\xb2l\xafa\xaa,\xa7b\xa0(\x9b(\x93\xe8\x86w~Xr4g\\P\x7f<\xf80iE\x85M>W<f\x83leq\x86u\xa4{\xf7~o\x82\xb8\x89\xd4\x8dr\x91\x9d\x98\x1b\x9ct\x9f\x90\xa2\xd3\xa8\xd0\xabm\xae3\xb3H\xb5\xe7\xb7"\xbb\x93\xbc%\xbf\x99\xc0g\xc1\xe4\xc3\x91\xc4\x87\xc3\xa7\xc5\xe4\xc5\xda\xc4\xab\xc5\x06\xc8q\xc8\xa9\xc9+\xcc\x83\xcd\xe3\xce\xa7\xd1\x1d\xd3\xd1\xd4\x14\xd6\x9f\xd7\xf0\xd8p\xd9\x84\xd9\x9a\xd9\xdd\xd9\x08\xd9t\xd8\xdd\xd7\x18\xd7\xbc\xd5\xe6\xd4M\xd4|\xd3\t\xd3\xb8\xd2 \xd2\xde\xd1\x8a\xd1+\xd1\xfd\xcf\x1a\xcf\x1b\xce\xa7\xcb \xca\x99\xc7k\xc3\xa0\xc0\xda\xbb\xdf\xb7\xb8\xb0\xb6\xa8n\xa2\xf3\x96\x01\x8f\xb2\x8a\xec\x85\x1c\x8c\x90\x9c\x01\xa3\x1c\xa9|\xb3\x04\xb8\xde\xbb>\xc1B\xc31\xc5I\xc6\x1b\xc7\x86\xc7J\xc7v\xc6\xe2\xc5!\xc5\x8c\xc4%\xc4\xbd\xc3\xe2\xc3d\xc5\x1b\xc6G\xc7\x97\xc9\x80\xcaf\xcbV\xcc\x84\xccQ\xcc\xf5\xcb:\xca\xd2\xc8-\xc7\xec\xc2\x84\xc0\xac\xbd\xaf\xb7\xab\xb4\x17\xb2\xab\xaf\x1b\xab2\xae,\xb0\x9e\xb2C\xb7 \xc1\x00\xc6\xa2\xca^\xd2\xc1\xd5V\xd9\xd5\xdd\xf2\xdff\xe2\x05\xe4\t\xe6\x82\xe76\xe8\xd8\xe8<\xe9\xae\xe9a\xe9C\xe9T\xe9\x9a\xe8d\xe8\x97\xe8f\xe8\x8a\xe7\xd6\xe7\xa7\xe7\xc2\xe6q\xe6v\xe6\x02\xe5-\xe4(\xe3\xf2\xe1\x93\xdfj\xdd\xac\xdb8\xd9\x83\xd7\x0c\xd4K\xd2\x98\xd0\xf5\xcb\xff\xc9\x0c\xcaa\xc5l\xc4J\xc5H\xc4\x0f\xc2\xe1\xc1\x02\xc13\xc0\\\xbf\xc6\xbbZ\xbb\xd3\xb9\xc9\xb4\r\xb3\xa9\xb2x\xae\xa9\xad\x0e\xad\x04\xacK\xab\xcc\xa9\x9e\xa9\x1b\xaa\xb6\xa9#\xa8\xa8\xa8\x85\xa8\x01\xa8*\xa8\xcd\xa77\xa7\xbd\xa6\x82\xa5\x15\xa5@\xa4N\xa2\x90\xa2\xd7\xa5\xfa\xa7A\xab\x0f\xb1 \xb4\xa8\xb74\xbce\xbe\xc2\xc0X\xc2&\xc4\xa7\xc5h\xc6Y\xc7\xfb\xc7\xe2\xc8k\xc9\xbd\xc94\xca3\xca>\xca\x17\xca\xe4\xc9\x8f\xc96\xc9P\xc89\xc77\xc6[\xc4\xfe\xc2\xa2\xc0\xf8\xbd\x01\xbc\xda\xb7\x01\xb5\x8a\xb1\xbc\xaa\xb5\xa6]\xa2\xae\x9dp\x92\xfc\x8b}\x84\xe5r\x85g\x8ac\xecd\x17r\x8d\x899\x93\xa8\x9b\x87\xa9\x9c\xaf\xf4\xb5\x9f\xbe\xb2\xc2\xa4\xc7\x11\xcbl\xcfI\xd3|\xd5\xa9\xd7=\xd9\x04\xdc\xfe\xdc\xf7\xdd\xb9\xdfT\xe0\xc1\xe0\xeb\xe1n\xe2%\xe3\xd3\xe3\x06\xe5%\xe6\xef\xe6F\xe8\t\xe9\xa9\xe9\x8f\xea\xc9\xea\x93\xeau\xea{\xea\x9f\xe93\xe9\x8b\xe8\xcc\xe7r\xe6\xd0\xe4~\xe3\x85\xe1\xcf\xdf\xcc\xdb\xf2\xd8#\xd6w\xcf\x98\xcbh\xc7J\xbe\x81\xb9G\xb5O\xb18\xa9\x08\xab\xd5\xaa\x10\xaac\xaek\xaf\xcb\xafb\xb0\xfd\xaf\x10\xaf\xfd\xad\xdd\xa9\xa4\xa7/\xa6\\\xa0\x8c\x9e\x16\xa0K\xa0\x93\x9f1\xa5r\xa7+\xaa\x97\xac\x0c\xb1\xd5\xb2h\xb4\x92\xb6\x05\xb7\x98\xb7\x91\xb6\xb8\xb5\x06\xb6\xf1\xb4\xa0\xafo\xb0\xfa\xae\xd1\xab3\xac\x87\xab\xde\xaeL\xb0\xbd\xafp\xb1.\xb6\xb5\xb6\xb0\xb8&\xbdC\xbfI\xc1&\xc6\x81\xc8\xc8\xca\xf3\xcc(\xd0\x19\xd2X\xd3N\xd4\xc1\xd4p\xd5\xc1\xd4\x86\xd4\xae\xd4A\xd4h\xd4d\xd56\xd6\x94\xd7A\xda\xf2\xdbz\xdd\n\xdf\xda\xe2v\xe3\xc6\xe4\xe2\xe7\xac\xe8\x9e\xe8\xdb\xe9\xcc\xe9{\xe9\x16\xe9_\xe7d\xe6\x08\xe5\x8d\xe1\xba\xdf\xc9\xdd\x95\xd9q\xd7\x1d\xd5\xcb\xd2\xbc\xcd\xca\xca\xae\xc7C\xc1\xc1\xbdp\xb9\x10\xb2\xba\xad)\xa8\x1f\xa4 \x9f\x98\x9c#\x9c\xac\x9d\xb1\x9e\x15\xa0\xa7\xa1\xfb\xa1b\xa2\xf5\xa1\xce\x9f\xac\x9e1\x9d\x05\x9a\xb3\x97x\x96U\x97%\x99\x82\x9b!\xa2\x81\xa5\xc7\xa8\x98\xab\xfd\xaf\x81\xb1\x85\xb2H\xb3\x03\xb3Z\xb2%\xb0\xbe\xae\x97\xad\xc7\xac\xe3\xab\xe3\xae5\xb1\x8a\xb4\xde\xb7m\xbd5\xc1\xe0\xc3\\\xc7$\xc9i\xcb\x07\xcd\xe2\xcd\xdb\xce<\xcf\x81\xcf_\xcf\x0b\xcfr\xce\xbe\xcd\xf2\xcb\xb4\xcaz\xc9\xe1\xc6\x93\xc5\xb5\xc4\xd1\xc2Y\xc2\xb5\xc2\xb5\xc2\x97\xc2\xfa\xc2\xea\xc2\xa8\xc2 \xc2\xd7\xbf&\xbe\x15\xbc\xca\xb6\xca\xb3|\xb0;\xa9\x1a\xa6Q\xa5\xd6\xa1\xd0\xa2\x17\xa8\xa2\xaa\xa0\xadw\xb3U\xb6\xc6\xb9g\xbc\x08\xc0\xe4\xc2\x9f\xc4h\xc6g\xc7\xf2\xc8\xd7\xc8\xcf\xc8\xfd\xc8W\xc8d\xc6\xbe\xc4\x02\xc3\xd5\xbf\x96\xbdi\xb9\x1a\xb5\xad\xb1\x04\xab\x9c\xa6\xec\xa0\xcd\x97\x7f\x92\xdd\x8cr\x88\x04\x82\xe5\x81\x7f\x82\x89\x85\x16\x88Q\x8b\xc7\x8f\x08\x92n\x94<\x96;\x99\xd5\x9a%\x9cf\x9ep\x9f\x86\xa0\xd9\xa1r\xa2B\xa3\x19\xa3\xe1\xa2\x01\xa3B\xa2\x81\x9f\xe5\x9d\x97\x9bQ\x97T\x94\x8c\x8e+\x8a\xa2\x86{\x7f\x1b} \x7f^~,\x81~\x89}\x8d\x1c\x91\xac\x99h\x9d\xc3\xa0\x06\xa4\xb4\xa9\x1e\xacN\xae\xb4\xb1&\xb3\xc3\xb4\xab\xb6\xae\xb7\xe1\xb8\xae\xb9\xc6\xba\xd1\xbb\x86\xbc\x88\xbd9\xbe0\xbf\xe9\xbfn\xc0T\xc1\xb3\xc1\xa9\xc1;\xc2"\xc29\xc1\xd1\xc0l\xc0\xd9\xbe\xf4\xbd\x0c\xbd\x02\xbc\xd1\xb9\x8f\xb8A\xb7\x8b\xb4\xc8\xb2\x05\xb1\xec\xad\xf3\xab\x8e\xa8j\xa5\x06\xa3\xdf\x9d\xde\x9a\n\x98\x89\x91]\x8e\xbd\x8b\xb2\x88\xc5\x81h\x80D~py\x17y%{P{\x14}\'\x80\xf3\x81\xc0\x84I\x86J\x87~\x89\xfd\x89\xc4\x88\xb0\x89\x19\x89\x9b\x86\xb4\x85"\x85\xe2\x82\x1f\x82\x83\x81;\x81\x80\x82\xe3\x81\xa1\x82\xd5\x86#\x88\xb9\x87\xbc\x8b\xbc\x8c\xef\x8c\xfa\x8d\x1b\x90\xd4\x90\x91\x91\xe3\x92\x86\x93\xb7\x94\xf7\x95\xa7\x96\xd8\x97\xf0\x98\xba\x99\xb7\x9aT\x9b\xe8\x9bO\x9cT\x9c\xba\x9b6\x9b\x1f\x9a\t\x98\x8d\x96D\x94F\x92W\x8eF\x8b\x93\x88#\x83\xd9\x7f\xe6{\xdes\x9an?h\xf4`TN\xbd=\xea\'\x00\x00J\x1d;5TP\xb5Ylb\x08i\xd4r\xd4w\xba{\xb5\x81\x8e\x84!\x88\xcc\x8b\xce\x8d\xc8\x90o\x92\x0f\x94U\x96M\x97\xcd\x97I\x98^\x99\xb2\x98{\x98\xce\x98{\x97\x0e\x97\xd1\x961\x96\xe8\x94k\x94\xd1\x93\xd3\x92W\x92"\x91z\x90\xd9\x8f\x9e\x8d\xe8\x8c\x83\x8dc\x8bp\x8b&\x8d\x8f\x8d\xe7\x8c\xc8\x8f\xdb\x90 \x91q\x92\x15\x95\x9a\x95i\x96\xfa\x97\x88\x98\xe8\x98\x9a\x99\xd7\x99?\x9aF\x9a\xe0\x99"\x9a\xd4\x99\xed\x98o\x98?\x98%\x97\x84\x96\x86\x960\x96\xc8\x95\xed\x95\xf5\x95\x85\x96\xd4\x96\x8c\x97\xe4\x98\xc3\x99t\x9a>\x9b\xa6\x9c[\x9d\x14\x9e1\x9f\x0b\xa0\xab\xa0\xe4\xa1\xb4\xa2\x98\xa3\xe2\xa4j\xa5e\xa6\xea\xa6w\xa7\x04\xa8\x1d\xa8\xc3\xa7a\xa7U\xa7;\xa6\x85\xa5\xaf\xa4\xd5\xa3e\xa2\xfd\xa0\x00\xa0Y\x9eL\x9d\\\x9bh\x99@\x98K\xd3')
None
I send you the modified files if you require it: test (2).zip
Did I missed something in my try ?
Hi @Tchiimy :-)
We're happy for people to contribute extensions or new device types to the ping protocol, but manually modifying the auto-generated files (instead of the protocol and/or the template files) is not the recommended approach for doing so, and makes it hard to determine whether there's an error in your code implementation or in the way you tried to specify the messages.
I'd recommend modifying the relevant protocol definition file(s) instead (in the lib/ping-protocol/src/definitions/ folder), which in this case would be the ping1d.json file, or a new s500.json file based on the Ping1D one. If you then run the ping-python generator and it fails, we can try to help determine whether it's a definition issue or something else.
I would also note that the API docs you linked to specify the S500 supports most of the Ping1D messages, but isn't clear which messages or fields it doesn't support, which makes it harder to know whether a proposed S500 definition file is correct.
Hi @ES-Alexander :-)
Thanks for your answer, for the context we were mainly trying to implement the functions profile_data6t and set_ping_params from the S500 api documentation (to have access to chirp signals + more data from the pings for analysis).
We "manually modified" the definitions.py by adding:
PING1D_PROFILE6_T = 1308
PING1D_SET_PING_PARAMETERS = 1015
PING1D_PROFILE: {
"name": "profile",
"format": "IHHIIIIH",
"field_names": (
"distance",
"confidence",
"transmit_duration",
"ping_number",
"scan_start",
"scan_length",
"gain_setting",
"profile_data_length",
"profile_data",
),
"payload_length": 26
},
PING1D_PROFILE6_T: {
"name": "profile6_t",
"format": "IIIIIIIIfffffffBBBBH",
"field_names": (
"ping_number",
"start_mm",
"length_mm",
"start_ping_hz",
"end_ping_hz",
"adc_sample_hz",
"timestamp_msec",
"spare2",
"pulse_duration_sec",
"analog_gain",
"max_pwr_db",
"min_pwr_db",
"this_ping_depth_m",
"smooth_depth_m",
"fspare2",
"this_ping_depth_measurement_confidence",
"gain_index",
"decimation",
"smoothed_depth_measurement_confidence",
"num_results",
"pwr_results",
),
"payload_length": 66
},
The pingmessage.py with:
variable_msgs = [definitions.PING1D_PROFILE, definitions.PING1D_PROFILE6_T, definitions.PING360_DEVICE_DATA, ]
And the ping1d.py with:
def get_profile6_t(self):
if self.legacyRequest(definitions.PING1D_PROFILE6_T) is None:
return None
data = ({
"ping_number": self._ping_number, # Units: N/A; The ping number.
"start_mm": self._start_mm, # Units: mm; Start position for the ping.
"length_mm": self._length_mm, # Units: mm; Length of the ping measurement.
"start_ping_hz": self._start_ping_hz, # Units: Hz; Starting frequency of the ping.
"end_ping_hz": self._end_ping_hz, # Units: Hz; Ending frequency of the ping.
"adc_sample_hz": self._adc_sample_hz, # Units: Hz; ADC sampling frequency.
"timestamp_msec": self._timestamp_msec, # Units: ms; Timestamp in milliseconds.
"spare2": self._spare2, # Units: N/A; Spare field, not used.
"pulse_duration_sec": self._pulse_duration_sec, # Units: sec; Duration of the pulse.
"analog_gain": self._analog_gain, # Units: N/A; Gain used in the analog signal processing.
"max_pwr_db": self._max_pwr_db, # Units: dB; Maximum power level measured.
"min_pwr_db": self._min_pwr_db, # Units: dB; Minimum power level measured.
"this_ping_depth_m": self._this_ping_depth_m, # Units: m; Depth measurement for this ping.
"smooth_depth_m": self._smooth_depth_m, # Units: m; Smoothed depth measurement.
"fspare2": self._fspare2, # Units: N/A; Spare field, not used.
"this_ping_depth_measurement_confidence": self._this_ping_depth_measurement_confidence, # Units: %; Confidence in this ping's depth measurement.
"gain_index": self._gain_index, # Units: N/A; Index of the gain setting used.
"decimation": self._decimation, # Units: N/A; Decimation factor used.
"smoothed_depth_measurement_confidence": self._smoothed_depth_measurement_confidence, # Units: %; Confidence in the smoothed depth measurement.
"num_results": self._num_results, # Units: N/A; Number of results returned.
"pwr_results": self._pwr_results, # Units: N/A; Array of power results.
})
return data
def set_ping_params(self, start_mm, length_mm, gain_index, msec_per_ping,
pulse_len_usec, report_id, reserved, chirp, decimation,
verify=True):
# Create and pack the message
m = pingmessage.PingMessage(definitions.PING1D_SET_PING_PARAMETERS)
m.start_mm = start_mm
m.length_mm = length_mm
m.gain_index = gain_index
m.msec_per_ping = msec_per_ping
m.pulse_len_usec = pulse_len_usec
m.report_id = report_id
m.reserved = reserved
m.chirp = chirp
m.decimation = decimation
m.pack_msg_data()
self.write(m.msg_data)
if self.legacyRequest(definitions.PING1D_SET_PING_PARAMETERS) is None:
return False
if (verify and (
self._start_mm != start_mm or
self._length_mm != length_mm or
self._gain_index != gain_index or
self._msec_per_ping != msec_per_ping or
self._pulse_len_usec != pulse_len_usec or
self._report_id != report_id or
self._reserved != reserved or
self._chirp != chirp or
self._decimation != decimation)):
return False
return True # Success
We didn't knew about the generation method, if I understood I need to add the modifications in ping1d.json and then run the src/generate-markdown.py right ? Or is it better to separate the devices and make a S500.json file instead ?
We didn't knew about the generation method, if I understood I need to add the modifications in ping1d.json ... Or is it better to separate the devices and make a S500.json file instead ?
If it's just for personal use (and you know you're not going to accidentally use the S500-exclusive methods when communicating with a device which only implements the Ping1D protocol) then directly extending the Ping1D file is the simplest approach to get something that works.
If you're wanting to contribute to the ping-protocol repository and/or the ping-python library then keeping the extra messages separate makes sense, to avoid confusion over which messages each device supports. Then you'd want to make a file generate/templates/s500.py.in, with an S500 class that inherits from Ping1D and pulls in the extra S500 messages.
and then run the src/generate-markdown.py right ?
That one is for documentation of ping-protocol. In the ping-python repo the file you want to run is generate/generate-python.py
Okay thanks for the information, I'll try to do it the clean way so that someone else won't have to do it again !
If I understood, I had to create a separated json file where I put the functions from the api
pingS500.json
{
"messages": {
"set": {
"set_device_id": {
"id": "1000",
"description": "Set the device ID.",
"payload": [
{
"name": "device_id",
"type": "u8",
"description": "Device ID (0-254). 255 is reserved for broadcast messages."
}
]
},
"set_speed_of_sound": {
"id": "1002",
"description": "Set the speed of sound used for distance calculations.",
"payload": [
{
"name": "sos_mm_per_sec",
"type": "u32",
"description": "The speed of sound in mm/sec. Default is 15000000 mm/sec (1500 m/sec)."
}
]
},
"set_ping_params": {
"id": "1015",
"description": "Configure ping parameters.",
"payload": [
{
"name": "start_mm",
"type": "u32",
"description": "Start of ping range, normally 0.",
"units": "mm"
},
{
"name": "length_mm",
"type": "u32",
"description": "Length of the returned profile. End of range = start_mm + length_mm. Set to 0 for auto range.",
"units": "mm"
},
{
"name": "gain_index",
"type": "i16",
"description": "Set to -1 for auto gain, otherwise 0-13 sets gain for manual gain."
},
{
"name": "msec_per_ping",
"type": "i16",
"description": "Set to -1 to start a single ping. Otherwise, sets minimum ping interval.",
"units": "ms"
},
{
"name": "pulse_len_usec",
"type": "u16",
"description": "Set to 0 for auto mode. Currently ignored and auto duration is always used.",
"units": "µs"
},
{
"name": "report_id",
"type": "u16",
"description": "The ID of the packet type you want in response. Options: distance2 (1223), profile6 (1308), or zero. Zero disables pinging."
},
{
"name": "reserved",
"type": "u16",
"description": "Set to 0."
},
{
"name": "chirp",
"type": "u8",
"description": "Set to 1 for chirp, 0 for monotone ping."
},
{
"name": "decimation",
"type": "u8",
"description": "Set to 0 for auto range resolution in chirp mode."
}
]
}
},
"get": {
"fw_version": {
"id": "1200",
"description": "Device information",
"payload": [
{
"name": "device_type",
"type": "u8",
"description": "Device type. 0: Unknown; 1: Echosounder"
},
{
"name": "device_model",
"type": "u8",
"description": "Device model. 0: Unknown; 1: Ping1D"
},
{
"name": "version_major",
"type": "u16",
"description": "Firmware version major number."
},
{
"name": "version_minor",
"type": "u16",
"description": "Firmware version minor number."
}
]
},
"speed_of_sound": {
"id": "1203",
"description": "The speed of sound used for distance calculations.",
"payload": [
{
"name": "sos_mm_per_sec",
"type": "u32",
"description": "Current speed of sound setting in mm/sec. Default is 1500000 mm/sec.",
"units": "mm/s"
}
]
},
"range": {
"id": "1204",
"description": "The scan range for acoustic measurements.",
"payload": [
{
"name": "start_mm",
"type": "u32",
"description": "The beginning of the scan range in mm from the transducer.",
"units": "mm"
},
{
"name": "length_mm",
"type": "u32",
"description": "Length of the scan range. Measurements will be within start_mm and start_mm + length_mm.",
"units": "mm"
}
]
},
"ping_rate_msec": {
"id": "1206",
"description": "The interval between acoustic measurements.",
"payload": [
{
"name": "msec_per_ping",
"type": "u16",
"description": "Minimum time between successive pings. Can be longer depending on range.",
"units": "ms"
}
]
},
"gain_index": {
"id": "1207",
"description": "The current gain setting.",
"payload": [
{
"name": "gain_index",
"type": "u32",
"description": "The current gain index setting."
}
]
},
"altitude": {
"id": "1211",
"description": "The result of the most recent distance calculation.",
"payload": [
{
"name": "altitude_mm",
"type": "u32",
"description": "Most recent calculated distance from the device to the target.",
"units": "mm"
},
{
"name": "quality",
"type": "u8",
"description": "Confidence in the distance measurement.",
"units": "%"
}
]
},
"processor_degC": {
"id": "1213",
"description": "Temperature of the device CPU.",
"payload": [
{
"name": "centi_degC",
"type": "u32",
"description": "The temperature in centi-degrees Centigrade (100 * degrees C).",
"units": "cC"
}
]
}
}
},
"response": {
"distance2": {
"id": "1223",
"description": "A simple distance measurement.",
"payload": [
{
"name": "this_ping_distance_mm",
"type": "u32",
"description": "Most recent ping distance measurement in mm."
},
{
"name": "averaged_distance_mm",
"type": "u32",
"description": "Averaged distance over the last 20 pings in mm."
},
{
"name": "reserved",
"type": "u16",
"description": "Reserved field."
},
{
"name": "this_ping_confidence",
"type": "u8",
"description": "Confidence in this ping measurement (0-100)."
},
{
"name": "confidence_of_averaged_distance",
"type": "u8",
"description": "Confidence in the averaged distance measurement (0-100)."
},
{
"name": "timestamp",
"type": "u32",
"description": "Timestamp in milliseconds."
}
]
},
"profile6_t": {
"id": "1308",
"description": "A detailed measurement of signal strength at all depths within the ping range.",
"payload": [
{
"name": "ping_number",
"type": "u32",
"description": "Sequentially assigned ping number from 0 at power up."
},
{
"name": "start_mm",
"type": "u32",
"description": "Start of the measurement range in mm."
},
{
"name": "length_mm",
"type": "u32",
"description": "Length of the measurement range in mm."
},
{
"name": "start_ping_hz",
"type": "u32",
"description": "Starting frequency of the ping in Hz."
},
{
"name": "end_ping_hz",
"type": "u32",
"description": "Ending frequency of the ping in Hz."
},
{
"name": "adc_sample_hz",
"type": "u32",
"description": "Sampling frequency of the ADC in Hz."
},
{
"name": "timestamp_msec",
"type": "u32",
"description": "Timestamp in milliseconds."
},
{
"name": "spare2",
"type": "u32",
"description": "Reserved field."
},
{
"name": "pulse_duration_sec",
"type": "float",
"description": "Duration of the acoustic pulse in seconds."
},
{
"name": "analog_gain",
"type": "float",
"description": "Analog gain applied during measurement."
},
{
"name": "max_pwr_db",
"type": "float",
"description": "Maximum power in dB."
},
{
"name": "min_pwr_db",
"type": "float",
"description": "Minimum power in dB."
},
{
"name": "this_ping_depth_m",
"type": "float",
"description": "Depth in meters as calculated from the most recent ping."
},
{
"name": "smooth_depth_m",
"type": "float",
"description": "Smoothed calculated depth in meters."
},
{
"name": "fspare2",
"type": "float",
"description": "Reserved field, set to 0."
},
{
"name": "this_ping_depth_confidence",
"type": "u8",
"description": "Confidence in the depth measurement based on the most recent ping (0-100)."
},
{
"name": "gain_index",
"type": "u8",
"description": "Gain index used during the measurement."
},
{
"name": "decimation",
"type": "u8",
"description": "Decimation setting affecting range resolution."
},
{
"name": "smooth_depth_confidence",
"type": "u8",
"description": "Confidence in the smoothed depth measurement (0-100)."
},
{
"name": "num_results",
"type": "u16",
"description": "Number of power results reported."
},
{
"name": "pwr_results",
"type": "u16[]",
"description": "Power results scaled from min_pwr to max_pwr. Number of entries equals num_results."
}
]
}
}
}
Then I tried to create the generate/templates/s500.py.in
#!/usr/bin/env python3
# 500.py
# A device API for the Blue Robotics S500 echosounder
# ~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!
# THIS IS AN AUTOGENERATED FILE
# DO NOT EDIT
# ~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!~!
from brping import Ping1D
from brping import definitions
from brping import pingmessage
class S500(Ping1D):
"""
Class for the Blue Robotics S500 echosounder, extending the functionality
of Ping1D with additional S500-specific commands and responses.
"""
def initialize(self):
if not super().initialize():
return False
# Additional initialization specific to S500
return True
# Auto-generated "get" messages
{% for msg in messages["get"]|sort %}
def get_{{msg}}(self):
"""
@brief Get a {{msg|replace("get_", "")}} message from the device
Message description: {{messages["get"][msg].description}}
@return None if there is no reply from the device, otherwise a dictionary with:
{% for field in messages["get"][msg].payload %}
- {{field.name}}: {% if field.units %}Units: {{field.units}}; {% endif %}{{field.description}}
{% endfor %}
"""
if self.legacyRequest({{messages["get"][msg].id}}) 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 %}
# Auto-generated "set" messages
{% for msg in messages["set"]|sort %}
def {{msg}}(self{% for field in messages["set"][msg].payload %}, {{field.name}}{% endfor %}, verify=True):
"""
@brief Send a {{msg}} message to the device
Message description: {{messages["set"][msg].description}}
{% for field in messages["set"][msg].payload %}
@param {{field.name}} - {% if field.units %}Units: {{field.units}}; {% endif %}{{field.description}}
{% endfor %}
@return True if successful. False otherwise.
"""
m = pingmessage.PingMessage({{messages["set"][msg].id}})
{% for field in messages["set"][msg].payload %}
m.{{field.name}} = {{field.name}}
{% endfor %}
m.pack_msg_data()
self.write(m.msg_data)
if self.legacyRequest({{messages["set"][msg].id}}) is None:
return False
# Verify values
if verify:
return all(
getattr(self, f"_{{field.name}}") == {{field.name}}
for field in {{messages["set"][msg].payload}}
)
return True
{% endfor %}
# Auto-generated response handling
{% for msg in messages["response"]|sort %}
def handle_{{msg}}(self):
"""
@brief Handle a {{msg}} response from the device
Message description: {{messages["response"][msg].description}}
@return A dictionary with:
{% for field in messages["response"][msg].payload %}
- {{field.name}}: {% if field.units %}Units: {{field.units}}; {% endif %}{{field.description}}
{% endfor %}
"""
if not self.read_response({{messages["response"][msg].id}}):
return None
data = {
{% for field in messages["response"][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="S500 python library example.")
parser.add_argument('--device', action="store", required=False, type=str, help="S500 device port. E.g: /dev/ttyUSB0")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="S500 device baudrate. E.g: 115200")
parser.add_argument('--udp', action="store", required=False, type=str, help="S500 UDP server. E.g: 192.168.2.2:9090")
args = parser.parse_args()
if args.device is None and args.udp is None:
parser.print_help()
exit(1)
p = S500()
if args.device is not None:
p.connect_serial(args.device, args.baudrate)
elif args.udp is not None:
(host, port) = args.udp.split(':')
p.connect_udp(host, int(port))
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 %}
{% for msg in messages["set"]|sort %}
print("\ntesting {{msg}}")
result = p.{{msg}}({% for field in messages["set"][msg].payload %}{{field.name}}=0{% if not loop.last %}, {% endif %}{% endfor %})
print(" > > pass: %s < <" % (result is not None))
{% endfor %}
To be honest I've never used .py.in files and I'm a little lost on this, could someone give a look at it ?
Then after I need to run generate/generate-python.py and that's all ?
We didn't knew about the generation method, if I understood I need to add the modifications in ping1d.json ... Or is it better to separate the devices and make a S500.json file instead ?
If it's just for personal use (and you know you're not going to accidentally use the S500-exclusive methods when communicating with a device which only implements the Ping1D protocol) then directly extending the Ping1D file is the simplest approach to get something that works.
If you're wanting to contribute to the ping-protocol repository and/or the ping-python library then keeping the extra messages separate makes sense, to avoid confusion over which messages each device supports. Then you'd want to make a file
generate/templates/s500.py.in, with anS500class that inherits from Ping1D and pulls in the extra S500 messages.and then run the src/generate-markdown.py right ?
That one is for documentation of ping-protocol. In the ping-python repo the file you want to run is
generate/generate-python.py
Okay I've made a try with this json file: pings500.json
From the api documentation I made "set_ping_param" like:
"set_ping_params": {
"id": "1015",
"description": "Configure ping parameters.",
"payload": [
{
"name": "start_mm",
"type": "u32",
"description": "Start of ping range, normally 0.",
"units": "mm"
},
{
"name": "length_mm",
"type": "u32",
"description": "Length of the returned profile. End of range = start_mm + length_mm. Set to 0 for auto range.",
"units": "mm"
},
{
"name": "gain_index",
"type": "i16",
"description": "Set to -1 for auto gain, otherwise 0-13 sets gain for manual gain."
},
{
"name": "msec_per_ping",
"type": "i16",
"description": "Set to -1 to start a single ping. Otherwise, sets minimum ping interval.",
"units": "ms"
},
{
"name": "pulse_len_usec",
"type": "u16",
"description": "Set to 0 for auto mode. Currently ignored and auto duration is always used.",
"units": "µs"
},
{
"name": "report_id",
"type": "u16",
"description": "The ID of the packet type you want in response. Options: distance2 (1223), profile6 (1308), or zero. Zero disables pinging."
},
{
"name": "reserved",
"type": "u16",
"description": "Set to 0."
},
{
"name": "chirp",
"type": "u8",
"description": "Set to 1 for chirp, 0 for monotone ping."
},
{
"name": "decimation",
"type": "u8",
"description": "Set to 0 for auto range resolution in chirp mode."
}
]
}
I put profile6t and distance2 in a "response" category because I'm not sure how am I supposed to define them. Could you help me with this ?
Then I made this pings500.py.in file:
from brping import definitions
from brping import Ping1D
from brping import pingmessage
class PingS500(Ping1D):
{% 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.legacyRequest(definitions.PINGS500_{{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 %}
{% for msg in messages["set"]|sort %}
##
# @brief Send a {{msg}} message to the device\n
# Message description:\n
# {{messages["set"][msg].description}}\n
# Send the message to write the device parameters, then read the values back from the device\n
#
{% for field in messages["set"][msg].payload %}
# @param {{field.name}} - {% if field.units %}Units: {{field.units}}; {% endif %}{{field.description}}
{% endfor %}
#
# @return If verify is False, True on successful communication with the device. If verify is False, True if the new device parameters are verified to have been written correctly. False otherwise (failure to read values back or on verification failure)
def {{msg}}(self{% for field in messages["set"][msg].payload %}, {{field.name}}{% endfor %}, verify=True):
m = pingmessage.PingMessage(definitions.PINGS500_{{msg|upper}})
{% for field in messages["set"][msg].payload %}
m.{{field.name}} = {{field.name}}
{% endfor %}
m.pack_msg_data()
self.write(m.msg_data)
if self.legacyRequest(definitions.PINGS500_{{msg|replace("set_", "")|upper}}) is None:
return False
# Read back the data and check that changes have been applied
if (verify
{% if messages["set"][msg].payload %}
and ({% for field in messages["set"][msg].payload %}self._{{field.name}} != {{field.name}}{{ " or " if not loop.last }}{% endfor %})):
{% endif %}
return False
return True # success
{% endfor %}
{% for msg in messages["control"]|sort %}
##
# @brief Send a {{msg}} message to the device\n
# Message description:\n
# {{messages["control"][msg].description}}\n
#
{% for field in messages["control"][msg].payload %}
# @param {{field.name}} - {% if field.units %}Units: {{field.units}}; {% endif %}{{field.description}}
{% endfor %}
def control_{{msg}}(self{% for field in messages["control"][msg].payload %}, {{field.name}}{% endfor %}):
m = pingmessage.PingMessage(definitions.PINGS500_{{msg|upper}})
{% for field in messages["control"][msg].payload %}
m.{{field.name}} = {{field.name}}
{% endfor %}
m.pack_msg_data()
self.write(m.msg_data)
{% endfor %}
if __name__ == "__main__":
import argparse
parser = argparse.ArgumentParser(description="Ping python library example.")
parser.add_argument('--device', action="store", required=False, type=str, help="Ping device port. E.g: /dev/ttyUSB0")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="Ping device baudrate. E.g: 115200")
parser.add_argument('--udp', action="store", required=False, type=str, help="Ping UDP server. E.g: 192.168.2.2:9090")
args = parser.parse_args()
if args.device is None and args.udp is None:
parser.print_help()
exit(1)
p = PingS500()
if args.device is not None:
p.connect_serial(args.device, args.baudrate)
elif args.udp is not None:
(host, port) = args.udp.split(':')
p.connect_udp(host, int(port))
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("\ntesting set_device_id")
print(" > > pass: %s < <" % p.set_device_id(43))
print("\ntesting set_mode_auto")
print(" > > pass: %s < <" % p.set_mode_auto(False))
print("\ntesting set_range")
print(" > > pass: %s < <" % p.set_range(1000, 2000))
print("\ntesting set_speed_of_sound")
print(" > > pass: %s < <" % p.set_speed_of_sound(1444000))
print("\ntesting set_ping_interval")
print(" > > pass: %s < <" % p.set_ping_interval(36))
print("\ntesting set_gain_setting")
print(" > > pass: %s < <" % p.set_gain_setting(3))
print("\ntesting set_ping_enable")
print(" > > pass: %s < <" % p.set_ping_enable(True))
print(p)
And at the end I get this pings500.py file:
from brping import definitions
from brping import Ping1D
from brping import pingmessage
class PingS500(Ping1D):
##
# @brief Get a altitude message from the device\n
# Message description:\n
# The result of the most recent distance calculation.
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
# altitude_mm: Units: mm; Most recent calculated distance from the device to the target.\n
# quality: Units: %; Confidence in the distance measurement.\n
def get_altitude(self):
if self.legacyRequest(definitions.PINGS500_ALTITUDE) is None:
return None
data = ({
"altitude_mm": self._altitude_mm, # Units: mm; Most recent calculated distance from the device to the target.
"quality": self._quality, # Units: %; Confidence in the distance measurement.
})
return data
##
# @brief Get a fw_version message from the device\n
# Message description:\n
# Device information
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
# device_type: Device type. 0: Unknown; 1: Echosounder\n
# device_model: Device model. 0: Unknown; 1: Ping1D\n
# version_major: Firmware version major number.\n
# version_minor: Firmware version minor number.\n
def get_fw_version(self):
if self.legacyRequest(definitions.PINGS500_FW_VERSION) is None:
return None
data = ({
"device_type": self._device_type, # Device type. 0: Unknown; 1: Echosounder
"device_model": self._device_model, # Device model. 0: Unknown; 1: Ping1D
"version_major": self._version_major, # Firmware version major number.
"version_minor": self._version_minor, # Firmware version minor number.
})
return data
##
# @brief Get a gain_index message from the device\n
# Message description:\n
# The current gain setting.
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
# gain_index: The current gain index setting.\n
def get_gain_index(self):
if self.legacyRequest(definitions.PINGS500_GAIN_INDEX) is None:
return None
data = ({
"gain_index": self._gain_index, # The current gain index setting.
})
return data
##
# @brief Get a ping_rate_msec message from the device\n
# Message description:\n
# The interval between acoustic measurements.
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
# msec_per_ping: Units: ms; Minimum time between successive pings. Can be longer depending on range.\n
def get_ping_rate_msec(self):
if self.legacyRequest(definitions.PINGS500_PING_RATE_MSEC) is None:
return None
data = ({
"msec_per_ping": self._msec_per_ping, # Units: ms; Minimum time between successive pings. Can be longer depending on range.
})
return data
##
# @brief Get a processor_degC message from the device\n
# Message description:\n
# Temperature of the device CPU.
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
# centi_degC: Units: cC; The temperature in centi-degrees Centigrade (100 * degrees C).\n
def get_processor_degC(self):
if self.legacyRequest(definitions.PINGS500_PROCESSOR_DEGC) is None:
return None
data = ({
"centi_degC": self._centi_degC, # Units: cC; The temperature in centi-degrees Centigrade (100 * degrees C).
})
return data
##
# @brief Get a range message from the device\n
# Message description:\n
# The scan range for acoustic measurements.
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
# start_mm: Units: mm; The beginning of the scan range in mm from the transducer.\n
# length_mm: Units: mm; Length of the scan range. Measurements will be within start_mm and start_mm + length_mm.\n
def get_range(self):
if self.legacyRequest(definitions.PINGS500_RANGE) is None:
return None
data = ({
"start_mm": self._start_mm, # Units: mm; The beginning of the scan range in mm from the transducer.
"length_mm": self._length_mm, # Units: mm; Length of the scan range. Measurements will be within start_mm and start_mm + length_mm.
})
return data
##
# @brief Get a speed_of_sound message from the device\n
# Message description:\n
# The speed of sound used for distance calculations.
#
# @return None if there is no reply from the device, otherwise a dictionary with the following keys:\n
# sos_mm_per_sec: Units: mm/s; Current speed of sound setting in mm/sec. Default is 1500000 mm/sec.\n
def get_speed_of_sound(self):
if self.legacyRequest(definitions.PINGS500_SPEED_OF_SOUND) is None:
return None
data = ({
"sos_mm_per_sec": self._sos_mm_per_sec, # Units: mm/s; Current speed of sound setting in mm/sec. Default is 1500000 mm/sec.
})
return data
##
# @brief Send a set_device_id message to the device\n
# Message description:\n
# Set the device ID.\n
# Send the message to write the device parameters, then read the values back from the device\n
#
# @param device_id - Device ID (0-254). 255 is reserved for broadcast messages.
#
# @return If verify is False, True on successful communication with the device. If verify is False, True if the new device parameters are verified to have been written correctly. False otherwise (failure to read values back or on verification failure)
def set_device_id(self, device_id, verify=True):
m = pingmessage.PingMessage(definitions.PINGS500_SET_DEVICE_ID)
m.device_id = device_id
m.pack_msg_data()
self.write(m.msg_data)
if self.legacyRequest(definitions.PINGS500_DEVICE_ID) is None:
return False
# Read back the data and check that changes have been applied
if (verify
and (self._device_id != device_id)):
return False
return True # success
##
# @brief Send a set_ping_params message to the device\n
# Message description:\n
# Configure ping parameters.\n
# Send the message to write the device parameters, then read the values back from the device\n
#
# @param start_mm - Units: mm; Start of ping range, normally 0.
# @param length_mm - Units: mm; Length of the returned profile. End of range = start_mm + length_mm. Set to 0 for auto range.
# @param gain_index - Set to -1 for auto gain, otherwise 0-13 sets gain for manual gain.
# @param msec_per_ping - Units: ms; Set to -1 to start a single ping. Otherwise, sets minimum ping interval.
# @param pulse_len_usec - Units: µs; Set to 0 for auto mode. Currently ignored and auto duration is always used.
# @param report_id - The ID of the packet type you want in response. Options: distance2 (1223), profile6 (1308), or zero. Zero disables pinging.
# @param reserved - Set to 0.
# @param chirp - Set to 1 for chirp, 0 for monotone ping.
# @param decimation - Set to 0 for auto range resolution in chirp mode.
#
# @return If verify is False, True on successful communication with the device. If verify is False, True if the new device parameters are verified to have been written correctly. False otherwise (failure to read values back or on verification failure)
def set_ping_params(self, start_mm, length_mm, gain_index, msec_per_ping, pulse_len_usec, report_id, reserved, chirp, decimation, verify=True):
m = pingmessage.PingMessage(definitions.PINGS500_SET_PING_PARAMS)
m.start_mm = start_mm
m.length_mm = length_mm
m.gain_index = gain_index
m.msec_per_ping = msec_per_ping
m.pulse_len_usec = pulse_len_usec
m.report_id = report_id
m.reserved = reserved
m.chirp = chirp
m.decimation = decimation
m.pack_msg_data()
self.write(m.msg_data)
if self.legacyRequest(definitions.PINGS500_PING_PARAMS) is None:
return False
# Read back the data and check that changes have been applied
if (verify
and (self._start_mm != start_mm or self._length_mm != length_mm or self._gain_index != gain_index or self._msec_per_ping != msec_per_ping or self._pulse_len_usec != pulse_len_usec or self._report_id != report_id or self._reserved != reserved or self._chirp != chirp or self._decimation != decimation)):
return False
return True # success
##
# @brief Send a set_speed_of_sound message to the device\n
# Message description:\n
# Set the speed of sound used for distance calculations.\n
# Send the message to write the device parameters, then read the values back from the device\n
#
# @param sos_mm_per_sec - The speed of sound in mm/sec. Default is 15000000 mm/sec (1500 m/sec).
#
# @return If verify is False, True on successful communication with the device. If verify is False, True if the new device parameters are verified to have been written correctly. False otherwise (failure to read values back or on verification failure)
def set_speed_of_sound(self, sos_mm_per_sec, verify=True):
m = pingmessage.PingMessage(definitions.PINGS500_SET_SPEED_OF_SOUND)
m.sos_mm_per_sec = sos_mm_per_sec
m.pack_msg_data()
self.write(m.msg_data)
if self.legacyRequest(definitions.PINGS500_SPEED_OF_SOUND) is None:
return False
# Read back the data and check that changes have been applied
if (verify
and (self._sos_mm_per_sec != sos_mm_per_sec)):
return False
return True # success
if __name__ == "__main__":
import argparse
parser = argparse.ArgumentParser(description="Ping python library example.")
parser.add_argument('--device', action="store", required=False, type=str, help="Ping device port. E.g: /dev/ttyUSB0")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="Ping device baudrate. E.g: 115200")
parser.add_argument('--udp', action="store", required=False, type=str, help="Ping UDP server. E.g: 192.168.2.2:9090")
args = parser.parse_args()
if args.device is None and args.udp is None:
parser.print_help()
exit(1)
p = PingS500()
if args.device is not None:
p.connect_serial(args.device, args.baudrate)
elif args.udp is not None:
(host, port) = args.udp.split(':')
p.connect_udp(host, int(port))
print("Initialized: %s" % p.initialize())
print("\ntesting get_altitude")
result = p.get_altitude()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))
print("\ntesting get_fw_version")
result = p.get_fw_version()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))
print("\ntesting get_gain_index")
result = p.get_gain_index()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))
print("\ntesting get_ping_rate_msec")
result = p.get_ping_rate_msec()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))
print("\ntesting get_processor_degC")
result = p.get_processor_degC()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))
print("\ntesting get_range")
result = p.get_range()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))
print("\ntesting get_speed_of_sound")
result = p.get_speed_of_sound()
print(" " + str(result))
print(" > > pass: %s < <" % (result is not None))
print("\ntesting set_device_id")
print(" > > pass: %s < <" % p.set_device_id(43))
print("\ntesting set_mode_auto")
print(" > > pass: %s < <" % p.set_mode_auto(False))
print("\ntesting set_range")
print(" > > pass: %s < <" % p.set_range(1000, 2000))
print("\ntesting set_speed_of_sound")
print(" > > pass: %s < <" % p.set_speed_of_sound(1444000))
print("\ntesting set_ping_interval")
print(" > > pass: %s < <" % p.set_ping_interval(36))
print("\ntesting set_gain_setting")
print(" > > pass: %s < <" % p.set_gain_setting(3))
print("\ntesting set_ping_enable")
print(" > > pass: %s < <" % p.set_ping_enable(True))
print(p)
Could you give a look at the json and the py.in to be sure I made no mistakes ?
We do not support response category, if the messages are being received from the sensor, they should be in the get category, if you look the python file, you'll see that there is no profile6.
We do not support response category, if the messages are being received from the sensor, they should be in the get category, if you look the python file, you'll see that there is no profile6.
Okay so when I look at the api-doc at the set_ping_params function there is the report_id description saying : the ID of the packet type that you would like in response. Options are: distance2 (1223), profile6 (1308), or zero. Zero disables pinging.
And then the packet types distance2 and profile6_t are defined after in the documentation.
So how should I organize my .json or .py.in file to implement correctly this ? I suppose we have to put the distance2 and profile6_t somewhere so that the set_ping_parameters can call it properly ?
Or is there something to change in the brping\pingmessage.py ?
import struct
from brping import definitions
payload_dict = definitions.payload_dict_all
asciiMsgs = [definitions.COMMON_NACK, definitions.COMMON_ASCII_TEXT]
variable_msgs = [
definitions.PING1D_PROFILE,
definitions.PING360_DEVICE_DATA,
definitions.PING360_AUTO_DEVICE_DATA,
]
Hi @Tchiimy, to help with your work, can you provide a branch or a PR that shares your changes ? With that we will be able to run the code and see if your approach will work.
Hi @Tchiimy, to help with your work, can you provide a branch or a PR that shares your changes ? With that we will be able to run the code and see if your approach will work.
Okay I've created the commit 4c44025, did you have time to try it out ?
Hi @Tchiimy, to help with your work, can you provide a branch or a PR that shares your changes ? With that we will be able to run the code and see if your approach will work.
Okay I've created the commit 4c44025, did you have time to try it out ?
Hello @patrickelectric, Did you or your team got any time to give a look at this attempt to implement the S500 functions in ping-python ?
Hi @Tchiimy not yet! Sadly we can't test in the near future.
Not sure if this is any use to you, but Cerulean have a ROS2 driver on their github which appears to use a modified ping - https://github.com/CeruleanSonar/s500_ros2