spatial_ros_i.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, Open Source Robotics Foundation
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <functional>
31 #include <memory>
32 #include <mutex>
33 
34 #include <ros/ros.h>
35 #include <ros/service_server.h>
36 #include <sensor_msgs/Imu.h>
37 #include <sensor_msgs/MagneticField.h>
38 #include <std_msgs/Bool.h>
39 #include <std_srvs/Empty.h>
40 
41 #include "phidgets_api/spatial.h"
43 
44 namespace phidgets {
45 
47  : nh_(nh), nh_private_(nh_private)
48 {
49  ROS_INFO("Starting Phidgets SPATIAL");
50 
51  ROS_INFO("Opening spatial");
52  int serial_num;
53  if (!nh_private_.getParam("serial", serial_num))
54  {
55  serial_num = -1; // default open any device
56  }
57  int hub_port;
58  if (!nh_private.getParam("hub_port", hub_port))
59  {
60  hub_port = 0; // only used if the device is on a VINT hub_port
61  }
62  if (!nh_private_.getParam("frame_id", frame_id_))
63  {
64  // As specified in http://www.ros.org/reps/rep-0145.html
65  frame_id_ = "imu_link";
66  }
67 
68  bool use_orientation;
69  if (!nh_private_.getParam("use_orientation", use_orientation))
70  {
71  use_orientation = false; // default do not use the onboard orientation
72  }
73 
74  std::string spatial_algorithm;
75  if (!nh_private_.getParam("spatial_algorithm", spatial_algorithm))
76  {
77  spatial_algorithm = "ahrs"; // default use AHRS algorithm
78  }
79 
80  double ahrsAngularVelocityThreshold;
81  double ahrsAngularVelocityDeltaThreshold;
82  double ahrsAccelerationThreshold;
83  double ahrsMagTime;
84  double ahrsAccelTime;
85  double ahrsBiasTime;
86 
87  bool has_ahrs_params =
88  nh_private_.getParam("ahrs_angular_velocity_threshold",
89  ahrsAngularVelocityThreshold) &&
90  nh_private_.getParam("ahrs_angular_velocity_delta_threshold",
91  ahrsAngularVelocityDeltaThreshold) &&
92  nh_private_.getParam("ahrs_acceleration_threshold",
93  ahrsAccelerationThreshold) &&
94  nh_private_.getParam("ahrs_mag_time", ahrsMagTime) &&
95  nh_private_.getParam("ahrs_accel_time", ahrsAccelTime) &&
96  nh_private_.getParam("ahrs_bias_time", ahrsBiasTime);
97 
98  double algorithm_magnetometer_gain;
99  bool set_algorithm_magnetometer_gain = true;
100  if (!nh_private_.getParam("algorithm_magnetometer_gain",
101  algorithm_magnetometer_gain))
102  {
103  algorithm_magnetometer_gain = 0.0;
104  set_algorithm_magnetometer_gain =
105  false; // if parameter not set, do not call api (because this
106  // function is not available from MOT0110 onwards)
107  }
108 
109  bool heating_enabled;
110  bool set_heating_enabled = true;
111  if (!nh_private_.getParam("heating_enabled", heating_enabled))
112  {
113  set_heating_enabled =
114  false; // if parameter not set, do not call api (because this
115  // function is just available from MOT0109 onwards)
116  }
117 
118  double linear_acceleration_stdev;
119  if (!nh_private_.getParam("linear_acceleration_stdev",
120  linear_acceleration_stdev))
121  {
122  // 280 ug accelerometer white noise sigma, as per manual
123  linear_acceleration_stdev = 280.0 * 1e-6 * G;
124  }
126  linear_acceleration_stdev * linear_acceleration_stdev;
127 
128  double angular_velocity_stdev;
129  if (!nh_private_.getParam("angular_velocity_stdev", angular_velocity_stdev))
130  {
131  // 0.095 deg/s gyroscope white noise sigma, as per manual
132  angular_velocity_stdev = 0.095 * (M_PI / 180.0);
133  }
135  angular_velocity_stdev * angular_velocity_stdev;
136 
137  double magnetic_field_stdev;
138  if (!nh_private_.getParam("magnetic_field_stdev", magnetic_field_stdev))
139  {
140  // 1.1 milligauss magnetometer white noise sigma, as per manual
141  magnetic_field_stdev = 1.1 * 1e-3 * 1e-4;
142  }
143  magnetic_field_variance_ = magnetic_field_stdev * magnetic_field_stdev;
144 
145  int time_resync_ms;
146  if (!nh_private_.getParam("time_resynchronization_interval_ms",
147  time_resync_ms))
148  {
149  time_resync_ms = 5000;
150  }
152  static_cast<int64_t>(time_resync_ms) * 1000 * 1000;
153 
154  int data_interval_ms;
155  if (!nh_private.getParam("data_interval_ms", data_interval_ms))
156  {
157  data_interval_ms = 8;
158  }
159  data_interval_ns_ = data_interval_ms * 1000 * 1000;
160 
161  int cb_delta_epsilon_ms;
162  if (!nh_private.getParam("callback_delta_epsilon_ms", cb_delta_epsilon_ms))
163  {
164  cb_delta_epsilon_ms = 1;
165  }
166  cb_delta_epsilon_ns_ = cb_delta_epsilon_ms * 1000 * 1000;
167 
168  if (cb_delta_epsilon_ms >= data_interval_ms)
169  {
170  throw std::runtime_error(
171  "Callback epsilon is larger than the data interval; this can never "
172  "work");
173  }
174 
175  if (!nh_private.getParam("publish_rate", publish_rate_))
176  {
177  publish_rate_ = 0;
178  }
179 
180  if (nh_private.getParam("server_name", server_name_) &&
181  nh_private.getParam("server_ip", server_ip_))
182  {
183  PhidgetNet_addServer(server_name_.c_str(), server_ip_.c_str(), 5661, "",
184  0);
185 
186  ROS_INFO("Using phidget server %s at IP %s", server_name_.c_str(),
187  server_ip_.c_str());
188  }
189 
190  // compass correction params (see
191  // http://www.phidgets.com/docs/1044_User_Guide)
192  double cc_mag_field;
193  double cc_offset0;
194  double cc_offset1;
195  double cc_offset2;
196  double cc_gain0;
197  double cc_gain1;
198  double cc_gain2;
199  double cc_T0;
200  double cc_T1;
201  double cc_T2;
202  double cc_T3;
203  double cc_T4;
204  double cc_T5;
205 
206  bool has_compass_params =
207  nh_private_.getParam("cc_mag_field", cc_mag_field) &&
208  nh_private_.getParam("cc_offset0", cc_offset0) &&
209  nh_private_.getParam("cc_offset1", cc_offset1) &&
210  nh_private_.getParam("cc_offset2", cc_offset2) &&
211  nh_private_.getParam("cc_gain0", cc_gain0) &&
212  nh_private_.getParam("cc_gain1", cc_gain1) &&
213  nh_private_.getParam("cc_gain2", cc_gain2) &&
214  nh_private_.getParam("cc_t0", cc_T0) &&
215  nh_private_.getParam("cc_t1", cc_T1) &&
216  nh_private_.getParam("cc_t2", cc_T2) &&
217  nh_private_.getParam("cc_t3", cc_T3) &&
218  nh_private_.getParam("cc_t4", cc_T4) &&
219  nh_private_.getParam("cc_t5", cc_T5);
220 
221  ROS_INFO("Connecting to Phidgets Spatial serial %d, hub port %d ...",
222  serial_num, hub_port);
223 
224  // We take the mutex here and don't unlock until the end of the constructor
225  // to prevent a callback from trying to use the publisher before we are
226  // finished setting up.
227  std::lock_guard<std::mutex> lock(spatial_mutex_);
228 
229  last_quat_w_ = 0.0;
230  last_quat_x_ = 0.0;
231  last_quat_y_ = 0.0;
232  last_quat_z_ = 0.0;
233 
234  try
235  {
236  std::function<void(const double[4], double)> algorithm_data_handler =
237  nullptr;
238  if (use_orientation)
239  {
240  algorithm_data_handler =
242  std::placeholders::_1, std::placeholders::_2);
243  }
244 
245  spatial_ = std::make_unique<Spatial>(
246  serial_num, hub_port, false,
247  std::bind(&SpatialRosI::spatialDataCallback, this,
248  std::placeholders::_1, std::placeholders::_2,
249  std::placeholders::_3, std::placeholders::_4),
250  algorithm_data_handler,
251  std::bind(&SpatialRosI::attachCallback, this),
252  std::bind(&SpatialRosI::detachCallback, this));
253 
254  ROS_INFO("Connected");
255 
256  spatial_->setDataInterval(data_interval_ms);
257 
258  imu_pub_ = nh_.advertise<sensor_msgs::Imu>("imu/data_raw", 1);
259 
260  cal_publisher_ = nh_.advertise<std_msgs::Bool>("imu/is_calibrated", 5,
261  true /* latched */);
262 
263  calibrate();
264 
265  if (use_orientation)
266  {
267  spatial_->setSpatialAlgorithm(spatial_algorithm);
268 
269  if (has_ahrs_params)
270  {
271  spatial_->setAHRSParameters(ahrsAngularVelocityThreshold,
272  ahrsAngularVelocityDeltaThreshold,
273  ahrsAccelerationThreshold,
274  ahrsMagTime, ahrsAccelTime,
275  ahrsBiasTime);
276  }
277 
278  if (set_algorithm_magnetometer_gain)
279  spatial_->setAlgorithmMagnetometerGain(
280  algorithm_magnetometer_gain);
281  }
282 
283  if (has_compass_params)
284  {
285  spatial_->setCompassCorrectionParameters(
286  cc_mag_field, cc_offset0, cc_offset1, cc_offset2, cc_gain0,
287  cc_gain1, cc_gain2, cc_T0, cc_T1, cc_T2, cc_T3, cc_T4, cc_T5);
288  } else
289  {
290  ROS_INFO("No compass correction params found.");
291  }
292 
293  if (set_heating_enabled)
294  {
295  spatial_->setHeatingEnabled(heating_enabled);
296  }
297  } catch (const Phidget22Error &err)
298  {
299  ROS_ERROR("Spatial: %s", err.what());
300  throw;
301  }
302 
303  cal_srv_ = nh_.advertiseService("imu/calibrate",
305 
307  nh_.advertise<sensor_msgs::MagneticField>("imu/mag", 1);
308 
309  if (publish_rate_ > 0)
310  {
313  }
314 }
315 
316 bool SpatialRosI::calibrateService(std_srvs::Empty::Request &req,
317  std_srvs::Empty::Response &res)
318 {
319  (void)req;
320  (void)res;
321  calibrate();
322  return true;
323 }
324 
326 {
327  ROS_INFO(
328  "Calibrating IMU, this takes around 2 seconds to finish. "
329  "Make sure that the device is not moved during this time.");
330  spatial_->zero();
331  // The API call returns directly, so we "enforce" the recommended 2 sec
332  // here. See: https://github.com/ros-drivers/phidgets_drivers/issues/40
333  ros::Duration(2.).sleep();
334  ROS_INFO("Calibrating IMU done.");
335 
336  // publish message
337  std_msgs::Bool is_calibrated_msg;
338  is_calibrated_msg.data = true;
339  cal_publisher_.publish(is_calibrated_msg);
340 }
341 
343 {
344  std::shared_ptr<sensor_msgs::Imu> msg =
345  std::make_shared<sensor_msgs::Imu>();
346 
347  std::shared_ptr<sensor_msgs::MagneticField> mag_msg =
348  std::make_shared<sensor_msgs::MagneticField>();
349 
350  // build covariance matrices
351  for (int i = 0; i < 3; ++i)
352  {
353  for (int j = 0; j < 3; ++j)
354  {
355  if (i == j)
356  {
357  int idx = j * 3 + i;
358  msg->linear_acceleration_covariance[idx] =
360  msg->angular_velocity_covariance[idx] =
362  mag_msg->magnetic_field_covariance[idx] =
364  }
365  }
366  }
367 
368  // Fill out and send IMU message
369  msg->header.frame_id = frame_id_;
370 
371  uint64_t imu_diff_in_ns = last_data_timestamp_ns_ - data_time_zero_ns_;
372  uint64_t time_in_ns = ros_time_zero_.toNSec() + imu_diff_in_ns;
373 
374  if (time_in_ns < last_ros_stamp_ns_)
375  {
376  ROS_WARN("Time went backwards (%lu < %lu)! Not publishing message.",
377  time_in_ns, last_ros_stamp_ns_);
378  return;
379  }
380 
381  last_ros_stamp_ns_ = time_in_ns;
382 
383  ros::Time ros_time = ros::Time().fromNSec(time_in_ns);
384 
385  msg->header.stamp = ros_time;
386 
387  // set linear acceleration
388  msg->linear_acceleration.x = last_accel_x_;
389  msg->linear_acceleration.y = last_accel_y_;
390  msg->linear_acceleration.z = last_accel_z_;
391 
392  // set angular velocities
393  msg->angular_velocity.x = last_gyro_x_;
394  msg->angular_velocity.y = last_gyro_y_;
395  msg->angular_velocity.z = last_gyro_z_;
396 
397  // set spatial algorithm orientation estimation
398  msg->orientation.w = last_quat_w_;
399  msg->orientation.x = last_quat_x_;
400  msg->orientation.y = last_quat_y_;
401  msg->orientation.z = last_quat_z_;
402 
403  imu_pub_.publish(*msg);
404 
405  // Fill out and publish magnetic message
406  mag_msg->header.frame_id = frame_id_;
407 
408  mag_msg->header.stamp = ros_time;
409 
410  mag_msg->magnetic_field.x = last_mag_x_;
411  mag_msg->magnetic_field.y = last_mag_y_;
412  mag_msg->magnetic_field.z = last_mag_z_;
413 
414  magnetic_field_pub_.publish(*mag_msg);
415 }
416 
417 void SpatialRosI::spatialDataCallback(const double acceleration[3],
418  const double angular_rate[3],
419  const double magnetic_field[3],
420  double timestamp)
421 {
422  // When publishing the message on the ROS network, we want to publish the
423  // time that the data was acquired in seconds since the Unix epoch. The
424  // data we have to work with is the time that the callback happened (on the
425  // local processor, in Unix epoch seconds), and the timestamp that the
426  // IMU gives us on the callback (from the processor on the IMU, in
427  // milliseconds since some arbitrary starting point).
428  //
429  // At a first approximation, we can apply the timestamp from the device to
430  // Unix epoch seconds by taking a common starting point on the IMU and the
431  // local processor, then applying the delta between this IMU timestamp and
432  // the "zero" IMU timestamp to the local processor starting point.
433  //
434  // There are several complications with the simple scheme above. The first
435  // is finding a proper "zero" point where the IMU timestamp and the local
436  // timestamp line up. Due to potential delays in servicing this process,
437  // along with USB delays, the delta timestamp from the IMU and the time when
438  // this callback gets called can be wildly different. Since we want the
439  // initial zero for both the IMU and the local time to be in the same time
440  // "window", we throw away data at the beginning until we see that the delta
441  // callback and delta timestamp are within reasonable bounds of each other.
442  //
443  // The second complication is that the time on the IMU drifts away from the
444  // time on the local processor. Taking the "zero" time once at the
445  // beginning isn't sufficient, and we have to periodically re-synchronize
446  // the times given the constraints above. Because we still have the
447  // arbitrary delays present as described above, it can take us several
448  // callbacks to successfully synchronize. We continue publishing data using
449  // the old "zero" time until successfully resynchronize, at which point we
450  // switch to the new zero point.
451 
452  std::lock_guard<std::mutex> lock(spatial_mutex_);
453 
454  ros::Time now = ros::Time::now();
455 
456  // At the beginning of time, need to initialize last_cb_time for later use;
457  // last_cb_time is used to figure out the time between callbacks
458  if (last_cb_time_.sec == 0 && last_cb_time_.nsec == 0)
459  {
460  last_cb_time_ = now;
461  return;
462  }
463 
464  ros::Duration time_since_last_cb = now - last_cb_time_;
465  uint64_t this_ts_ns = static_cast<uint64_t>(timestamp * 1000.0 * 1000.0);
466 
468  {
469  // The only time it's safe to sync time between IMU and ROS Node is when
470  // the data that came in is within the data interval that data is
471  // expected. It's possible for data to come late because of USB issues
472  // or swapping, etc and we don't want to sync with data that was
473  // actually published before this time interval, so we wait until we get
474  // data that is within the data interval +/- an epsilon since we will
475  // have taken some time to process and/or a short delay (maybe USB
476  // comms) may have happened
477  if (time_since_last_cb.toNSec() >=
479  time_since_last_cb.toNSec() <=
481  {
482  ros_time_zero_ = now;
483  data_time_zero_ns_ = this_ts_ns;
484  synchronize_timestamps_ = false;
485  can_publish_ = true;
486  } else
487  {
488  ROS_DEBUG(
489  "Data not within acceptable window for synchronization: "
490  "expected between %ld and %ld, saw %ld",
493  time_since_last_cb.toNSec());
494  }
495  }
496 
497  if (can_publish_) // Cannot publish data until IMU/ROS timestamps have been
498  // synchronized at least once
499  {
500  // Save off the values
501  last_accel_x_ = -acceleration[0] * G;
502  last_accel_y_ = -acceleration[1] * G;
503  last_accel_z_ = -acceleration[2] * G;
504 
505  last_gyro_x_ = angular_rate[0] * (M_PI / 180.0);
506  last_gyro_y_ = angular_rate[1] * (M_PI / 180.0);
507  last_gyro_z_ = angular_rate[2] * (M_PI / 180.0);
508 
509  if (magnetic_field[0] != PUNK_DBL)
510  {
511  // device reports data in Gauss, multiply by 1e-4 to convert to
512  // Tesla
513  last_mag_x_ = magnetic_field[0] * 1e-4;
514  last_mag_y_ = magnetic_field[1] * 1e-4;
515  last_mag_z_ = magnetic_field[2] * 1e-4;
516  } else
517  {
518  // data is PUNK_DBL ("unknown double"), which means the magnetometer
519  // did not return valid readings. When publishing at 250 Hz, this
520  // will happen in every second message, because the magnetometer can
521  // only sample at 125 Hz. It is still important to publish these
522  // messages, because a downstream node sometimes uses a
523  // TimeSynchronizer to get Imu and Magnetometer nodes.
524  double nan = std::numeric_limits<double>::quiet_NaN();
525 
526  last_mag_x_ = nan;
527  last_mag_y_ = nan;
528  last_mag_z_ = nan;
529  }
530  last_data_timestamp_ns_ = this_ts_ns;
531 
532  // Publish if we aren't publishing on a timer
533  if (publish_rate_ <= 0)
534  {
535  publishLatest();
536  }
537  }
538 
539  // Determine if we need to resynchronize - time between IMU and ROS Node can
540  // drift, periodically resync to deal with this issue
541  ros::Duration diff = now - ros_time_zero_;
542  if (time_resync_interval_ns_ > 0 &&
544  {
546  }
547 
548  last_cb_time_ = now;
549 }
550 
551 void SpatialRosI::spatialAlgorithmDataCallback(const double quaternion[4],
552  double timestamp)
553 {
554  (void)timestamp;
555  last_quat_w_ = quaternion[3];
556  last_quat_x_ = quaternion[0];
557  last_quat_y_ = quaternion[1];
558  last_quat_z_ = quaternion[2];
559 }
560 
562 {
563  ROS_INFO("Phidget Spatial attached.");
564 
565  // Set data interval. This is in attachCallback() because it has to be
566  // repeated on reattachment.
567  spatial_->setDataInterval(data_interval_ns_ / 1000 / 1000);
568 
569  // Force resynchronization, because the device time is reset to 0 after
570  // reattachment.
572  can_publish_ = false;
574 }
575 
577 {
578  ROS_INFO("Phidget Spatial detached.");
579 }
580 
582 {
583  std::lock_guard<std::mutex> lock(spatial_mutex_);
584  if (can_publish_)
585  {
586  publishLatest();
587  }
588 }
589 
590 } // namespace phidgets
phidgets
phidgets::SpatialRosI::last_accel_x_
double last_accel_x_
Definition: spatial_ros_i.h:87
phidgets::SpatialRosI::spatial_mutex_
std::mutex spatial_mutex_
Definition: spatial_ros_i.h:56
phidgets::SpatialRosI::last_ros_stamp_ns_
uint64_t last_ros_stamp_ns_
Definition: spatial_ros_i.h:71
phidgets::SpatialRosI::cal_srv_
ros::ServiceServer cal_srv_
Definition: spatial_ros_i.h:63
phidgets::SpatialRosI::frame_id_
std::string frame_id_
Definition: spatial_ros_i.h:55
phidgets::SpatialRosI::last_quat_y_
double last_quat_y_
Definition: spatial_ros_i.h:106
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
phidgets::SpatialRosI::nh_private_
ros::NodeHandle nh_private_
Definition: spatial_ros_i.h:54
phidgets::SpatialRosI::calibrateService
bool calibrateService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: spatial_ros_i.cpp:316
phidgets::SpatialRosI::spatialAlgorithmDataCallback
void spatialAlgorithmDataCallback(const double quaternion[4], double timestamp)
Definition: spatial_ros_i.cpp:551
phidgets::SpatialRosI::spatialDataCallback
void spatialDataCallback(const double acceleration[3], const double angular_rate[3], const double magnetic_field[3], double timestamp)
Definition: spatial_ros_i.cpp:417
phidgets::SpatialRosI::timer_
ros::Timer timer_
Definition: spatial_ros_i.h:58
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
phidgets::SpatialRosI::angular_velocity_variance_
double angular_velocity_variance_
Definition: spatial_ros_i.h:92
phidgets::SpatialRosI::ros_time_zero_
ros::Time ros_time_zero_
Definition: spatial_ros_i.h:67
phidgets::SpatialRosI::synchronize_timestamps_
bool synchronize_timestamps_
Definition: spatial_ros_i.h:68
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
phidgets::SpatialRosI::publish_rate_
int publish_rate_
Definition: spatial_ros_i.h:59
phidgets::SpatialRosI::last_gyro_z_
double last_gyro_z_
Definition: spatial_ros_i.h:95
phidgets::SpatialRosI::calibrate
void calibrate()
Definition: spatial_ros_i.cpp:325
phidgets::SpatialRosI::can_publish_
bool can_publish_
Definition: spatial_ros_i.h:74
spatial.h
phidgets::SpatialRosI::last_quat_w_
double last_quat_w_
Definition: spatial_ros_i.h:104
phidgets::SpatialRosI::last_quat_x_
double last_quat_x_
Definition: spatial_ros_i.h:105
ROS_DEBUG
#define ROS_DEBUG(...)
phidgets::SpatialRosI::data_time_zero_ns_
uint64_t data_time_zero_ns_
Definition: spatial_ros_i.h:69
phidgets::SpatialRosI::cb_delta_epsilon_ns_
int64_t cb_delta_epsilon_ns_
Definition: spatial_ros_i.h:76
phidgets::SpatialRosI::magnetic_field_pub_
ros::Publisher magnetic_field_pub_
Definition: spatial_ros_i.h:65
phidgets::SpatialRosI::SpatialRosI
SpatialRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
Definition: spatial_ros_i.cpp:46
phidgets::Phidget22Error
phidgets::SpatialRosI::magnetic_field_variance_
double magnetic_field_variance_
Definition: spatial_ros_i.h:98
ROS_WARN
#define ROS_WARN(...)
phidgets::SpatialRosI::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: spatial_ros_i.cpp:581
phidgets::SpatialRosI::last_mag_z_
double last_mag_z_
Definition: spatial_ros_i.h:101
ros::TimerEvent
spatial_ros_i.h
phidgets::SpatialRosI::publishLatest
void publishLatest()
Definition: spatial_ros_i.cpp:342
phidgets::SpatialRosI::last_accel_y_
double last_accel_y_
Definition: spatial_ros_i.h:88
TimeBase< Time, Duration >::sec
uint32_t sec
TimeBase< Time, Duration >::nsec
uint32_t nsec
phidgets::SpatialRosI::imu_pub_
ros::Publisher imu_pub_
Definition: spatial_ros_i.h:64
phidgets::Phidget22Error::what
const char * what() const noexcept
phidgets::SpatialRosI::last_mag_y_
double last_mag_y_
Definition: spatial_ros_i.h:100
phidgets::SpatialRosI::last_gyro_x_
double last_gyro_x_
Definition: spatial_ros_i.h:93
phidgets::SpatialRosI::last_quat_z_
double last_quat_z_
Definition: spatial_ros_i.h:107
phidgets::SpatialRosI::last_accel_z_
double last_accel_z_
Definition: spatial_ros_i.h:89
TimeBase< Time, Duration >::fromNSec
Time & fromNSec(uint64_t t)
ros::Time
DurationBase< Duration >::toNSec
int64_t toNSec() const
phidgets::SpatialRosI::time_resync_interval_ns_
int64_t time_resync_interval_ns_
Definition: spatial_ros_i.h:72
phidgets::SpatialRosI::server_name_
std::string server_name_
Definition: spatial_ros_i.h:60
phidgets::SpatialRosI::last_gyro_y_
double last_gyro_y_
Definition: spatial_ros_i.h:94
phidgets::SpatialRosI::nh_
ros::NodeHandle nh_
Definition: spatial_ros_i.h:53
phidgets::SpatialRosI::linear_acceleration_variance_
double linear_acceleration_variance_
Definition: spatial_ros_i.h:86
ROS_ERROR
#define ROS_ERROR(...)
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
phidgets::SpatialRosI::cal_publisher_
ros::Publisher cal_publisher_
Definition: spatial_ros_i.h:62
phidgets::SpatialRosI::spatial_
std::unique_ptr< Spatial > spatial_
Definition: spatial_ros_i.h:83
phidgets::SpatialRosI::detachCallback
void detachCallback()
Definition: spatial_ros_i.cpp:576
phidgets::G
const float G
Definition: spatial_ros_i.h:45
ros::Duration::sleep
bool sleep() const
phidgets::SpatialRosI::server_ip_
std::string server_ip_
Definition: spatial_ros_i.h:61
ROS_INFO
#define ROS_INFO(...)
phidgets::SpatialRosI::data_interval_ns_
int64_t data_interval_ns_
Definition: spatial_ros_i.h:73
phidgets::SpatialRosI::attachCallback
void attachCallback()
Definition: spatial_ros_i.cpp:561
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
service_server.h
phidgets::SpatialRosI::last_cb_time_
ros::Time last_cb_time_
Definition: spatial_ros_i.h:75
phidgets::SpatialRosI::last_mag_x_
double last_mag_x_
Definition: spatial_ros_i.h:99
ros::NodeHandle
phidgets::SpatialRosI::last_data_timestamp_ns_
uint64_t last_data_timestamp_ns_
Definition: spatial_ros_i.h:70
ros::Time::now
static Time now()


phidgets_spatial
Author(s): Ivan Dryanovski
autogenerated on Sat Dec 2 2023 03:18:58