00001 #include <boost/make_shared.hpp>
00002 #include "phidgets_imu/imu_ros_i.h"
00003
00004 namespace phidgets {
00005
00006 ImuRosI::ImuRosI(ros::NodeHandle nh, ros::NodeHandle nh_private):
00007 Imu(),
00008 nh_(nh),
00009 nh_private_(nh_private),
00010 is_connected_(false),
00011 error_number_(0),
00012 target_publish_freq_(0.0),
00013 initialized_(false)
00014 {
00015 ROS_INFO ("Starting Phidgets IMU");
00016
00017
00018
00019 if (!nh_private_.getParam ("period", period_))
00020 period_ = 8;
00021 if (!nh_private_.getParam ("frame_id", frame_id_))
00022 frame_id_ = "imu";
00023 if (!nh_private_.getParam ("angular_velocity_stdev", angular_velocity_stdev_))
00024 angular_velocity_stdev_ = 0.02 * (M_PI / 180.0);
00025 if (!nh_private_.getParam ("linear_acceleration_stdev", linear_acceleration_stdev_))
00026 linear_acceleration_stdev_ = 300.0 * 1e-6 * G;
00027
00028 bool has_compass_params =
00029 nh_private_.getParam ("cc_mag_field", cc_mag_field_)
00030 && nh_private_.getParam ("cc_offset0", cc_offset0_)
00031 && nh_private_.getParam ("cc_offset1", cc_offset1_)
00032 && nh_private_.getParam ("cc_offset2", cc_offset2_)
00033 && nh_private_.getParam ("cc_gain0", cc_gain0_)
00034 && nh_private_.getParam ("cc_gain1", cc_gain1_)
00035 && nh_private_.getParam ("cc_gain2", cc_gain2_)
00036 && nh_private_.getParam ("cc_t0", cc_T0_)
00037 && nh_private_.getParam ("cc_t1", cc_T1_)
00038 && nh_private_.getParam ("cc_t2", cc_T2_)
00039 && nh_private_.getParam ("cc_t3", cc_T3_)
00040 && nh_private_.getParam ("cc_t4", cc_T4_)
00041 && nh_private_.getParam ("cc_t5", cc_T5_);
00042
00043
00044
00045 imu_publisher_ = nh_.advertise<ImuMsg>(
00046 "imu/data_raw", 5);
00047 mag_publisher_ = nh_.advertise<MagMsg>(
00048 "imu/mag", 5);
00049 cal_publisher_ = nh_.advertise<std_msgs::Bool>(
00050 "imu/is_calibrated", 5);
00051
00052
00053
00054
00055
00056
00057
00058 target_publish_freq_ = 1000.0 / static_cast<double>(period_);
00059 imu_publisher_diag_ptr_ = boost::make_shared<diagnostic_updater::TopicDiagnostic>(
00060 "imu/data_raw",
00061 boost::ref(diag_updater_),
00062 diagnostic_updater::FrequencyStatusParam(&target_publish_freq_, &target_publish_freq_, 0.1, 5),
00063 diagnostic_updater::TimeStampStatusParam(-0.1, 0.1)
00064 );
00065
00066
00067
00068 cal_srv_ = nh_.advertiseService(
00069 "imu/calibrate", &ImuRosI::calibrateService, this);
00070
00071
00072
00073 imu_msg_.header.frame_id = frame_id_;
00074
00075
00076
00077 double ang_vel_var = angular_velocity_stdev_ * angular_velocity_stdev_;
00078 double lin_acc_var = linear_acceleration_stdev_ * linear_acceleration_stdev_;
00079
00080 for (int i = 0; i < 3; ++i)
00081 for (int j = 0; j < 3; ++j)
00082 {
00083 int idx = j*3 +i;
00084
00085 if (i == j)
00086 {
00087 imu_msg_.angular_velocity_covariance[idx] = ang_vel_var;
00088 imu_msg_.linear_acceleration_covariance[idx] = lin_acc_var;
00089 }
00090 else
00091 {
00092 imu_msg_.angular_velocity_covariance[idx] = 0.0;
00093 imu_msg_.linear_acceleration_covariance[idx] = 0.0;
00094 }
00095 }
00096
00097
00098 imu_msg_.orientation_covariance[0] = -1;
00099
00100
00101 diag_updater_.setHardwareID("none");
00102 diag_updater_.add("IMU Driver Status", this, &phidgets::ImuRosI::phidgetsDiagnostics);
00103
00104 initDevice();
00105
00106 if (has_compass_params)
00107 {
00108 int result = CPhidgetSpatial_setCompassCorrectionParameters(imu_handle_, cc_mag_field_,
00109 cc_offset0_, cc_offset1_, cc_offset2_, cc_gain0_, cc_gain1_, cc_gain2_,
00110 cc_T0_, cc_T1_, cc_T2_, cc_T3_, cc_T4_, cc_T5_);
00111 if (result)
00112 {
00113 const char *err;
00114 CPhidget_getErrorDescription(result, &err);
00115 ROS_ERROR("Problem while trying to set compass correction params: '%s'.", err);
00116 }
00117 }
00118 else
00119 {
00120 ROS_INFO("No compass correction params found.");
00121 }
00122 }
00123
00124 void ImuRosI::initDevice()
00125 {
00126 ROS_INFO("Opening device");
00127 open(-1);
00128
00129 ROS_INFO("Waiting for IMU to be attached...");
00130 int result = waitForAttachment(10000);
00131 if(result)
00132 {
00133 is_connected_ = false;
00134 error_number_ = result;
00135 diag_updater_.force_update();
00136 const char *err;
00137 CPhidget_getErrorDescription(result, &err);
00138 ROS_FATAL("Problem waiting for IMU attachment: %s Make sure the USB cable is connected and you have executed the phidgets_api/share/setup-udev.sh script.", err);
00139 }
00140
00141
00142 calibrate();
00143
00144
00145 diag_updater_.setHardwareIDf("%s-%d",
00146 getDeviceName().c_str(),
00147 getDeviceSerialNumber());
00148 }
00149
00150 bool ImuRosI::calibrateService(std_srvs::Empty::Request &req,
00151 std_srvs::Empty::Response &res)
00152 {
00153 calibrate();
00154 return true;
00155 }
00156
00157 void ImuRosI::calibrate()
00158 {
00159 ROS_INFO("Calibrating IMU...");
00160 zero();
00161 ROS_INFO("Calibrating IMU done.");
00162
00163 time_zero_ = ros::Time::now();
00164
00165
00166 std_msgs::Bool is_calibrated_msg;
00167 is_calibrated_msg.data = true;
00168 cal_publisher_.publish(is_calibrated_msg);
00169 }
00170
00171 void ImuRosI::processImuData(CPhidgetSpatial_SpatialEventDataHandle* data, int i)
00172 {
00173
00174 ros::Duration time_imu(data[i]->timestamp.seconds +
00175 data[i]->timestamp.microseconds * 1e-6);
00176
00177 ros::Time time_now = time_zero_ + time_imu;
00178
00179 double timediff = time_now.toSec() - ros::Time::now().toSec();
00180 if (fabs(timediff) > 0.1) {
00181 ROS_WARN("IMU time lags behind by %f seconds, resetting IMU time offset!", timediff);
00182 time_zero_ = ros::Time::now() - time_imu;
00183 time_now = ros::Time::now();
00184 }
00185
00186
00187
00188 if (!initialized_)
00189 {
00190 last_imu_time_ = time_now;
00191 initialized_ = true;
00192 }
00193
00194
00195
00196 boost::shared_ptr<ImuMsg> imu_msg =
00197 boost::make_shared<ImuMsg>(imu_msg_);
00198
00199 imu_msg->header.stamp = time_now;
00200
00201
00202 imu_msg->linear_acceleration.x = - data[i]->acceleration[0] * G;
00203 imu_msg->linear_acceleration.y = - data[i]->acceleration[1] * G;
00204 imu_msg->linear_acceleration.z = - data[i]->acceleration[2] * G;
00205
00206
00207 imu_msg->angular_velocity.x = data[i]->angularRate[0] * (M_PI / 180.0);
00208 imu_msg->angular_velocity.y = data[i]->angularRate[1] * (M_PI / 180.0);
00209 imu_msg->angular_velocity.z = data[i]->angularRate[2] * (M_PI / 180.0);
00210
00211 imu_publisher_.publish(imu_msg);
00212 imu_publisher_diag_ptr_->tick(time_now);
00213
00214
00215
00216 boost::shared_ptr<MagMsg> mag_msg =
00217 boost::make_shared<MagMsg>();
00218
00219 mag_msg->header.frame_id = frame_id_;
00220 mag_msg->header.stamp = time_now;
00221
00222 if (data[i]->magneticField[0] != PUNK_DBL)
00223 {
00224 mag_msg->vector.x = data[i]->magneticField[0];
00225 mag_msg->vector.y = data[i]->magneticField[1];
00226 mag_msg->vector.z = data[i]->magneticField[2];
00227 }
00228 else
00229 {
00230 double nan = std::numeric_limits<double>::quiet_NaN();
00231
00232 mag_msg->vector.x = nan;
00233 mag_msg->vector.y = nan;
00234 mag_msg->vector.z = nan;
00235 }
00236
00237 mag_publisher_.publish(mag_msg);
00238
00239
00240 diag_updater_.update();
00241 }
00242
00243 void ImuRosI::dataHandler(CPhidgetSpatial_SpatialEventDataHandle *data, int count)
00244 {
00245 for(int i = 0; i < count; i++)
00246 processImuData(data, i);
00247 }
00248
00249 void ImuRosI::attachHandler()
00250 {
00251 Imu::attachHandler();
00252 is_connected_ = true;
00253
00254 if (error_number_ == 13) error_number_ = 0;
00255 diag_updater_.force_update();
00256
00257
00258 setDataRate(period_);
00259 }
00260
00261 void ImuRosI::detachHandler()
00262 {
00263 Imu::detachHandler();
00264 is_connected_ = false;
00265 diag_updater_.force_update();
00266 }
00267
00268 void ImuRosI::errorHandler(int error)
00269 {
00270 Imu::errorHandler(error);
00271 error_number_ = error;
00272 diag_updater_.force_update();
00273 }
00274
00275 void ImuRosI::phidgetsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
00276 {
00277 if (is_connected_)
00278 {
00279 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "The Phidget is connected.");
00280 stat.add("Device Serial Number", getDeviceSerialNumber());
00281 stat.add("Device Name", getDeviceName());
00282 stat.add("Device Type", getDeviceType());
00283 }
00284 else
00285 {
00286 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "The Phidget is not connected. Check the USB.");
00287 }
00288
00289 if (error_number_ != 0)
00290 {
00291 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "The Phidget reports error.");
00292 stat.add("Error Number", error_number_);
00293 stat.add("Error message", getErrorDescription(error_number_));
00294 }
00295 }
00296
00297 }
00298