-
Notifications
You must be signed in to change notification settings - Fork 7
/
Copy pathiot_client.py
executable file
·186 lines (153 loc) · 6.42 KB
/
iot_client.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
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
#!/usr/bin/env python
# encoding=utf-8
import utils.linkkit as linkkit
# from linkkit import linkkit
import time
import requests
import json
import sys
from utils.config import IOT_KEY, IOT_SECRET, IOT_PASSWORD
from utils.utils import get_my_id
import rospy
from std_msgs.msg import String
from geometry_msgs.msg import Twist
from galileo_serial_server.msg import GalileoStatus, GalileoNativeCmds
import logging
logging.basicConfig()
def galileo_status_to_json(galileo_status):
return json.dumps({
"timestamp": galileo_status.header.stamp.to_nsec() / 1000 / 1000,
"angleGoalStatus": galileo_status.angleGoalStatus,
"busyStatus": galileo_status.busyStatus,
"chargeStatus": galileo_status.chargeStatus,
"controlSpeedTheta": galileo_status.controlSpeedTheta,
"controlSpeedX": galileo_status.controlSpeedX,
"currentAngle": galileo_status.currentAngle,
"currentPosX": galileo_status.currentPosX,
"currentPosY": galileo_status.currentPosY,
"currentSpeedTheta": galileo_status.currentSpeedTheta,
"currentSpeedX": galileo_status.currentSpeedX,
"gbaStatus": galileo_status.gbaStatus,
"gcStatus": galileo_status.gcStatus,
"loopStatus": galileo_status.loopStatus,
"mapStatus": galileo_status.mapStatus,
"navStatus": galileo_status.navStatus,
"power": galileo_status.power,
"targetDistance": galileo_status.targetDistance,
"targetNumID": galileo_status.targetNumID,
"targetStatus": galileo_status.targetStatus,
"visualStatus": galileo_status.visualStatus,
}, indent=4)
class IotClient():
def __init__(self, id, is_robot=True):
self.id = id
self.on_galileo_cmds = None
self.on_status_update = None
self.on_test = None
self.on_audio = None
self.on_speed = None
self.secret = IOT_SECRET
self.skip_count = 30
self.lk = linkkit.LinkKit(
host_name="cn-shanghai",
product_key=IOT_KEY,
device_name=self.id_to_device_name(),
device_secret=self.secret)
# self.lk.enable_logger(logging.DEBUG)
self.connect_flag = False
def on_connect(session_flag, rc, userdata):
print("Connected")
self.connect_flag = True
def on_disconnect(rc, userdata):
print("Disconnected")
self.lk.on_connect = on_connect
self.lk.on_disconnect = on_disconnect
self.lk.connect_async()
while not self.connect_flag:
time.sleep(1)
if is_robot:
_rc, _mid = self.lk.subscribe_topic(
self.lk.to_full_topic("user/galileo/cmds"))
self.lk.subscribe_topic(
self.lk.to_full_topic("user/test"))
self.lk.subscribe_topic(
self.lk.to_full_topic("user/speed"))
self.lk.subscribe_topic(
self.lk.to_full_topic("user/audio"))
self.lk.subscribe_rrpc_topic("/user/check_permission")
else:
_rc, _mid = self.lk.subscribe_topic(
self.lk.to_full_topic("user/galileo/status"))
def on_topic_message(topic, payload, qos, userdata):
if topic == self.lk.to_full_topic("user/galileo/cmds") and self.on_galileo_cmds is not None:
self.on_galileo_cmds(payload)
if topic == self.lk.to_full_topic("user/galileo/status") and self.on_status_update is not None:
self.on_status_update(payload)
if topic == self.lk.to_full_topic("user/test") and self.on_test is not None:
self.on_test(payload)
if topic == self.lk.to_full_topic("user/audio") and self.on_audio is not None:
self.on_audio(payload)
if topic == self.lk.to_full_topic("user/speed") and self.on_speed is not None:
self.on_speed(payload)
def on_rrpc_msg(rrpc_id, topic, payload, qos, userdata):
req = json.loads(payload.decode())
self.lk.thing_answer_rrpc(rrpc_id, json.dumps({
"status": IOT_PASSWORD == req["password"],
"description": payload.decode(),
}))
self.lk.on_topic_message = on_topic_message
self.lk.on_topic_rrpc_message = on_rrpc_msg
def id_to_device_name(self):
return self.id[:32]
def set_on_galileo_cmds(self, cb):
self.on_galileo_cmds = cb
def publish_galileo_cmds(self, cmd):
_rc, _mid = self.lk.publish_topic(
self.lk.to_full_topic("user/galileo/cmds"), cmd)
def publish_status(self, status):
_rc, _mid = self.lk.publish_topic(
self.lk.to_full_topic("user/galileo/status"), status, qos=0)
def set_on_status_update(self, cb):
self.on_status_update = cb
def status_received(self, status):
if self.skip_count >= 0:
self.skip_count -= 1
return
self.skip_count = 30
self.publish_status(galileo_status_to_json(status))
def set_on_test(self, cb):
self.on_test = cb
def set_on_audio(self, cb):
self.on_audio = cb
def set_on_speed(self, cb):
self.on_speed = cb
if __name__ == "__main__":
rospy.init_node("iot_client")
client = IotClient(get_my_id())
galileo_cmd_pub = rospy.Publisher("/galileo/cmds", GalileoNativeCmds, queue_size=1)
test_pub = rospy.Publisher("/pub_test", String, queue_size=1)
audio_pub = rospy.Publisher("/xiaoqiang_tts/text", String, queue_size=1)
speed_pub = rospy.Publisher("/cmd_vel", Twist, queue_size=1)
def on_cmd_received(cmd):
galileo_cmd = GalileoNativeCmds()
galileo_cmd.header.stamp = rospy.Time.now()
galileo_cmd.length = len(cmd)
galileo_cmd.data = cmd
galileo_cmd_pub.publish(galileo_cmd)
def on_test_received(msg):
test_pub.publish(msg)
def on_audio_received(msg):
audio_pub.publish(msg)
def on_speed_received(msg):
msg = json.loads(msg)
speed_twist = Twist()
speed_twist.linear.x = msg["vLinear"]
speed_twist.angular.z = msg["vAngle"]
speed_pub.publish(speed_twist)
client.set_on_galileo_cmds(on_cmd_received)
client.set_on_test(on_test_received)
client.set_on_audio(on_audio_received)
client.set_on_speed(on_speed_received)
rospy.Subscriber("/galileo/status", GalileoStatus, client.status_received)
while not rospy.is_shutdown():
time.sleep(1)