accelerometer_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 <sensor_msgs/Imu.h>
36 
38 
39 namespace phidgets {
40 
42  ros::NodeHandle nh_private)
43  : nh_(nh), nh_private_(nh_private)
44 {
45  ROS_INFO("Starting Phidgets Accelerometer");
46 
47  int serial_num;
48  if (!nh_private_.getParam("serial", serial_num))
49  {
50  serial_num = -1; // default open any device
51  }
52  int hub_port;
53  if (!nh_private.getParam("hub_port", hub_port))
54  {
55  hub_port = 0; // only used if the device is on a VINT hub_port
56  }
57  if (!nh_private_.getParam("frame_id", frame_id_))
58  {
59  // As specified in http://www.ros.org/reps/rep-0145.html
60  frame_id_ = "imu_link";
61  }
62 
63  double linear_acceleration_stdev;
64  if (!nh_private_.getParam("linear_acceleration_stdev",
65  linear_acceleration_stdev))
66  {
67  // 280 ug accelerometer white noise sigma, as per manual
68  linear_acceleration_stdev = 280.0 * 1e-6 * G;
69  }
71  linear_acceleration_stdev * linear_acceleration_stdev;
72 
73  int time_resync_ms;
74  if (!nh_private_.getParam("time_resynchronization_interval_ms",
75  time_resync_ms))
76  {
77  time_resync_ms = 5000;
78  }
80  static_cast<int64_t>(time_resync_ms) * 1000 * 1000;
81 
82  int data_interval_ms;
83  if (!nh_private.getParam("data_interval_ms", data_interval_ms))
84  {
85  data_interval_ms = 8;
86  }
87  data_interval_ns_ = data_interval_ms * 1000 * 1000;
88 
89  int cb_delta_epsilon_ms;
90  if (!nh_private.getParam("callback_delta_epsilon_ms", cb_delta_epsilon_ms))
91  {
92  cb_delta_epsilon_ms = 1;
93  }
94  cb_delta_epsilon_ns_ = cb_delta_epsilon_ms * 1000 * 1000;
95 
96  if (cb_delta_epsilon_ms >= data_interval_ms)
97  {
98  throw std::runtime_error(
99  "Callback epsilon is larger than the data interval; this can never "
100  "work");
101  }
102 
103  if (!nh_private.getParam("publish_rate", publish_rate_))
104  {
105  publish_rate_ = 0;
106  }
107 
108  if (nh_private.getParam("server_name", server_name_) &&
109  nh_private.getParam("server_ip", server_ip_))
110  {
111  PhidgetNet_addServer(server_name_.c_str(), server_ip_.c_str(), 5661, "",
112  0);
113 
114  ROS_INFO("Using phidget server %s at IP %s", server_name_.c_str(),
115  server_ip_.c_str());
116  }
117 
118  ROS_INFO("Connecting to Phidgets Accelerometer serial %d, hub port %d ...",
119  serial_num, hub_port);
120 
121  // We take the mutex here and don't unlock until the end of the constructor
122  // to prevent a callback from trying to use the publisher before we are
123  // finished setting up.
124  std::lock_guard<std::mutex> lock(accel_mutex_);
125 
126  try
127  {
128  accelerometer_ = std::make_unique<Accelerometer>(
129  serial_num, hub_port, false,
131  std::placeholders::_1, std::placeholders::_2));
132 
133  ROS_INFO("Connected");
134 
135  accelerometer_->setDataInterval(data_interval_ms);
136 
137  accelerometer_pub_ = nh_.advertise<sensor_msgs::Imu>("imu/data_raw", 1);
138  } catch (const Phidget22Error& err)
139  {
140  ROS_ERROR("Accelerometer: %s", err.what());
141  throw;
142  }
143 
144  if (publish_rate_ > 0)
145  {
148  }
149 }
150 
152 {
153  std::shared_ptr<sensor_msgs::Imu> msg =
154  std::make_shared<sensor_msgs::Imu>();
155 
156  msg->header.frame_id = frame_id_;
157 
158  for (int i = 0; i < 3; ++i)
159  {
160  for (int j = 0; j < 3; ++j)
161  {
162  if (i == j)
163  {
164  int idx = j * 3 + i;
165  msg->linear_acceleration_covariance[idx] =
167  }
168  }
169  }
170 
171  uint64_t accel_diff_in_ns = last_data_timestamp_ns_ - data_time_zero_ns_;
172  uint64_t time_in_ns = ros_time_zero_.toNSec() + accel_diff_in_ns;
173 
174  if (time_in_ns < last_ros_stamp_ns_)
175  {
176  ROS_WARN("Time went backwards (%lu < %lu)! Not publishing message.",
177  time_in_ns, last_ros_stamp_ns_);
178  return;
179  }
180 
181  last_ros_stamp_ns_ = time_in_ns;
182 
183  msg->header.stamp = ros::Time().fromNSec(time_in_ns);
184 
185  // set linear acceleration
186  msg->linear_acceleration.x = last_accel_x_;
187  msg->linear_acceleration.y = last_accel_y_;
188  msg->linear_acceleration.z = last_accel_z_;
189 
191 }
192 
194 {
195  std::lock_guard<std::mutex> lock(accel_mutex_);
196  if (can_publish_)
197  {
198  publishLatest();
199  }
200 }
201 
203  const double acceleration[3], double timestamp)
204 {
205  // When publishing the message on the ROS network, we want to publish the
206  // time that the data was acquired in seconds since the Unix epoch. The
207  // data we have to work with is the time that the callback happened (on the
208  // local processor, in Unix epoch seconds), and the timestamp that the
209  // IMU gives us on the callback (from the processor on the IMU, in
210  // milliseconds since some arbitrary starting point).
211  //
212  // At a first approximation, we can apply the timestamp from the device to
213  // Unix epoch seconds by taking a common starting point on the IMU and the
214  // local processor, then applying the delta between this IMU timestamp and
215  // the "zero" IMU timestamp to the local processor starting point.
216  //
217  // There are several complications with the simple scheme above. The first
218  // is finding a proper "zero" point where the IMU timestamp and the local
219  // timestamp line up. Due to potential delays in servicing this process,
220  // along with USB delays, the delta timestamp from the IMU and the time when
221  // this callback gets called can be wildly different. Since we want the
222  // initial zero for both the IMU and the local time to be in the same time
223  // "window", we throw away data at the beginning until we see that the delta
224  // callback and delta timestamp are within reasonable bounds of each other.
225  //
226  // The second complication is that the time on the IMU drifts away from the
227  // time on the local processor. Taking the "zero" time once at the
228  // beginning isn't sufficient, and we have to periodically re-synchronize
229  // the times given the constraints above. Because we still have the
230  // arbitrary delays present as described above, it can take us several
231  // callbacks to successfully synchronize. We continue publishing data using
232  // the old "zero" time until successfully resynchronize, at which point we
233  // switch to the new zero point.
234 
235  std::lock_guard<std::mutex> lock(accel_mutex_);
236 
237  ros::Time now = ros::Time::now();
238 
239  // At the beginning of time, need to initialize last_cb_time for later use;
240  // last_cb_time is used to figure out the time between callbacks
241  if (last_cb_time_.sec == 0 && last_cb_time_.nsec == 0)
242  {
243  last_cb_time_ = now;
244  return;
245  }
246 
247  ros::Duration time_since_last_cb = now - last_cb_time_;
248  uint64_t this_ts_ns = static_cast<uint64_t>(timestamp * 1000.0 * 1000.0);
249 
251  {
252  // The only time it's safe to sync time between IMU and ROS Node is when
253  // the data that came in is within the data interval that data is
254  // expected. It's possible for data to come late because of USB issues
255  // or swapping, etc and we don't want to sync with data that was
256  // actually published before this time interval, so we wait until we get
257  // data that is within the data interval +/- an epsilon since we will
258  // have taken some time to process and/or a short delay (maybe USB
259  // comms) may have happened
260  if (time_since_last_cb.toNSec() >=
262  time_since_last_cb.toNSec() <=
264  {
265  ros_time_zero_ = now;
266  data_time_zero_ns_ = this_ts_ns;
267  synchronize_timestamps_ = false;
268  can_publish_ = true;
269  } else
270  {
271  ROS_DEBUG(
272  "Data not within acceptable window for synchronization: "
273  "expected between %ld and %ld, saw %ld",
276  time_since_last_cb.toNSec());
277  }
278  }
279 
280  if (can_publish_) // Cannot publish data until IMU/ROS timestamps have been
281  // synchronized at least once
282  {
283  // Save off the values
284  last_accel_x_ = -acceleration[0] * G;
285  last_accel_y_ = -acceleration[1] * G;
286  last_accel_z_ = -acceleration[2] * G;
287 
288  last_data_timestamp_ns_ = this_ts_ns;
289 
290  // Publish if we aren't publishing on a timer
291  if (publish_rate_ <= 0)
292  {
293  publishLatest();
294  }
295  }
296 
297  // Determine if we need to resynchronize - time between IMU and ROS Node can
298  // drift, periodically resync to deal with this issue
299  ros::Duration diff = now - ros_time_zero_;
300  if (time_resync_interval_ns_ > 0 &&
302  {
304  }
305 
306  last_cb_time_ = now;
307 }
308 
309 } // namespace phidgets
phidgets
phidgets::AccelerometerRosI::linear_acceleration_variance_
double linear_acceleration_variance_
Definition: accelerometer_ros_i.h:53
phidgets::AccelerometerRosI::publish_rate_
int publish_rate_
Definition: accelerometer_ros_i.h:64
phidgets::AccelerometerRosI::nh_private_
ros::NodeHandle nh_private_
Definition: accelerometer_ros_i.h:60
phidgets::AccelerometerRosI::server_name_
std::string server_name_
Definition: accelerometer_ros_i.h:65
phidgets::AccelerometerRosI::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: accelerometer_ros_i.cpp:193
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
phidgets::AccelerometerRosI::accelerometer_pub_
ros::Publisher accelerometer_pub_
Definition: accelerometer_ros_i.h:61
phidgets::AccelerometerRosI::last_accel_y_
double last_accel_y_
Definition: accelerometer_ros_i.h:56
phidgets::AccelerometerRosI::synchronize_timestamps_
bool synchronize_timestamps_
Definition: accelerometer_ros_i.h:69
phidgets::AccelerometerRosI::accel_mutex_
std::mutex accel_mutex_
Definition: accelerometer_ros_i.h:54
phidgets::AccelerometerRosI::accelerometerChangeCallback
void accelerometerChangeCallback(const double acceleration[3], const double timestamp)
Definition: accelerometer_ros_i.cpp:202
phidgets::AccelerometerRosI::last_accel_x_
double last_accel_x_
Definition: accelerometer_ros_i.h:55
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
phidgets::AccelerometerRosI::last_accel_z_
double last_accel_z_
Definition: accelerometer_ros_i.h:57
phidgets::AccelerometerRosI::can_publish_
bool can_publish_
Definition: accelerometer_ros_i.h:75
ROS_DEBUG
#define ROS_DEBUG(...)
phidgets::AccelerometerRosI::frame_id_
std::string frame_id_
Definition: accelerometer_ros_i.h:52
phidgets::AccelerometerRosI::AccelerometerRosI
AccelerometerRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
Definition: accelerometer_ros_i.cpp:41
phidgets::AccelerometerRosI::data_time_zero_ns_
uint64_t data_time_zero_ns_
Definition: accelerometer_ros_i.h:70
phidgets::AccelerometerRosI::ros_time_zero_
ros::Time ros_time_zero_
Definition: accelerometer_ros_i.h:68
phidgets::AccelerometerRosI::nh_
ros::NodeHandle nh_
Definition: accelerometer_ros_i.h:59
phidgets::Phidget22Error
ROS_WARN
#define ROS_WARN(...)
phidgets::AccelerometerRosI::publishLatest
void publishLatest()
Definition: accelerometer_ros_i.cpp:151
ros::TimerEvent
TimeBase< Time, Duration >::sec
uint32_t sec
TimeBase< Time, Duration >::nsec
uint32_t nsec
phidgets::Phidget22Error::what
const char * what() const noexcept
phidgets::AccelerometerRosI::timer_
ros::Timer timer_
Definition: accelerometer_ros_i.h:63
TimeBase< Time, Duration >::fromNSec
Time & fromNSec(uint64_t t)
ros::Time
phidgets::AccelerometerRosI::last_ros_stamp_ns_
uint64_t last_ros_stamp_ns_
Definition: accelerometer_ros_i.h:72
DurationBase< Duration >::toNSec
int64_t toNSec() const
ROS_ERROR
#define ROS_ERROR(...)
phidgets::AccelerometerRosI::last_data_timestamp_ns_
uint64_t last_data_timestamp_ns_
Definition: accelerometer_ros_i.h:71
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
phidgets::AccelerometerRosI::data_interval_ns_
int64_t data_interval_ns_
Definition: accelerometer_ros_i.h:74
phidgets::AccelerometerRosI::server_ip_
std::string server_ip_
Definition: accelerometer_ros_i.h:66
phidgets::G
const double G
Definition: accelerometer_ros_i.h:43
phidgets::AccelerometerRosI::time_resync_interval_ns_
int64_t time_resync_interval_ns_
Definition: accelerometer_ros_i.h:73
phidgets::AccelerometerRosI::last_cb_time_
ros::Time last_cb_time_
Definition: accelerometer_ros_i.h:76
accelerometer_ros_i.h
ROS_INFO
#define ROS_INFO(...)
phidgets::AccelerometerRosI::accelerometer_
std::unique_ptr< Accelerometer > accelerometer_
Definition: accelerometer_ros_i.h:51
phidgets::AccelerometerRosI::cb_delta_epsilon_ns_
int64_t cb_delta_epsilon_ns_
Definition: accelerometer_ros_i.h:77
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()


phidgets_accelerometer
Author(s): Chris Lalancette
autogenerated on Sat Dec 2 2023 03:18:48