36 #include <sensor_msgs/Imu.h>
37 #include <sensor_msgs/MagneticField.h>
38 #include <std_msgs/Bool.h>
39 #include <std_srvs/Empty.h>
47 : nh_(nh), nh_private_(nh_private)
49 ROS_INFO(
"Starting Phidgets SPATIAL");
58 if (!nh_private.
getParam(
"hub_port", hub_port))
71 use_orientation =
false;
74 std::string spatial_algorithm;
77 spatial_algorithm =
"ahrs";
80 double ahrsAngularVelocityThreshold;
81 double ahrsAngularVelocityDeltaThreshold;
82 double ahrsAccelerationThreshold;
87 bool has_ahrs_params =
89 ahrsAngularVelocityThreshold) &&
91 ahrsAngularVelocityDeltaThreshold) &&
93 ahrsAccelerationThreshold) &&
98 double algorithm_magnetometer_gain;
99 bool set_algorithm_magnetometer_gain =
true;
101 algorithm_magnetometer_gain))
103 algorithm_magnetometer_gain = 0.0;
104 set_algorithm_magnetometer_gain =
109 bool heating_enabled;
110 bool set_heating_enabled =
true;
113 set_heating_enabled =
118 double linear_acceleration_stdev;
120 linear_acceleration_stdev))
123 linear_acceleration_stdev = 280.0 * 1e-6 *
G;
126 linear_acceleration_stdev * linear_acceleration_stdev;
128 double angular_velocity_stdev;
132 angular_velocity_stdev = 0.095 * (M_PI / 180.0);
135 angular_velocity_stdev * angular_velocity_stdev;
137 double magnetic_field_stdev;
141 magnetic_field_stdev = 1.1 * 1e-3 * 1e-4;
149 time_resync_ms = 5000;
152 static_cast<int64_t
>(time_resync_ms) * 1000 * 1000;
154 int data_interval_ms;
155 if (!nh_private.
getParam(
"data_interval_ms", data_interval_ms))
157 data_interval_ms = 8;
161 int cb_delta_epsilon_ms;
162 if (!nh_private.
getParam(
"callback_delta_epsilon_ms", cb_delta_epsilon_ms))
164 cb_delta_epsilon_ms = 1;
168 if (cb_delta_epsilon_ms >= data_interval_ms)
170 throw std::runtime_error(
171 "Callback epsilon is larger than the data interval; this can never "
206 bool has_compass_params =
221 ROS_INFO(
"Connecting to Phidgets Spatial serial %d, hub port %d ...",
222 serial_num, hub_port);
236 std::function<void(
const double[4],
double)> algorithm_data_handler =
240 algorithm_data_handler =
242 std::placeholders::_1, std::placeholders::_2);
245 spatial_ = std::make_unique<Spatial>(
246 serial_num, hub_port,
false,
248 std::placeholders::_1, std::placeholders::_2,
249 std::placeholders::_3, std::placeholders::_4),
250 algorithm_data_handler,
256 spatial_->setDataInterval(data_interval_ms);
267 spatial_->setSpatialAlgorithm(spatial_algorithm);
271 spatial_->setAHRSParameters(ahrsAngularVelocityThreshold,
272 ahrsAngularVelocityDeltaThreshold,
273 ahrsAccelerationThreshold,
274 ahrsMagTime, ahrsAccelTime,
278 if (set_algorithm_magnetometer_gain)
279 spatial_->setAlgorithmMagnetometerGain(
280 algorithm_magnetometer_gain);
283 if (has_compass_params)
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);
290 ROS_INFO(
"No compass correction params found.");
293 if (set_heating_enabled)
295 spatial_->setHeatingEnabled(heating_enabled);
307 nh_.
advertise<sensor_msgs::MagneticField>(
"imu/mag", 1);
317 std_srvs::Empty::Response &res)
328 "Calibrating IMU, this takes around 2 seconds to finish. "
329 "Make sure that the device is not moved during this time.");
337 std_msgs::Bool is_calibrated_msg;
338 is_calibrated_msg.data =
true;
344 std::shared_ptr<sensor_msgs::Imu> msg =
345 std::make_shared<sensor_msgs::Imu>();
347 std::shared_ptr<sensor_msgs::MagneticField> mag_msg =
348 std::make_shared<sensor_msgs::MagneticField>();
351 for (
int i = 0; i < 3; ++i)
353 for (
int j = 0; j < 3; ++j)
358 msg->linear_acceleration_covariance[idx] =
360 msg->angular_velocity_covariance[idx] =
362 mag_msg->magnetic_field_covariance[idx] =
376 ROS_WARN(
"Time went backwards (%lu < %lu)! Not publishing message.",
385 msg->header.stamp = ros_time;
408 mag_msg->header.stamp = ros_time;
418 const double angular_rate[3],
419 const double magnetic_field[3],
465 uint64_t this_ts_ns =
static_cast<uint64_t
>(timestamp * 1000.0 * 1000.0);
477 if (time_since_last_cb.
toNSec() >=
479 time_since_last_cb.
toNSec() <=
489 "Data not within acceptable window for synchronization: "
490 "expected between %ld and %ld, saw %ld",
493 time_since_last_cb.
toNSec());
509 if (magnetic_field[0] != PUNK_DBL)
524 double nan = std::numeric_limits<double>::quiet_NaN();
563 ROS_INFO(
"Phidget Spatial attached.");
578 ROS_INFO(
"Phidget Spatial detached.");