imu.cpp
Go to the documentation of this file.
1 
34 #include <multisense_ros/imu.h>
35 #include <multisense_ros/RawImuData.h>
36 #include <std_msgs/Time.h>
37 
38 using namespace crl::multisense;
39 
40 namespace multisense_ros {
41 
42 namespace { // anonymous
43 
44 //
45 // Shim for C-style driver callbacks
46 
47 void imuCB(const imu::Header& header, void* userDataP)
48 { reinterpret_cast<Imu*>(userDataP)->imuCallback(header); }
49 
50 
51 } // anonymous
52 
53 Imu::Imu(Channel* driver, std::string tf_prefix) :
54  driver_(driver),
55  device_nh_(""),
56  imu_nh_(device_nh_, "imu"),
57  accelerometer_pub_(),
58  gyroscope_pub_(),
59  magnetometer_pub_(),
60  imu_pub_(),
61  accelerometer_vector_pub_(),
62  gyroscope_vector_pub_(),
63  magnetometer_vector_pub_(),
64  imu_message_(),
65  sub_lock_(),
66  total_subscribers_(0),
67  tf_prefix_(tf_prefix),
68  accel_frameId_(tf_prefix_ + "/accel"),
69  gyro_frameId_(tf_prefix_ + "/gyro"),
70  mag_frameId_(tf_prefix_ + "/mag"),
71  next_gen_camera_(false)
72 {
73 
74  //
75  // Covariance matrix for linear acceleration and angular velocity were
76  // generated using 2 minutes of logged data with the default imu
77  // settings. Note the angular velocity covariance has the nominal gyro
78  // to accelerometer transform applied to it
79 
80  imu_message_.linear_acceleration_covariance[0] = 6.98179077e-04;
81  imu_message_.linear_acceleration_covariance[1] = 2.46789341e-06;
82  imu_message_.linear_acceleration_covariance[2] =-2.50549745e-06;
83  imu_message_.linear_acceleration_covariance[3] = 2.46789341e-06;
84  imu_message_.linear_acceleration_covariance[4] = 5.02177646e-04;
85  imu_message_.linear_acceleration_covariance[5] = 5.26265558e-05;
86  imu_message_.linear_acceleration_covariance[6] =-2.50549745e-06;
87  imu_message_.linear_acceleration_covariance[7] = 5.26265558e-05;
88  imu_message_.linear_acceleration_covariance[8] = 9.22796937e-04;
89 
90  imu_message_.angular_velocity_covariance[0] = 8.79376936e-06;
91  imu_message_.angular_velocity_covariance[1] = -3.56007627e-07;
92  imu_message_.angular_velocity_covariance[2] = 2.22611968e-07;
93  imu_message_.angular_velocity_covariance[3] = -3.56007627e-07;
94  imu_message_.angular_velocity_covariance[4] = 8.78939245e-06;
95  imu_message_.angular_velocity_covariance[5] = -8.08367486e-07;
96  imu_message_.angular_velocity_covariance[6] = 1.33981577e-05;
97  imu_message_.angular_velocity_covariance[7] = 2.22611968e-07;
98  imu_message_.angular_velocity_covariance[8] = -8.08367486e-07;
99 
100  //
101  // Get device info
102 
103  system::DeviceInfo deviceInfo;
104  Status status = driver_->getDeviceInfo(deviceInfo);
105  if (Status_Ok != status) {
106  ROS_ERROR("IMU: failed to query device info: %s",
107  Channel::statusString(status));
108  return;
109  }
110 
111  if (system::DeviceInfo::HARDWARE_REV_BCAM == deviceInfo.hardwareRevision) {
112  ROS_INFO("hardware does not support an IMU");
113  return;
114  }
115 
117  status = driver_->getVersionInfo(v);
118  if (Status_Ok != status) {
119  ROS_ERROR("IMU: Unable to query sensor firmware version: %s",
120  Channel::statusString(status));
121  return;
122  }
123 
124  //
125  // All cameras running firmware greater than version 4.3 are next gen cameras
126 
128 
129  if (v.sensorFirmwareVersion < 0x0203) {
130  ROS_WARN("IMU support requires sensor firmware v2.3 or greater (sensor is running v%d.%d)",
132  return;
133  }
134  else {
135 
136  //
137  // Only publish IMU if we know firmware 2.3 or greater is running.
138 
139  driver_->stopStreams(Source_Imu);
140 
141  accelerometer_pub_ = imu_nh_.advertise<multisense_ros::RawImuData>("accelerometer", 20,
142  std::bind(&Imu::startStreams, this),
143  std::bind(&Imu::stopStreams, this));
144 
145  gyroscope_pub_ = imu_nh_.advertise<multisense_ros::RawImuData>("gyroscope", 20,
146  std::bind(&Imu::startStreams, this),
147  std::bind(&Imu::stopStreams, this));
148 
149  //
150  // Only older cameras have a magnetometer
151 
152  if (!next_gen_camera_) {
153  magnetometer_pub_ = imu_nh_.advertise<multisense_ros::RawImuData>("magnetometer", 20,
154  std::bind(&Imu::startStreams, this),
155  std::bind(&Imu::stopStreams, this));
156 
157  magnetometer_vector_pub_ = imu_nh_.advertise<geometry_msgs::Vector3Stamped>("magnetometer_vector", 20,
158  std::bind(&Imu::startStreams, this),
159  std::bind(&Imu::stopStreams, this));
160 
161  }
162 
163  imu_pub_ = imu_nh_.advertise<sensor_msgs::Imu>("imu_data", 20,
164  std::bind(&Imu::startStreams, this),
165  std::bind(&Imu::stopStreams, this));
166 
167  accelerometer_vector_pub_ = imu_nh_.advertise<geometry_msgs::Vector3Stamped>("accelerometer_vector", 20,
168  std::bind(&Imu::startStreams, this),
169  std::bind(&Imu::stopStreams, this));
170 
171  gyroscope_vector_pub_ = imu_nh_.advertise<geometry_msgs::Vector3Stamped>("gyroscope_vector", 20,
172  std::bind(&Imu::startStreams, this),
173  std::bind(&Imu::stopStreams, this));
174  driver_->addIsolatedCallback(imuCB, this);
175  }
176 
177  if (next_gen_camera_)
178  {
179  accel_frameId_ = tf_prefix_ + "/imu";
180  gyro_frameId_ = tf_prefix + "/imu";
181  }
182 
183  //
184  // Initialize the sensor_msgs::Imu topic
185  // We will publish the data in the accelerometer frame applying the
186  // transform from the /gyro to the /accel frame to the gyroscope data
187 
188  imu_message_.header.frame_id = accel_frameId_;
189 
190 }
191 
193 {
194  driver_->stopStreams(Source_Imu);
196 }
197 
198 void Imu::imuCallback(const imu::Header& header)
199 {
200  std::vector<imu::Sample>::const_iterator it = header.samples.begin();
201 
202  const uint32_t accel_subscribers = accelerometer_pub_.getNumSubscribers();
203  const uint32_t gyro_subscribers = gyroscope_pub_.getNumSubscribers();
204  const uint32_t mag_subscribers = next_gen_camera_ ? 0 : magnetometer_pub_.getNumSubscribers();
205  const uint32_t imu_subscribers = imu_pub_.getNumSubscribers();
206  const uint32_t accel_vector_subscribers = accelerometer_vector_pub_.getNumSubscribers();
207  const uint32_t gyro_vector_subscribers = gyroscope_vector_pub_.getNumSubscribers();
208  const uint32_t mag_vector_subscribers = next_gen_camera_ ? 0 : magnetometer_vector_pub_.getNumSubscribers();
209 
210  for(; it != header.samples.end(); ++it) {
211 
212  const imu::Sample& s = *it;
213 
214  multisense_ros::RawImuData msg;
215  geometry_msgs::Vector3Stamped vector_msg;
216 
217  msg.time_stamp = ros::Time(s.timeSeconds,
218  1000 * s.timeMicroSeconds);
219  msg.x = s.x;
220  msg.y = s.y;
221  msg.z = s.z;
222 
223  vector_msg.header.stamp = msg.time_stamp;
224  vector_msg.vector.x = s.x;
225  vector_msg.vector.y = s.y;
226  vector_msg.vector.z = s.z;
227 
228  //
229  // There are cases where the accel and gyro data are published with the same timestamps. Instead of
230  // publishing two IMU messages for each, publish a new IMU message once we know for sure we have all the
231  // samples from the same timestamp
232 
233  const bool publish_previous_imu_message = (s.type == imu::Sample::Type_Accelerometer ||
234  s.type == imu::Sample::Type_Gyroscope) &&
235  imu_message_.header.stamp != msg.time_stamp;
236 
237  if (publish_previous_imu_message && imu_subscribers > 0)
239 
240  imu_message_.header.stamp = msg.time_stamp;
241 
242  switch(s.type) {
243  case imu::Sample::Type_Accelerometer:
244  //
245  // Convert from g to m/s^2
246 
247  imu_message_.linear_acceleration.x = s.x * 9.80665;
248  imu_message_.linear_acceleration.y = s.y * 9.80665;
249  imu_message_.linear_acceleration.z = s.z * 9.80665;
250 
251  if (accel_subscribers > 0)
253 
254  if (accel_vector_subscribers > 0) {
255  vector_msg.header.frame_id = accel_frameId_;
257  }
258 
259  break;
260  case imu::Sample::Type_Gyroscope:
261  //
262  // Convert from deg/sec to rad/sec and apply the nominal
263  // calibration from the gyro to the accelerometer. Since all points
264  // on a rigid body have the same angular velocity only the rotation
265  // about the z axis of 90 degrees needs to be applied. (i.e.
266  // new_x = orig_y ; new_y = -orig_x). Note this only applies for older cameras where
267  // the gyro and accelerometer are on independent ICs.
268 
269  if (next_gen_camera_) {
270  imu_message_.angular_velocity.x = s.x * M_PI/180.;
271  imu_message_.angular_velocity.y = s.y * M_PI/180.;
272  imu_message_.angular_velocity.z = s.z * M_PI/180.;
273  }
274  else {
275  imu_message_.angular_velocity.x = s.y * M_PI/180.;
276  imu_message_.angular_velocity.y = -s.x * M_PI/180.;
277  imu_message_.angular_velocity.z = s.z * M_PI/180.;
278  }
279 
280  if (gyro_subscribers > 0)
282 
283  if (gyro_vector_subscribers > 0) {
284  vector_msg.header.frame_id = gyro_frameId_;
285  gyroscope_vector_pub_.publish(vector_msg);
286  }
287 
288  break;
289  case imu::Sample::Type_Magnetometer:
290 
291  if (!next_gen_camera_) {
292  if (mag_subscribers > 0)
294 
295  if (mag_vector_subscribers > 0) {
296  vector_msg.header.frame_id = mag_frameId_;
297  magnetometer_vector_pub_.publish(vector_msg);
298  }
299  }
300 
301  break;
302  }
303  }
304 }
305 
306 
308 {
309  if (0 == total_subscribers_) {
310  Status status = driver_->startStreams(Source_Imu);
311  if (Status_Ok != status)
312  ROS_ERROR("IMU: failed to start streams: %s",
313  Channel::statusString(status));
314  }
315 
320 }
321 
323 {
328 
329  if (total_subscribers_ <= 0){
330  Status status = driver_->stopStreams(Source_Imu);
331  if (Status_Ok != status)
332  ROS_ERROR("IMU: failed to stop streams: %s",
333  Channel::statusString(status));
334  }
335 }
336 
337 } // namespace
multisense_ros::Imu::accel_frameId_
std::string accel_frameId_
Definition: imu.h:101
multisense_ros::Imu::mag_frameId_
std::string mag_frameId_
Definition: imu.h:103
multisense_ros::Imu::accelerometer_pub_
ros::Publisher accelerometer_pub_
Definition: imu.h:72
crl::multisense::Channel::getDeviceInfo
virtual Status getDeviceInfo(system::DeviceInfo &info)=0
msg
msg
multisense_ros::Imu::magnetometer_vector_pub_
ros::Publisher magnetometer_vector_pub_
Definition: imu.h:84
multisense_ros::Imu::gyroscope_pub_
ros::Publisher gyroscope_pub_
Definition: imu.h:73
multisense_ros::Imu::imu_nh_
ros::NodeHandle imu_nh_
Definition: imu.h:67
s
XmlRpcServer s
crl::multisense::imu::Header
multisense_ros::Imu::total_subscribers_
int32_t total_subscribers_
Definition: imu.h:94
multisense_ros::Imu::tf_prefix_
const std::string tf_prefix_
Definition: imu.h:100
crl::multisense::Channel::removeIsolatedCallback
virtual Status removeIsolatedCallback(apriltag::Callback callback)=0
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
multisense_ros::Imu::gyroscope_vector_pub_
ros::Publisher gyroscope_vector_pub_
Definition: imu.h:83
crl::multisense::Channel::startStreams
virtual Status startStreams(DataSource mask)=0
imu.h
multisense_ros::Status
Definition: status.h:43
multisense_ros::Imu::~Imu
~Imu()
Definition: imu.cpp:192
multisense_ros
Definition: camera.h:58
crl::multisense::imu::Sample
multisense_ros::Imu::accelerometer_vector_pub_
ros::Publisher accelerometer_vector_pub_
Definition: imu.h:82
crl::multisense::system::DeviceInfo
crl::multisense::system::DeviceInfo::hardwareRevision
uint32_t hardwareRevision
multisense_ros::Imu::imu_message_
sensor_msgs::Imu imu_message_
Definition: imu.h:88
ROS_WARN
#define ROS_WARN(...)
crl::multisense::system::VersionInfo::sensorFirmwareVersion
VersionType sensorFirmwareVersion
crl::multisense::Channel::getVersionInfo
virtual Status getVersionInfo(system::VersionInfo &v)=0
crl::multisense::Channel::addIsolatedCallback
virtual Status addIsolatedCallback(apriltag::Callback callback, void *userDataP=NULL)=0
multisense_ros::Imu::imu_pub_
ros::Publisher imu_pub_
Definition: imu.h:78
crl::multisense::system::VersionInfo
crl::multisense::Channel
ros::Time
multisense_ros::Imu::stopStreams
void stopStreams()
Definition: imu.cpp:322
ROS_ERROR
#define ROS_ERROR(...)
multisense_ros::Imu::driver_
crl::multisense::Channel * driver_
Definition: imu.h:61
multisense_ros::Imu::imuCallback
void imuCallback(const crl::multisense::imu::Header &header)
Definition: imu.cpp:198
crl::multisense
multisense_ros::Imu::gyro_frameId_
std::string gyro_frameId_
Definition: imu.h:102
crl::multisense::Channel::stopStreams
virtual Status stopStreams(DataSource mask)=0
multisense_ros::Imu::next_gen_camera_
bool next_gen_camera_
Definition: imu.h:105
multisense_ros::Imu::startStreams
void startStreams()
Definition: imu.cpp:307
multisense_ros::Imu::magnetometer_pub_
ros::Publisher magnetometer_pub_
Definition: imu.h:74
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
header
const std::string header
ROS_INFO
#define ROS_INFO(...)


multisense_ros
Author(s):
autogenerated on Thu Feb 20 2025 03:51:03