Skip to content

Commit 38cb368

Browse files
committed
Add sensor interface for user input PCB
Add sensor interface script to read and write data from user input PCB.
1 parent c92abed commit 38cb368

File tree

4 files changed

+84
-1
lines changed

4 files changed

+84
-1
lines changed

CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@ find_package(catkin REQUIRED COMPONENTS
5151
add_message_files(
5252
FILES
5353
Weight.msg
54+
UserInput.msg
5455
)
5556

5657
## Generate services in the 'srv' folder

msg/UserInput.msg

+3
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
Header header
2+
string ingredient
3+
int32 quantity

scripts/user_input_pcb.py

+79
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
#!/usr/bin/env python3
2+
import re
3+
import rospy
4+
import serial
5+
from std_msgs.msg import Bool
6+
7+
from sensor_interface.msg import UserInput
8+
9+
10+
class UserInputInterface:
11+
publisher = None
12+
subscriber = None
13+
dispensing_in_progress = False
14+
serial = None
15+
rate = None
16+
17+
def __init__(self, device="/dev/ttyACM0", publish_rate=500) -> None:
18+
rospy.init_node("user_input_node")
19+
self.publisher = rospy.Publisher("user_input", UserInput, queue_size=10)
20+
self.subscriber = rospy.Subscriber(
21+
"/dispensing_progress", Bool, self.update_dispensing_state
22+
)
23+
self.serial = serial.Serial(device, 9600, timeout=1)
24+
self.rate = rospy.Rate(publish_rate)
25+
26+
# self.read_user_input()
27+
28+
def update_dispensing_state(self, progressMsg):
29+
self.dispensing_in_progress = progressMsg.data
30+
# print(self.dispensing_in_progress)
31+
if self.dispensing_in_progress:
32+
self.serial.write(b"t")
33+
else:
34+
self.serial.write(b"f")
35+
# Serial Write to arduino
36+
37+
def read_user_input(self):
38+
count = 0
39+
while not rospy.is_shutdown():
40+
line = self.serial.readline() # read a '\n' terminated line
41+
if type(line) is bytes:
42+
data = line.decode("utf-8")
43+
# print(f"Received = {data}")
44+
# parsed_data = re.findall(r"[-+]?(?:\d*\.\d+|\d+)", data)
45+
# print(f"Parsed = {parsed_data}")
46+
if len(data) == 0:
47+
# rospy.logerr(
48+
# f"Invalid value from sensor. Raw value received: {data}"
49+
# )
50+
# print("Stopping serial read")
51+
# break
52+
continue
53+
# message pipeline to start dispensing
54+
send_msg = UserInput()
55+
send_msg.header.seq = count
56+
send_msg.header.stamp = rospy.Time.now()
57+
send_msg.ingredient = data[: data.index("#")]
58+
send_msg.quantity = int(data[data.index("#") + 1 :])
59+
# print(f"Name: {send_msg.ingredient}")
60+
# print(f"Quantity: {send_msg.quantity}")
61+
62+
# write read input
63+
64+
# if parsed_data is of form
65+
# self.dispensing_in_progress = True
66+
count += 1
67+
self.publisher.publish(send_msg)
68+
self.rate.sleep()
69+
else:
70+
rospy.logwarn("Garbage value recieved from the weighing scale")
71+
72+
73+
if __name__ == "__main__":
74+
try:
75+
inputObj = UserInputInterface()
76+
# inputObj.read_user_input(device=rospy.get_param('device'))
77+
inputObj.read_user_input()
78+
except rospy.ROSInterruptException:
79+
pass

scripts/weighing_scale.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
def read_weight(device="/dev/ttyUSB0", publish_rate=500):
1010
pub = rospy.Publisher("weighing_scale", Weight, queue_size=10)
1111
count = 0
12-
rospy.init_node("weighing_scale", anonymous=True)
12+
rospy.init_node("weighing_scale")
1313
rate = rospy.Rate(publish_rate)
1414
ser = serial.Serial(device, 9600, timeout=1)
1515
while not rospy.is_shutdown():

0 commit comments

Comments
 (0)