38 #include "sensor_msgs/Imu.h"
39 #include "sensor_msgs/MagneticField.h"
40 #include "std_msgs/Float64.h"
47 int16_t short_data = 0;
50 short_data = short_data << 8;
89 unsigned char imu_data_buf[256];
97 if (data_size_of_buf <= 0)
122 if (strspn(str_vector[i].c_str(),
"-.0123456789") != str_vector[i].size())
132 static std::vector<std::string> imu_data_vector_buf;
134 unsigned char imu_data_buf[256];
136 std::string imu_data_oneline_buf;
139 imu_data_oneline_buf.clear();
141 int data_size_of_buf =
readFromDevice(imu_data_buf,
sizeof(imu_data_buf));
143 if (data_size_of_buf <= 0)
148 for (
int char_count = 0; char_count < data_size_of_buf; char_count++)
150 if (imu_data_buf[char_count] ==
',' || imu_data_buf[char_count] ==
'\n')
152 imu_data_vector_buf.push_back(imu_data_oneline_buf);
153 imu_data_oneline_buf.clear();
157 imu_data_oneline_buf += imu_data_buf[char_count];
174 imu_data_vector_buf.clear();
180 imu_data_vector_buf.clear();
181 ROS_WARN(
"ASCII data size is incorrect.");
216 double magnetic_field)
238 unsigned char data_buf[256];
283 sensor_msgs::Imu imu_data_raw_msg;
284 sensor_msgs::MagneticField imu_magnetic_msg;
285 std_msgs::Float64 imu_temperature_msg;
297 imu_data_raw_msg.orientation_covariance[0] = -1;
299 imu_data_raw_msg.linear_acceleration_covariance[0] = imu_data_raw_msg.linear_acceleration_covariance[4] =
300 imu_data_raw_msg.linear_acceleration_covariance[8] = linear_acceleration_cov;
302 imu_data_raw_msg.angular_velocity_covariance[0] = imu_data_raw_msg.angular_velocity_covariance[4] =
303 imu_data_raw_msg.angular_velocity_covariance[8] = angular_velocity_cov;
305 imu_magnetic_msg.magnetic_field_covariance[0] = imu_magnetic_msg.magnetic_field_covariance[4] =
306 imu_magnetic_msg.magnetic_field_covariance[8] = magnetic_field_cov;
310 imu_data_raw_msg.header.stamp = imu_magnetic_msg.header.stamp = now;
312 imu_data_raw_msg.header.frame_id = imu_magnetic_msg.header.frame_id =
frame_id_;
329 imu_data_raw_msg.angular_velocity.x = imu.
gx;
330 imu_data_raw_msg.angular_velocity.y = imu.
gy;
331 imu_data_raw_msg.angular_velocity.z = imu.
gz;