35 #include <sensor_msgs/Imu.h>
43 : nh_(nh), nh_private_(nh_private)
45 ROS_INFO(
"Starting Phidgets Accelerometer");
53 if (!nh_private.
getParam(
"hub_port", hub_port))
63 double linear_acceleration_stdev;
65 linear_acceleration_stdev))
68 linear_acceleration_stdev = 280.0 * 1e-6 *
G;
71 linear_acceleration_stdev * linear_acceleration_stdev;
77 time_resync_ms = 5000;
80 static_cast<int64_t
>(time_resync_ms) * 1000 * 1000;
83 if (!nh_private.
getParam(
"data_interval_ms", data_interval_ms))
89 int cb_delta_epsilon_ms;
90 if (!nh_private.
getParam(
"callback_delta_epsilon_ms", cb_delta_epsilon_ms))
92 cb_delta_epsilon_ms = 1;
96 if (cb_delta_epsilon_ms >= data_interval_ms)
98 throw std::runtime_error(
99 "Callback epsilon is larger than the data interval; this can never "
118 ROS_INFO(
"Connecting to Phidgets Accelerometer serial %d, hub port %d ...",
119 serial_num, hub_port);
129 serial_num, hub_port,
false,
131 std::placeholders::_1, std::placeholders::_2));
153 std::shared_ptr<sensor_msgs::Imu> msg =
154 std::make_shared<sensor_msgs::Imu>();
158 for (
int i = 0; i < 3; ++i)
160 for (
int j = 0; j < 3; ++j)
165 msg->linear_acceleration_covariance[idx] =
176 ROS_WARN(
"Time went backwards (%lu < %lu)! Not publishing message.",
203 const double acceleration[3],
double timestamp)
248 uint64_t this_ts_ns =
static_cast<uint64_t
>(timestamp * 1000.0 * 1000.0);
260 if (time_since_last_cb.
toNSec() >=
262 time_since_last_cb.
toNSec() <=
272 "Data not within acceptable window for synchronization: "
273 "expected between %ld and %ld, saw %ld",
276 time_since_last_cb.
toNSec());