-
Notifications
You must be signed in to change notification settings - Fork 0
/
roboteq_ros_node.py
executable file
·339 lines (258 loc) · 15 KB
/
roboteq_ros_node.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
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
#!/usr/bin/python
import serial
import time
import rospy
from geometry_msgs.msg import Twist
from std_msgs.msg import String
#########################################################################################
#########################################################################################
######################### Roboteq Controller Serial Connection ##########################
#########################################################################################
#########################################################################################
# begin the connection to the roboteq controller
try:
ser = serial.Serial(
port='/dev/ttyUSB0',
baudrate=115200, #8N1
parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE,
bytesize=serial.EIGHTBITS
)
except:
raise IOError
# reset the connection if need be
if (ser.isOpen()):
ser.close()
ser.open()
#########################################################################################
#########################################################################################
#########################################################################################
##################################### Initialize ########################################
#########################################################################################
#########################################################################################
def initialize():
global encoder_pub
rospy.init_node('roboteq_ros_node')
rospy.loginfo('status: roboteq_ros_node crearted')
rospy.Subscriber('/cmd_vel', Twist, move_callback)
encoder_pub = rospy.Publisher('roboteq_ros/encoders', String, queue_size=1000)
rospy.loginfo('status: cmd_vel subscribed, encoder_pub initiated')
#########################################################################################
#########################################################################################
#########################################################################################
############################### Get Data and Clean messages #############################
#########################################################################################
#########################################################################################
def getdata():
info = ''
while ser.inWaiting() > 0: # While data is in the buffer
info += str(ser.read())
return info
def clean_encoder_messages(message):
#===========================================================================================
# NOTE: can also be used to clean battery voltage messages |
#===========================================================================================
# Encoder output looks like this - "01 C=123456\r"
# This function reads output like that and returns "123456"
clean_message = ''
start = 0
try:
for i in range(0,len(message)):
if (message[i]== '='):
start = 1
if (message[i]== '\r'):
clean_message = int(clean_message)
return clean_message
if (start == 1):
clean_message += message[i+1]
except:
return clean_message
def clean_pulse_messages(message):
# Pulse output looks like this - "PI=1234\r"
# This function reads output like that and returns "1234"
clean_message = ''
start = 0
try:
for i in range(3,len(message)):
if (message[i]== '\r'):
clean_message = int(clean_message)
return clean_message
clean_message += message[i]
except:
return clean_message
#########################################################################################
#########################################################################################
#########################################################################################
####################################### reader ##########################################
#########################################################################################
#########################################################################################
#===========================================================================================
# --> Arguments - 1. query_id |
# 2. can_node_id |
# 3. channel |
# |
# 1. query_id - Roboteq has about 20 or so values that can be queried but the current |
# version of function can get pulse input(pulse-PI), absolute encoder |
# value(enc_abs - C), relative encoder rpm(enc_rel_rpm - RS) and battery|
# voltage(battery - V) |
# |
# 2. can_node_id - refers to the node id of the node in the RoboCAN network you wish |
# to contact |
# |
# 3. channel - refers to the motor channel of the node you wish to contact |
# |
# |
# |
# --> Returns - The function returns what is read from the serial port for the command |
#===========================================================================================
def reader(query_id,can_node_id,channel):
broadcast = ''
if query_id == 'pulse':
q_id = 'PI'
error = 0
elif query_id == 'battery':
q_id = 'V'
broadcast = '@0'+ str(can_node_id)
channel = 2
error = 0
elif query_id == 'enc_abs':
q_id = 'C'
broadcast = '@0'+ str(can_node_id)
error = 0
elif query_id == 'enc_rel_rpm':
q_id = 'SR'
broadcast = '@0'+ str(can_node_id)
error = 0
else:
error = 1
print 'error: query_id unknown'
if error == 0:
command = broadcast + '?' + q_id + ' ' + str(channel) + '\r'
ser.write(command) #enc right wheel 1
time.sleep(.005)
output = getdata()
else:
output = 'error: incorrect arguments for reader function'
return output
#########################################################################################
#########################################################################################
#########################################################################################
####################################### RC Input ########################################
#########################################################################################
#########################################################################################
pulse1 = 1490
pulse2 = 1490
def getRCInput():
global pulse1
global pulse2
try:
time.sleep(.01)
getdata() #clear buffer
pulse1 = clean_pulse_messages(reader('pulse',1,1))
pulse2 = clean_pulse_messages(reader('pulse',1,2))
except Exception as e: # catch *all* exceptions
print e
print( "error: getRCInput" )
return pulse1, pulse2
#########################################################################################
#########################################################################################
#########################################################################################
###################################### Encoders test ####################################
#########################################################################################
#########################################################################################
def getEncoders():
global encoder_pub
leftWheel = [0,0,0,0]
rightWheel = [0,0,0,0]
time.sleep(.01)
getdata() #clear buffer
leftWheel[0] = clean_encoder_messages(reader('enc_abs',1,1))
leftWheel[1] = clean_encoder_messages(reader('enc_abs',1,2))
leftWheel[2] = clean_encoder_messages(reader('enc_rel_rpm',1,1))
leftWheel[3] = clean_encoder_messages(reader('enc_rel_rpm',1,2))
rightWheel[0] = clean_encoder_messages(reader('enc_abs',2,1))
rightWheel[1] = clean_encoder_messages(reader('enc_abs',2,2))
rightWheel[2] = clean_encoder_messages(reader('enc_rel_rpm',2,1))
rightWheel[3] = clean_encoder_messages(reader('enc_rel_rpm',2,2))
print leftWheel , rightWheel
encoder_pub.publish(str(leftWheel)+str(rightWheel))
return leftWheel, rightWheel
#########################################################################################
#########################################################################################
#########################################################################################
################################## Read Battery Voltage #################################
#########################################################################################
#########################################################################################
def getVoltage():
front_controller_voltage = 0
rear_controller_voltage = 0
time.sleep(.01)
getdata() #clear buffer
front_controller_voltage = clean_encoder_messages(reader('battery',1,2))
rear_controller_voltage = clean_encoder_messages(reader('battery',2,2))
return front_controller_voltage, rear_controller_voltage
#########################################################################################
#########################################################################################
#########################################################################################
##################################### move callback #####################################
#########################################################################################
#########################################################################################
def move_callback(data):
cmd = '@01!G 1 ' + str(data.linear.x) + '\r'
ser.write(cmd)
cmd = '@01!G 2 ' + str(-data.linear.x) + '\r'
ser.write(cmd)
cmd = '@02!G 1 ' + str(data.linear.x) + '\r'
ser.write(cmd)
cmd = '@02!G 2 ' + str(-data.linear.x) + '\r'
ser.write(cmd)
#########################################################################################
#===========================================================================================|
# |
# exit = 0 |
# |
# while exit != 1: |
# try: |
# speed = 25 |
# cmd = '@01!G 1 ' + str(speed) + '\r' |
# ser.write(cmd) |
# cmd = '@01!G 2 ' + str(speed) + '\r' |
# ser.write(cmd) |
# cmd = '@02!G 1 ' + str(speed) + '\r' |
# ser.write(cmd) |
# cmd = '@02!G 2 ' + str(speed) + '\r' |
# ser.write(cmd) |
# |
# time.sleep(0.01) |
# getEncoders() |
# |
# except KeyboardInterrupt: |
# cmd = '@01!G 1 ' + str(0) + '\r' |
# ser.write(cmd) |
# cmd = '@01!G 2 ' + str(0) + '\r' |
# ser.write(cmd) |
# cmd = '@02!G 1 ' + str(0) + '\r' |
# ser.write(cmd) |
# cmd = '@02!G 2 ' + str(0) + '\r' |
# ser.write(cmd) |
# |
# getEncoders() |
# getVoltage() |
# ser.close() |
# exit = 1 |
# |
#===========================================================================================|
#########################################################################################
#########################################################################################
######################################### Main ##########################################
#########################################################################################
#########################################################################################
if __name__ == "__main__":
initialize()
try:
# rate = rospy.Rate(10)
while not rospy.is_shutdown():
getEncoders()
except KeyboardInterrupt:
ser.close()
#########################################################################################