Skip to content

Commit 374df61

Browse files
committed
imports w/ tests
1 parent ccfbecf commit 374df61

File tree

7 files changed

+64
-22
lines changed

7 files changed

+64
-22
lines changed

src/rosserial_msgs/__init__.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
from ._TopicInfo import TopicInfo

src/uros/core.py

Lines changed: 26 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -11,13 +11,13 @@
1111
import uio
1212
import ustruct as struct
1313
from time import sleep, sleep_ms, sleep_us
14-
from rosserial_msgs._TopicInfo import TopicInfo
15-
from sys import platform as platform
16-
14+
from rosserial_msgs import TopicInfo
15+
import sys
16+
import os
1717
#for now threads are used, will be changed with asyncio in the future
18-
if platform == "esp32":
18+
if sys.platform == "esp32":
1919
import _thread as threading
20-
else :
20+
else:
2121
import threading
2222

2323
#rosserial protocol header
@@ -43,15 +43,15 @@ def __init__(self, serial_id, baudrate):
4343
self.uart = m.UART(self.serial_id, self.baudrate)
4444
self.uart.init(self.baudrate, bits=8, parity=None, stop=1, txbuf=0)
4545

46-
if platform == "esp32":
46+
if sys.platform == "esp32":
4747
threading.start_new_thread(self._listen, ())
4848
else:
4949
threading.Thread(target = self._listen).start()
5050

5151

5252
#method to manage and advertise topic
5353
#before publishing or subscribing
54-
def _advertise_topic(self,topic_name, msg, buffer_size=50, endpoint):
54+
def _advertise_topic(self, topic_name, msg, endpoint, buffer_size):
5555

5656
"""
5757
topic_name: eg. (Greet)
@@ -72,9 +72,7 @@ def _advertise_topic(self,topic_name, msg, buffer_size=50, endpoint):
7272
try:
7373
register.buffer_size=buffer_size
7474
except Exception as e:
75-
exc_type, exc_obj, exc_tb = sys.exc_info()
76-
fname = os.path.split(exc_tb.tb_frame.f_code.co_filename)[1]
77-
print(exc_type, fname, exc_tb.tb_lineno)
75+
print('No buffer size could be defined for topic negotiation.')
7876

7977
#serialization
8078
packet=uio.StringIO()
@@ -93,10 +91,10 @@ def _advertise_topic(self,topic_name, msg, buffer_size=50, endpoint):
9391
self.uart.write(bytearray(fpacket))
9492

9593

96-
def publish(self,topic_name,msg):
94+
def publish(self, topic_name, msg, buffer_size=1024):
9795

9896
if topic_name not in self.advertised_topics:
99-
self._advertise_topic(topic_name, msg, endpoint = 0)
97+
self._advertise_topic(topic_name, msg, 0, buffer_size)
10098

10199
#same as advertise
102100
packet=uio.StringIO()
@@ -112,7 +110,7 @@ def publish(self,topic_name,msg):
112110
fpacket=header+le(length)+crclen+topic_id+packet+crcpack
113111
self.uart.write(bytearray(fpacket))
114112

115-
def subscribe(self, topic_name, msgobj, cb):
113+
def subscribe(self, topic_name, msgobj, cb, buffer_size=1024):
116114
assert cb is not None, "Subscribe callback is not set"
117115

118116
#subscribing topic attributes are added
@@ -121,7 +119,7 @@ def subscribe(self, topic_name, msgobj, cb):
121119
#advertised if not already subscribed
122120
if topic_name not in self.advertised_topics:
123121
msg = msgobj()
124-
self._advertise_topic(topic_name, msg, endpoint = 1)
122+
self._advertise_topic(topic_name, msg, 1, buffer_size)
125123

126124
def _listen(self):
127125
while True:
@@ -152,19 +150,17 @@ def _listen(self):
152150
#incoming object msg initialized
153151
msgobj = self.subscribing_topics.get(inid)[0]
154152
except Exception :
155-
print('A subscribe packet is being sent from rosserial but not actually subscribed from microcontroller.')
153+
print('TX request was made or got message from not available subscribed topic.')
156154
#object sent to callback
157155
callback = self.subscribing_topics.get(inid)[1]
158156
fdata = msgobj()
159157
fdata = fdata.deserialize(msgdata)
160158
callback(fdata)
161159
else:
162-
raise ValueError('Message plus Topic ID Checksum is wrong')
160+
raise ValueError('Message plus Topic ID Checksum is wrong!')
163161

164162
except Exception as e:
165-
exc_type, exc_obj, exc_tb = sys.exc_info()
166-
fname = os.path.split(exc_tb.tb_frame.f_code.co_filename)[1]
167-
print(exc_type, fname, exc_tb.tb_lineno)
163+
print('No incoming data could be read for subscribes.')
168164

169165
#functions to be used in class
170166
def word(l, h):
@@ -179,4 +175,14 @@ def checksum(arr):
179175
#little-endian method
180176
def le(h):
181177
h &= 0xffff
182-
return [h & 0xff, h >> 8]
178+
return [h & 0xff, h >> 8]
179+
180+
#example code
181+
if __name__ == "__main__":
182+
from std_msgs import String
183+
from uros import NodeHandle
184+
msg=String()
185+
msg.data= 'HiItsMeMario'
186+
node=NodeHandle(2,115200)
187+
while True:
188+
node.publish('greet',msg)

tests/colorrgba.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
import uros
2-
from std_msgs._ColorRGBA import ColorRGBA #message object ColorRGBA
2+
from std_msgs import ColorRGBA #message object ColorRGBA
33
from time import sleep
44
node=uros.NodeHandle(2,115200) #node initialized, for tx2/rx2 and 115200 baudrate
55
msg=ColorRGBA() #msg object init

tests/doublesubscribe.py

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
from std_msgs import String
2+
from uros import NodeHandle
3+
import time
4+
5+
def cb(msg):
6+
print(msg.data)
7+
8+
node=NodeHandle(2,57600)
9+
node.subscribe('chatter', String, cb)
10+
node.subscribe('greet', String, cb)

tests/publishSubscribe.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
from std_msgs import String
2+
from uros import NodeHandle
3+
import time
4+
5+
def cb(msg):
6+
print(msg.data)
7+
8+
msgp=String()
9+
msgp.data='ItsMeLuigi'
10+
11+
node=NodeHandle(2,57600)
12+
node.subscribe('chatter', String, cb)
13+
14+
while True:
15+
node.publish('groop',msgp)
16+
time.sleep(1)

tests/publishhola.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#uros contains NodeHandle which is reponsable to publish and subscribe
22
import uros
3-
from std_msgs._String import String #object string imported
3+
from std_msgs import String #object string imported
44
from time import sleep
55
node=uros.NodeHandle(2,115200) #node initialized, for tx2/rx2 and 115200 baudrate
66
msg=String() #msg object init

tests/subscribetest.py

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
from std_msgs import String
2+
from uros import NodeHandle
3+
import time
4+
5+
def cb(msg):
6+
print(msg.data)
7+
8+
node=NodeHandle(2,57600)
9+
node.subscribe('chatter', String, cb)

0 commit comments

Comments
 (0)