/
imu_node.py
executable file
·350 lines (291 loc) · 14.1 KB
/
imu_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
338
339
340
341
342
343
344
345
346
347
348
349
350
#!/usr/bin/env python
# Copyright (c) 2012, Tang Tiong Yew
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# * Neither the name of the Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
import rospy
import serial
import string
import math
import sys
import os ## add os use os.path.dirname
import datetime
#from time import time
from sensor_msgs.msg import Imu
from tf.transformations import quaternion_from_euler
from dynamic_reconfigure.server import Server
from razor_imu_9dof.cfg import imuConfig
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
degrees2rad = math.pi/180.0
imu_yaw_calibration = 0.0
# Callback for dynamic reconfigure requests
def reconfig_callback(config, level):
global imu_yaw_calibration
rospy.loginfo("""Reconfigure request for yaw_calibration: %d""" %(config['yaw_calibration']))
#if imu_yaw_calibration != config('yaw_calibration'):
imu_yaw_calibration = config['yaw_calibration']
rospy.loginfo("Set imu_yaw_calibration to %d" % (imu_yaw_calibration))
return config
rospy.init_node("razor_node")
#We only care about the most recent measurement, i.e. queue_size=1
pub = rospy.Publisher('imu', Imu, queue_size=1)
srv = Server(imuConfig, reconfig_callback) # define dynamic_reconfigure callback
diag_pub = rospy.Publisher('diagnostics', DiagnosticArray, queue_size=1)
diag_pub_time = rospy.get_time();
imuMsg = Imu()
# Orientation covariance estimation:
# Observed orientation noise: 0.3 degrees in x, y, 0.6 degrees in z
# Magnetometer linearity: 0.1% of full scale (+/- 2 gauss) => 4 milligauss
# Earth's magnetic field strength is ~0.5 gauss, so magnetometer nonlinearity could
# cause ~0.8% yaw error (4mgauss/0.5 gauss = 0.008) => 2.8 degrees, or 0.050 radians
# i.e. variance in yaw: 0.0025
# Accelerometer non-linearity: 0.2% of 4G => 0.008G. This could cause
# static roll/pitch error of 0.8%, owing to gravity orientation sensing
# error => 2.8 degrees, or 0.05 radians. i.e. variance in roll/pitch: 0.0025
# so set all covariances the same.
imuMsg.orientation_covariance = [
0.0025 , 0 , 0,
0, 0.0025, 0,
0, 0, 0.0025
]
# Angular velocity covariance estimation:
# Observed gyro noise: 4 counts => 0.28 degrees/sec
# nonlinearity spec: 0.2% of full scale => 8 degrees/sec = 0.14 rad/sec
# Choosing the larger (0.14) as std dev, variance = 0.14^2 ~= 0.02
imuMsg.angular_velocity_covariance = [
0.02, 0 , 0,
0 , 0.02, 0,
0 , 0 , 0.02
]
# linear acceleration covariance estimation:
# observed acceleration noise: 5 counts => 20milli-G's ~= 0.2m/s^2
# nonliniarity spec: 0.5% of full scale => 0.2m/s^2
# Choosing 0.2 as std dev, variance = 0.2^2 = 0.04
imuMsg.linear_acceleration_covariance = [
0.04 , 0 , 0,
0 , 0.04, 0,
0 , 0 , 0.04
]
default_port='/dev/ttyUSB0'
port = rospy.get_param('~port', default_port)
#read calibration parameters
port = rospy.get_param('~port', default_port)
#accelerometer
accel_x_min = rospy.get_param('~accel_x_min', -250.0)
accel_x_max = rospy.get_param('~accel_x_max', 250.0)
accel_y_min = rospy.get_param('~accel_y_min', -250.0)
accel_y_max = rospy.get_param('~accel_y_max', 250.0)
accel_z_min = rospy.get_param('~accel_z_min', -250.0)
accel_z_max = rospy.get_param('~accel_z_max', 250.0)
# magnetometer
magn_x_min = rospy.get_param('~magn_x_min', -600.0)
magn_x_max = rospy.get_param('~magn_x_max', 600.0)
magn_y_min = rospy.get_param('~magn_y_min', -600.0)
magn_y_max = rospy.get_param('~magn_y_max', 600.0)
magn_z_min = rospy.get_param('~magn_z_min', -600.0)
magn_z_max = rospy.get_param('~magn_z_max', 600.0)
calibration_magn_use_extended = rospy.get_param('~calibration_magn_use_extended', False)
magn_ellipsoid_center = rospy.get_param('~magn_ellipsoid_center', [0, 0, 0])
magn_ellipsoid_transform = rospy.get_param('~magn_ellipsoid_transform', [[0, 0, 0], [0, 0, 0], [0, 0, 0]])
imu_yaw_calibration = rospy.get_param('~imu_yaw_calibration', 0.0)
# gyroscope
gyro_average_offset_x = rospy.get_param('~gyro_average_offset_x', 0.0)
gyro_average_offset_y = rospy.get_param('~gyro_average_offset_y', 0.0)
gyro_average_offset_z = rospy.get_param('~gyro_average_offset_z', 0.0)
#rospy.loginfo("%f %f %f %f %f %f", accel_x_min, accel_x_max, accel_y_min, accel_y_max, accel_z_min, accel_z_max)
#rospy.loginfo("%f %f %f %f %f %f", magn_x_min, magn_x_max, magn_y_min, magn_y_max, magn_z_min, magn_z_max)
#rospy.loginfo("%s %s %s", str(calibration_magn_use_extended), str(magn_ellipsoid_center), str(magn_ellipsoid_transform[0][0]))
#rospy.loginfo("%f %f %f", gyro_average_offset_x, gyro_average_offset_y, gyro_average_offset_z)
# Check your COM port and baud rate
rospy.loginfo("Opening %s...", port)
try:
ser = serial.Serial(port=port, baudrate=57600, timeout=1)
except serial.serialutil.SerialException:
rospy.logerr("IMU not found at port "+port + ". Did you specify the correct port in the launch file?")
#exit
sys.exit(0)
roll=0
pitch=0
yaw=0
seq=0
accel_factor = 9.806 / 256.0 # sensor reports accel as 256.0 = 1G (9.8m/s^2). Convert to m/s^2.
rospy.loginfo("Giving the razor IMU board 5 seconds to boot...")
rospy.sleep(5) # Sleep for 5 seconds to wait for the board to boot
### configure board ###
#stop datastream
ser.write('#o0' + chr(13))
#discard old input
#automatic flush - NOT WORKING
#ser.flushInput() #discard old input, still in invalid format
#flush manually, as above command is not working
discard = ser.readlines()
#set output mode
ser.write('#ox' + chr(13)) # To start display angle and sensor reading in text
rospy.loginfo("Writing calibration values to razor IMU board...")
#set calibration values
ser.write('#caxm' + str(accel_x_min) + chr(13))
ser.write('#caxM' + str(accel_x_max) + chr(13))
ser.write('#caym' + str(accel_y_min) + chr(13))
ser.write('#cayM' + str(accel_y_max) + chr(13))
ser.write('#cazm' + str(accel_z_min) + chr(13))
ser.write('#cazM' + str(accel_z_max) + chr(13))
if (not calibration_magn_use_extended):
ser.write('#cmxm' + str(magn_x_min) + chr(13))
ser.write('#cmxM' + str(magn_x_max) + chr(13))
ser.write('#cmym' + str(magn_y_min) + chr(13))
ser.write('#cmyM' + str(magn_y_max) + chr(13))
ser.write('#cmzm' + str(magn_z_min) + chr(13))
ser.write('#cmzM' + str(magn_z_max) + chr(13))
else:
ser.write('#ccx' + str(magn_ellipsoid_center[0]) + chr(13))
ser.write('#ccy' + str(magn_ellipsoid_center[1]) + chr(13))
ser.write('#ccz' + str(magn_ellipsoid_center[2]) + chr(13))
ser.write('#ctxX' + str(magn_ellipsoid_transform[0][0]) + chr(13))
ser.write('#ctxY' + str(magn_ellipsoid_transform[0][1]) + chr(13))
ser.write('#ctxZ' + str(magn_ellipsoid_transform[0][2]) + chr(13))
ser.write('#ctyX' + str(magn_ellipsoid_transform[1][0]) + chr(13))
ser.write('#ctyY' + str(magn_ellipsoid_transform[1][1]) + chr(13))
ser.write('#ctyZ' + str(magn_ellipsoid_transform[1][2]) + chr(13))
ser.write('#ctzX' + str(magn_ellipsoid_transform[2][0]) + chr(13))
ser.write('#ctzY' + str(magn_ellipsoid_transform[2][1]) + chr(13))
ser.write('#ctzZ' + str(magn_ellipsoid_transform[2][2]) + chr(13))
ser.write('#cgx' + str(gyro_average_offset_x) + chr(13))
ser.write('#cgy' + str(gyro_average_offset_y) + chr(13))
ser.write('#cgz' + str(gyro_average_offset_z) + chr(13))
#print calibration values for verification by user
ser.flushInput()
ser.write('#p' + chr(13))
calib_data = ser.readlines()
calib_data_print = "Printing set calibration values:\r\n"
for line in calib_data:
calib_data_print += line
rospy.loginfo(calib_data_print)
#start datastream
ser.write('#o1' + chr(13))
#automatic flush - NOT WORKING
#ser.flushInput() #discard old input, still in invalid format
#flush manually, as above command is not working - it breaks the serial connection
rospy.loginfo("Flushing first 200 IMU entries...")
for x in range(0, 200):
line = ser.readline()
rospy.loginfo("Publishing IMU data...")
#f = open("raw_imu_data.log", 'w')
################################################################################
################################################################################
####TODO CHANGE THE MAIN PATH WHERE ALL THE DATA IS GOING TO BE SAVED
### This section of code create a path path with date and time each time that
### a the ros package is launched
default_number_of_samples = 1000
number_of_samples = rospy.get_param('~number_of_samples', default_number_of_samples)
default_filename = 'raw_imu_data.log'
rawdata_filename = rospy.get_param('~rawdata_filename', default_filename)
script_dir = os.path.dirname(__file__) #<-- absolute dir the script is in
#abs_file_path = os.path.join(script_dir, rawdata_filename)
default_script_dir = os.path.dirname(__file__) #<-- absolute dir the script is in
main_data_stream_path = rospy.get_param('~main_data_stream_path', default_script_dir)
# headtail_path = os.path.split(script_dir) # split the main path: '/home/map479-admin/catkin_ws/src/razor_imu_9dof' 'razor'
# datastreampath = os.path.join(headtail_path[0], 'datastream_storage') # create datastream path
datastreampath = os.path.join(main_data_stream_path, 'razor_data_path') # set datastream path
if not os.path.isdir(datastreampath):
os.makedirs(datastreampath)
#https://stackoverflow.com/questions/273192/how-can-i-create-a-directory-if-it-does-not-exist
now = datetime.datetime.now()
timenow = now.strftime('%Y%m%d_%H%M')
timenow_YmdHM = str(timenow)
time_datastreampath = os.path.join(datastreampath,timenow_YmdHM)
if not os.path.isdir(time_datastreampath):
os.mkdir(time_datastreampath)
os.chdir(time_datastreampath)
datastream_path_filename = os.path.join(time_datastreampath, rawdata_filename)
f = open(datastream_path_filename, 'w')
################################################################################
################################################################################
while not rospy.is_shutdown():
line = ser.readline()
line = line.replace("#YPRAG=","") # Delete "#YPRAG="
f.write(line) # Write to the output log file
words = string.split(line,",") # Fields split
if len(words) > 2:
#in AHRS firmware z axis points down, in ROS z axis points up (see REP 103)
yaw_deg = -float(words[0])
yaw_deg = yaw_deg + imu_yaw_calibration
if yaw_deg > 180.0:
yaw_deg = yaw_deg - 360.0
if yaw_deg < -180.0:
yaw_deg = yaw_deg + 360.0
yaw = yaw_deg*degrees2rad
#in AHRS firmware y axis points right, in ROS y axis points left (see REP 103)
pitch = -float(words[1])*degrees2rad
roll = float(words[2])*degrees2rad
# Publish message
# AHRS firmware accelerations are negated
# This means y and z are correct for ROS, but x needs reversing
imuMsg.linear_acceleration.x = -float(words[3]) * accel_factor
imuMsg.linear_acceleration.y = float(words[4]) * accel_factor
imuMsg.linear_acceleration.z = float(words[5]) * accel_factor
imuMsg.angular_velocity.x = float(words[6])
#in AHRS firmware y axis points right, in ROS y axis points left (see REP 103)
imuMsg.angular_velocity.y = -float(words[7])
#in AHRS firmware z axis points down, in ROS z axis points up (see REP 103)
imuMsg.angular_velocity.z = -float(words[8])
q = quaternion_from_euler(roll,pitch,yaw)
imuMsg.orientation.x = q[0]
imuMsg.orientation.y = q[1]
imuMsg.orientation.z = q[2]
imuMsg.orientation.w = q[3]
imuMsg.header.stamp= rospy.Time.now()
imuMsg.header.frame_id = 'base_imu_link'
imuMsg.header.seq = seq
seq = seq + 1
pub.publish(imuMsg)
if (diag_pub_time < rospy.get_time()) :
diag_pub_time += 1
diag_arr = DiagnosticArray()
diag_arr.header.stamp = rospy.get_rostime()
diag_arr.header.frame_id = '1'
diag_msg = DiagnosticStatus()
diag_msg.name = 'Razor_Imu'
diag_msg.level = DiagnosticStatus.OK
diag_msg.message = 'Received AHRS measurement'
diag_msg.values.append(KeyValue('roll (deg)',
str(roll*(180.0/math.pi))))
diag_msg.values.append(KeyValue('pitch (deg)',
str(pitch*(180.0/math.pi))))
diag_msg.values.append(KeyValue('yaw (deg)',
str(yaw*(180.0/math.pi))))
diag_msg.values.append(KeyValue('sequence number', str(seq)))
diag_arr.status.append(diag_msg)
diag_pub.publish(diag_arr)
################################################################################
################################################################################
print seq
if (seq > number_of_samples): ## with 30000 samples, data is collected for almost 10 minutes
ser.write('#o0' + chr(13))
ser.close
f.close
################################################################################
################################################################################
# ser.close
# f.close