-
Notifications
You must be signed in to change notification settings - Fork 6
/
Copy pathmpu6050_serial_to_imu_node.cpp
300 lines (259 loc) · 12.4 KB
/
mpu6050_serial_to_imu_node.cpp
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
#include <geometry_msgs/Quaternion.h>
#include <ros/ros.h>
#include <serial/serial.h>
#include <sensor_msgs/TimeReference.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/Temperature.h>
#include <std_msgs/String.h>
#include <std_srvs/Empty.h>
#include <string>
//patrick-mod
#include <boost/algorithm/clamp.hpp>
#include <tf/transform_broadcaster.h>
#include <tf/transform_datatypes.h>
bool zero_orientation_set = false;
bool set_zero_orientation(std_srvs::Empty::Request&,
std_srvs::Empty::Response&)
{
ROS_INFO("Zero Orientation Set.");
zero_orientation_set = false;
return true;
}
int main(int argc, char** argv)
{
serial::Serial ser;
std::string port;
std::string tf_parent_frame_id;
std::string tf_frame_id;
std::string frame_id;
double time_offset_in_seconds;
bool broadcast_tf;
double linear_acceleration_stddev;
double angular_velocity_stddev;
double orientation_stddev;
uint8_t last_received_message_number;
bool received_message = false;
int data_packet_start;
//patrick-mod
using boost::algorithm::clamp;
tf::Quaternion orientation;
tf::Quaternion zero_orientation;
ros::init(argc, argv, "mpu6050_serial_to_imu_node");
ros::NodeHandle private_node_handle("~");
private_node_handle.param<std::string>("port", port, "/dev/ttyACM0");
private_node_handle.param<std::string>("tf_parent_frame_id", tf_parent_frame_id, "imu_base");
private_node_handle.param<std::string>("tf_frame_id", tf_frame_id, "imu_link");
private_node_handle.param<std::string>("frame_id", frame_id, "imu");
private_node_handle.param<double>("time_offset_in_seconds", time_offset_in_seconds, 0.0);
private_node_handle.param<bool>("broadcast_tf", broadcast_tf, false);
private_node_handle.param<double>("linear_acceleration_stddev", linear_acceleration_stddev, 0.0);
private_node_handle.param<double>("angular_velocity_stddev", angular_velocity_stddev, 0.0);
private_node_handle.param<double>("orientation_stddev", orientation_stddev, 0.0);
ros::NodeHandle nh("");
ros::Publisher imu_pub = nh.advertise<sensor_msgs::Imu>("imu0", 50);
ros::Publisher imu_temperature_pub = nh.advertise<sensor_msgs::Temperature>("temperature", 50);
ros::Publisher trigger_time_pub = nh.advertise<sensor_msgs::TimeReference>("trigger_time", 50);
ros::ServiceServer service = nh.advertiseService("set_zero_orientation", set_zero_orientation);
ros::Rate r(400); // 400 hz
sensor_msgs::Imu imu;
imu.linear_acceleration_covariance[0] = linear_acceleration_stddev;
imu.linear_acceleration_covariance[4] = linear_acceleration_stddev;
imu.linear_acceleration_covariance[8] = linear_acceleration_stddev;
imu.angular_velocity_covariance[0] = angular_velocity_stddev;
imu.angular_velocity_covariance[4] = angular_velocity_stddev;
imu.angular_velocity_covariance[8] = angular_velocity_stddev;
imu.orientation_covariance[0] = orientation_stddev;
imu.orientation_covariance[4] = orientation_stddev;
imu.orientation_covariance[8] = orientation_stddev;
sensor_msgs::TimeReference trigger_time_msg;
sensor_msgs::Temperature temperature_msg;
temperature_msg.variance = 0;
static tf::TransformBroadcaster tf_br;
tf::Transform transform;
transform.setOrigin(tf::Vector3(0,0,0));
std::string input;
std::string read;
uint32_t lastTriggerCounter = 0;
while(ros::ok())
{
try
{
if (ser.isOpen())
{
// read string from serial device
if(ser.available())
{
read = ser.read(ser.available());
ROS_DEBUG("read %i new characters from serial port, adding to %i characters of old input.", (int)read.size(), (int)input.size());
input += read;
while (input.length() >= 36) // while there might be a complete package in input
{
//parse for data packets
data_packet_start = input.find("$\x03");
if (data_packet_start != std::string::npos)
{
ROS_DEBUG("found possible start of data packet at position %d", data_packet_start);
if ((input.length() >= data_packet_start + 36) && (input.compare(data_packet_start + 34, 2, "\n\r"))) //check if positions 26,27 exist, then test values
{
ROS_DEBUG("seems to be a real data package: long enough and found end characters");
// get quaternion values
int16_t w = (((0xff &(char)input[data_packet_start + 2]) << 8) | 0xff &(char)input[data_packet_start + 3]);
int16_t x = (((0xff &(char)input[data_packet_start + 4]) << 8) | 0xff &(char)input[data_packet_start + 5]);
int16_t y = (((0xff &(char)input[data_packet_start + 6]) << 8) | 0xff &(char)input[data_packet_start + 7]);
int16_t z = (((0xff &(char)input[data_packet_start + 8]) << 8) | 0xff &(char)input[data_packet_start + 9]);
double wf = w/16384.0;
double xf = x/16384.0;
double yf = y/16384.0;
double zf = z/16384.0;
tf::Quaternion orientation(xf, yf, zf, wf);
if (!zero_orientation_set)
{
zero_orientation = orientation;
zero_orientation_set = true;
}
//http://answers.ros.org/question/10124/relative-rotation-between-two-quaternions/
tf::Quaternion differential_rotation;
differential_rotation = zero_orientation.inverse() * orientation;
// get gyro values
int16_t gx = (((0xff &(char)input[data_packet_start + 10]) << 8) | 0xff &(char)input[data_packet_start + 11]);
int16_t gy = (((0xff &(char)input[data_packet_start + 12]) << 8) | 0xff &(char)input[data_packet_start + 13]);
int16_t gz = (((0xff &(char)input[data_packet_start + 14]) << 8) | 0xff &(char)input[data_packet_start + 15]);
// calculate rotational velocities in rad/s
// without the last factor the velocities were too small
// http://www.i2cdevlib.com/forums/topic/106-get-angular-velocity-from-mpu-6050/
// FIFO frequency 100 Hz -> factor 10 ?
// seems 25 is the right factor
//TODO: check / test if rotational velocities are correct -- patrick-mod from 25 to 5
//patrick-mod == add clamping
double min = -8.0;
double max = 8.0;
double gxf = clamp ((gx * (4000.0/65536.0) * (M_PI/180.0) * 22.0), min, max);
double gyf = clamp ((gy * (4000.0/65536.0) * (M_PI/180.0) * 22.0), min, max);
double gzf = clamp ((gz * (4000.0/65536.0) * (M_PI/180.0) * 22.0), min, max);
// get acelerometer values
int16_t ax = (((0xff &(char)input[data_packet_start + 16]) << 8) | 0xff &(char)input[data_packet_start + 17]);
int16_t ay = (((0xff &(char)input[data_packet_start + 18]) << 8) | 0xff &(char)input[data_packet_start + 19]);
int16_t az = (((0xff &(char)input[data_packet_start + 20]) << 8) | 0xff &(char)input[data_packet_start + 21]);
// calculate accelerations in m/s²
double axf = ax * (8.0 / 65536.0) * 9.81;
double ayf = ay * (8.0 / 65536.0) * 9.81;
double azf = az * (8.0 / 65536.0) * 9.81;
// get temperature
int16_t temperature = (((0xff &(char)input[data_packet_start + 22]) << 8) | 0xff &(char)input[data_packet_start + 23]);
double temperature_in_C = (temperature / 340.0 ) + 36.53;
ROS_DEBUG_STREAM("Temperature [in C] " << temperature_in_C);
uint8_t received_message_number = input[data_packet_start + 25];
ROS_DEBUG("received message number: %i", received_message_number);
if (received_message) // can only check for continuous numbers if already received at least one packet
{
uint8_t message_distance = received_message_number - last_received_message_number;
if ( message_distance > 1 )
{
ROS_WARN_STREAM("Missed " << message_distance - 1 << " MPU6050 data packets from arduino.");
}
}
else
{
received_message = true;
}
last_received_message_number = received_message_number;
// calculate measurement time
uint32_t ts = ( ((0xff &(char)input[data_packet_start + 26]) << 24)
| ((0xff &(char)input[data_packet_start + 27]) << 16)
| ((0xff &(char)input[data_packet_start + 28]) << 8)
| 0xff &(char)input[data_packet_start + 29]);
// get trigger counter
uint32_t triggerCounter = ( ((0xff &(char)input[data_packet_start + 30]) << 24)
| ((0xff &(char)input[data_packet_start + 31]) << 16)
| ((0xff &(char)input[data_packet_start + 32]) << 8)
| 0xff &(char)input[data_packet_start + 33]);
//patrick-mod == set to local time for onboard companion computer
ros::Time measurement_time = ros::Time::now() + ros::Duration(time_offset_in_seconds);
//ros::Time measurement_time(ts / 1000, (ts % 1000) * 1000*1000); // sec, nsec
// publish imu message
imu.header.stamp = measurement_time;
imu.header.frame_id = frame_id;
//quaternionTFToMsg(differential_rotation, imu.orientation);
imu.angular_velocity.x = gxf;
imu.angular_velocity.y = gyf;
imu.angular_velocity.z = gzf;
imu.linear_acceleration.x = axf;
imu.linear_acceleration.y = ayf;
imu.linear_acceleration.z = azf;
imu_pub.publish(imu);
// publish temperature message
temperature_msg.header.stamp = measurement_time;
temperature_msg.header.frame_id = frame_id;
temperature_msg.temperature = temperature_in_C;
imu_temperature_pub.publish(temperature_msg);
// publish triggertime message
if (triggerCounter != lastTriggerCounter){
ros::Time time_ref(0, 0);
trigger_time_msg.header.frame_id = frame_id;
trigger_time_msg.header.stamp = measurement_time;
trigger_time_msg.time_ref = time_ref;
trigger_time_pub.publish(trigger_time_msg);
lastTriggerCounter = triggerCounter;
}
// publish tf transform
if (broadcast_tf)
{
transform.setRotation(differential_rotation);
tf_br.sendTransform(tf::StampedTransform(transform, measurement_time, tf_parent_frame_id, tf_frame_id));
}
input.erase(0, data_packet_start + 28); // delete everything up to and including the processed packet
}
else
{
if (input.length() >= data_packet_start + 36)
{
input.erase(0, data_packet_start + 1); // delete up to false data_packet_start character so it is not found again
}
else
{
// do not delete start character, maybe complete package has not arrived yet
input.erase(0, data_packet_start);
}
}
}
else
{
// no start character found in input, so delete everything
input.clear();
}
}
}
}
else
{
// try and open the serial port
try
{
ser.setPort(port);
//ser.setBaudrate(57600);
ser.setBaudrate(115200);
//ser.setBaudrate(230400);
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
ser.setTimeout(to);
ser.open();
}
catch (serial::IOException& e)
{
ROS_ERROR_STREAM("Unable to open serial port " << ser.getPort() << ". Trying again in 5 seconds.");
ros::Duration(5).sleep();
}
if(ser.isOpen())
{
ROS_DEBUG_STREAM("Serial port " << ser.getPort() << " initialized and opened.");
}
}
}
catch (serial::IOException& e)
{
ROS_ERROR_STREAM("Error reading from the serial port " << ser.getPort() << ". Closing connection.");
ser.close();
}
ros::spinOnce();
r.sleep();
}
}