40 #include <boost/format.hpp>
46 #include "diagnostic_msgs/DiagnosticStatus.h"
51 #include "sensor_msgs/Imu.h"
52 #include "std_srvs/Empty.h"
55 #include "microstrain_3dmgx2_imu/AddOffset.h"
57 #include "std_msgs/Bool.h"
110 node_handle_(h), private_node_handle_(
"~"), calibrate_requested_(false),
114 freq_diag_(
diagnostic_updater::FrequencyStatusParam(&desired_freq_, &desired_freq_, 0.05))
118 private_node_handle_.
param(
"autocalibrate", autocalibrate_,
true);
119 private_node_handle_.
param(
"assume_calibrated", calibrated_,
false);
120 private_node_handle_.
param(
"port", port,
string(
"/dev/ttyUSB0"));
121 private_node_handle_.
param(
"max_drift_rate", max_drift_rate_, 0.0002);
124 imu_data_pub_ = imu_node_handle.
advertise<sensor_msgs::Imu>(
"data", 100);
127 is_calibrated_pub_ = imu_node_handle.
advertise<std_msgs::Bool>(
"is_calibrated", 1,
true);
129 publish_is_calibrated();
135 bias_x_ = bias_y_ = bias_z_ = 0;
137 private_node_handle_.
param(
"frame_id", frameid_,
string(
"imu"));
138 reading.header.frame_id = frameid_;
140 private_node_handle_.
param(
"time_offset", offset_, 0.0);
142 private_node_handle_.
param(
"linear_acceleration_stdev", linear_acceleration_stdev_, 0.098);
143 private_node_handle_.
param(
"orientation_stdev", orientation_stdev_, 0.035);
144 private_node_handle_.
param(
"angular_velocity_stdev", angular_velocity_stdev_, 0.012);
146 double angular_velocity_covariance = angular_velocity_stdev_ * angular_velocity_stdev_;
147 double orientation_covariance = orientation_stdev_ * orientation_stdev_;
148 double linear_acceleration_covariance = linear_acceleration_stdev_ * linear_acceleration_stdev_;
150 reading.linear_acceleration_covariance[0] = linear_acceleration_covariance;
151 reading.linear_acceleration_covariance[4] = linear_acceleration_covariance;
152 reading.linear_acceleration_covariance[8] = linear_acceleration_covariance;
154 reading.angular_velocity_covariance[0] = angular_velocity_covariance;
155 reading.angular_velocity_covariance[4] = angular_velocity_covariance;
156 reading.angular_velocity_covariance[8] = angular_velocity_covariance;
158 reading.orientation_covariance[0] = orientation_covariance;
159 reading.orientation_covariance[4] = orientation_covariance;
160 reading.orientation_covariance[8] = orientation_covariance;
172 diagnostic_.
add( freq_diag_ );
186 va_start(va, format);
187 if (vsnprintf(buff, 1000, format, va) >= 1000)
188 ROS_DEBUG(
"Really long string in setErrorStatus, it was truncated.");
189 std::string value = std::string(buff);
190 setErrorStatus(buff);
196 if (error_status_ !=
msg)
199 ROS_ERROR(
"%s You may find further details at http://www.ros.org/wiki/microstrain_3dmgx2_imu/Troubleshooting",
msg.c_str());
203 ROS_DEBUG(
"%s You may find further details at http://www.ros.org/wiki/microstrain_3dmgx2_imu/Troubleshooting",
msg.c_str());
209 error_status_.clear();
221 }
catch (microstrain_3dmgx2_imu::Exception& e) {
223 setErrorStatus(e.what());
230 ROS_INFO(
"Initializing IMU time with offset %f.", offset_);
234 if (autocalibrate_ || calibrate_requested_)
237 calibrate_requested_ =
false;
238 autocalibrate_ =
false;
242 ROS_INFO(
"Not calibrating the IMU sensor. Use the calibrate service to calibrate it before use.");
245 ROS_INFO(
"IMU sensor initialized.");
253 }
catch (microstrain_3dmgx2_imu::Exception& e) {
257 setErrorStatusf(
"Exception thrown while starting IMU. This sometimes happens if you are not connected to an IMU or if another process is trying to access the IMU port. You may try 'lsof|grep %s' to see if other processes have the port open. %s", port.c_str(), e.what());
258 diagnostic_.
broadcast(2,
"Error opening IMU.");
266 std::string
getID(
bool output_info =
false)
269 char dev_model_num[17];
270 char dev_serial_num[17];
278 ROS_INFO(
"Connected to IMU [%s] model [%s] s/n [%s] options [%s]",
279 dev_name, dev_model_num, dev_serial_num, dev_opt);
281 char *dev_name_ptr = dev_name;
282 char *dev_model_num_ptr = dev_model_num;
283 char *dev_serial_num_ptr = dev_serial_num;
285 while (*dev_name_ptr ==
' ')
287 while (*dev_model_num_ptr ==
' ')
289 while (*dev_serial_num_ptr ==
' ')
290 dev_serial_num_ptr++;
292 return (boost::format(
"%s_%s-%s")%dev_name_ptr%dev_model_num_ptr%dev_serial_num_ptr).str();
302 }
catch (microstrain_3dmgx2_imu::Exception& e) {
304 ROS_INFO(
"Exception thrown while stopping IMU. %s", e.what());
316 static double prevtime = 0;
318 if (prevtime && prevtime - starttime > 0.05)
320 ROS_WARN(
"Full IMU loop took %f ms. Nominal is 10ms.", 1000 * (prevtime - starttime));
321 was_slow_ =
"Full IMU loop was slow.";
326 if (endtime - starttime > 0.05)
328 ROS_WARN(
"Gathering data took %f ms. Nominal is 10ms.", 1000 * (endtime - starttime));
329 was_slow_ =
"Full IMU loop was slow.";
332 prevtime = starttime;
334 imu_data_pub_.
publish(reading);
336 if (endtime - starttime > 0.05)
338 ROS_WARN(
"Publishing took %f ms. Nominal is 10 ms.", 1000 * (endtime - starttime));
339 was_slow_ =
"Full IMU loop was slow.";
345 }
catch (microstrain_3dmgx2_imu::Exception& e) {
349 ROS_WARN(
"Exception thrown while trying to get the IMU reading. This sometimes happens due to a communication glitch, or if another process is trying to access the IMU port. You may try 'lsof|grep %s' to see if other processes have the port open. %s", port.c_str(), e.what());
362 while(node_handle_.
ok()) {
363 if(publish_datum() < 0)
386 msg.data = calibrated_;
396 status.
summary(0,
"Device closed successfully.");
397 }
catch (microstrain_3dmgx2_imu::Exception& e) {
398 status.
summary(1,
"Failed to close device.");
405 status.
summary(0,
"No operation interrupted.");
407 status.
summary(1,
"There were active subscribers. Running of self test interrupted operations.");
414 status.
summary(0,
"Connected successfully.");
421 status.
summary(0,
"Read Successfully");
426 imu.
initGyros(&bias_x_, &bias_y_, &bias_z_);
428 status.
summary(0,
"Successfully calculated gyro biases.");
430 status.
add(
"Bias_X", bias_x_);
431 status.
add(
"Bias_Y", bias_y_);
432 status.
add(
"Bias_Z", bias_z_);
441 double orientation[9];
444 data.linear_acceleration.x = accel[0];
445 data.linear_acceleration.y = accel[1];
446 data.linear_acceleration.z = accel[2];
448 data.angular_velocity.x = angrate[0];
449 data.angular_velocity.y = angrate[1];
450 data.angular_velocity.z = angrate[2];
456 tf::Matrix3x3(orientation[0], orientation[3], orientation[6],
457 orientation[1], orientation[4], orientation[7],
458 orientation[2], orientation[5], orientation[8])).getRotation(quat);
474 status.
summary(2,
"Could not start streaming data.");
477 for (
int i = 0; i < 100; i++)
484 status.
summary(0,
"Data streamed successfully.");
502 status.
summary(2,
"Could not start streaming data.");
507 for (
int i = 0; i < num; i++)
519 grav += sqrt( pow(grav_x / (
double)(num), 2.0) +
520 pow(grav_y / (
double)(num), 2.0) +
521 pow(grav_z / (
double)(num), 2.0));
524 double err = (grav - 9.796);
528 status.
summary(0,
"Gravity detected correctly.");
530 status.
summaryf(2,
"Measured gravity deviates by %f", err);
533 status.
add(
"Measured gravity", grav);
534 status.
add(
"Gravity error", err);
542 status.
summary(0,
"Disconnected successfully.");
555 status.
summary(2,
"Failed to resume previous mode of operation.");
560 status.
summary(0,
"Previous operation resumed successfully.");
566 status.
summary(2,
"IMU is stopped");
567 else if (!was_slow_.empty())
569 status.
summary(1,
"Excessive delay");
573 status.
summary(0,
"IMU is running");
575 status.
add(
"Device", port);
576 status.
add(
"TF frame", frameid_);
577 status.
add(
"Error count", error_count_);
578 status.
add(
"Excessive delay", slow_count_);
585 status.
summary(0,
"Gyro is calibrated");
586 status.
add(
"X bias", bias_x_);
587 status.
add(
"Y bias", bias_y_);
588 status.
add(
"Z bias", bias_z_);
591 status.
summary(2,
"Gyro not calibrated");
597 bool addOffset(microstrain_3dmgx2_imu::AddOffset::Request &req, microstrain_3dmgx2_imu::AddOffset::Response &resp)
599 double offset = req.add_offset;
602 ROS_INFO(
"Adding %f to existing IMU time offset.", offset);
603 ROS_INFO(
"Total IMU time offset is now %f.", offset_);
609 private_node_handle_.
setParam(
"time_offset", offset_);
612 resp.total_offset = offset_;
617 bool calibrate(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
619 bool old_running = running;
623 calibrate_requested_ =
true;
635 }
catch (microstrain_3dmgx2_imu::Exception& e) {
638 publish_is_calibrated();
639 ROS_ERROR(
"Exception thrown while calibrating IMU %s", e.what());
652 imu.
initGyros(&bias_x_, &bias_y_, &bias_z_);
656 ROS_ERROR(
"Could not start streaming data to verify calibration");
664 ros::Time start_time = reading.header.stamp;
666 while(reading.header.stamp - start_time <
ros::Duration(2.0)){
668 x_rate += reading.angular_velocity.x;
669 y_rate += reading.angular_velocity.y;
670 z_rate += reading.angular_velocity.z;
674 double average_rate = sqrt(x_rate*x_rate + y_rate*y_rate + z_rate*z_rate) / count;
677 ROS_WARN(
"Imu: calibration check acquired fewer than 200 samples.");
681 if (average_rate < max_drift_rate_) {
682 ROS_INFO(
"Imu: calibration check succeeded: average angular drift %f mdeg/sec < %f mdeg/sec", average_rate*180*1000/M_PI, max_drift_rate_*180*1000/M_PI);
684 publish_is_calibrated();
685 ROS_INFO(
"IMU gyro calibration completed.");
691 publish_is_calibrated();
692 ROS_ERROR(
"Imu: calibration check failed: average angular drift = %f mdeg/sec > %f mdeg/sec", average_rate*180*1000/M_PI, max_drift_rate_*180*1000/M_PI);
702 ros::init(argc, argv,
"microstrain_3dmgx2_node");