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