-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcmd_vel.py
60 lines (46 loc) · 1.48 KB
/
cmd_vel.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
#!/usr/bin/env python3
import re
import json
import time
import rospy
import paho.mqtt.client as mqtt
from geometry_msgs.msg import Twist
#client config
client = mqtt.Client()
arduino_cmd_vel = Twist()
client.connect("localhost", 1883, 60)
#Publish joystick message from ROS to MQTT
def callback(data):
joystick_cmd_vel = {
"x":data.linear.x,
"z":data.angular.z
}
rospy.loginfo("sending joystick command velocity to arduino from ros to mqtt:")
rospy.loginfo(joystick_cmd_vel)
client.publish("ros_mqtt/cmd_vel", json.dumps(joystick_cmd_vel))
#Deserialize arduino data from MQTT
def deserialize(data):
data = str(data.payload.decode("utf-8"))
regex = '\d+'
match = re.findall(regex, data)
arduino_cmd_vel.linear.x = match[0]
arduino_cmd_vel.angular.z = match[1]
#Receive Message from MQTT
def on_message(client, userdata, message):
deserialize(message)
rospy.loginfo("received arduino cmd velocity from mqtt to ros:")
rospy.loginfo(arduino_cmd_vel)
#Create node for MQTT_bridge
def mqtt_bridge():
#create mode for MQTT bridge
rospy.init_node('mqtt_bridge', anonymous=True)
rospy.Subscriber('/cmd_vel', Twist, callback)
#Mqtt Subscribtion
client.loop_start()
client.subscribe("mqtt_ros/receive_arduino_msg")
client.on_message=on_message
time.sleep(30)
client.loop_stop()
rospy.spin()
if __name__ == '__main__':
mqtt_bridge()