sickld.cpp
Go to the documentation of this file.
1 /*
2  * Authors: Nick Hillier and Fred Pauling (CSIRO, 2011)
3  *
4  * Based on the sicklms.cpp from the sicktoolbox_wrapper ROS package
5  * and the sample code from the sicktoolbox manual.
6  *
7  * Released under BSD license.
8  */
9 
10 #include <iostream>
11 #include <sicktoolbox/SickLD.hh>
12 #include "ros/ros.h"
13 #include "sensor_msgs/LaserScan.h"
14 #include <deque>
15 
16 #define DEG2RAD(x) ((x)*M_PI/180.)
17 
18 using namespace std;
19 using namespace SickToolbox;
20 
21 // TODO: refactor these functions into a common util lib (similar to code in sicklms.cpp)
22 void publish_scan(ros::Publisher *pub, double *range_values,
23  uint32_t n_range_values, unsigned int *intensity_values,
24  uint32_t n_intensity_values, ros::Time start,
25  double scan_time, bool inverted, float angle_min,
26  float angle_max, std::string frame_id)
27 {
28  static int scan_count = 0;
29  sensor_msgs::LaserScan scan_msg;
30  scan_msg.header.frame_id = frame_id;
31  scan_count++;
32  if (inverted) { // assumes scan window at the bottom
33  scan_msg.angle_min = angle_max;
34  scan_msg.angle_max = angle_min;
35  } else {
36  scan_msg.angle_min = angle_min;
37  scan_msg.angle_max = angle_max;
38  }
39  scan_msg.angle_increment = (scan_msg.angle_max - scan_msg.angle_min) / (double)(n_range_values-1);
40  scan_msg.scan_time = scan_time;
41  scan_msg.time_increment = scan_time / n_range_values;
42  scan_msg.range_min = 0.5;
43  scan_msg.range_max = 250.;
44  scan_msg.ranges.resize(n_range_values);
45  scan_msg.header.stamp = start;
46  for (size_t i = 0; i < n_range_values; i++) {
47  scan_msg.ranges[i] = (float)range_values[i];
48  }
49  scan_msg.intensities.resize(n_intensity_values);
50  for (size_t i = 0; i < n_intensity_values; i++) {
51  scan_msg.intensities[i] = (float)intensity_values[i];
52  }
53  pub->publish(scan_msg);
54 }
55 
56 // A complimentary filter to get a (much) better time estimate, does not
57 // calibrate out constant network latency delays, but does get rid of
58 // timming jitter to get better timing estimates than the
59 // communicated clock resolution (which is only 1ms)
60 class smoothtime {
61  protected:
62  ros::Time smoothtime_prev, smoothed_timestamp;
65  public:
68  time_smoothing_factor = 0.95;
69  error_threshold = .50;
70  }
72  void set_smoothing_factor(double smoothing_factor){
73  time_smoothing_factor = smoothing_factor;
74  }
76  void set_error_threshold(double err_threshold){
77  error_threshold = err_threshold;
78  }
79  ros::Time smooth_timestamp(ros::Time recv_timestamp, ros::Duration expctd_dur) {
80  if (smoothtime_prev.is_zero() == true) {
81  smoothed_timestamp = recv_timestamp;
82  } else {
83  smoothed_timestamp = smoothtime_prev + expctd_dur;
84  double err = (recv_timestamp - smoothed_timestamp).toSec();
85  double time_error_threshold = expctd_dur.toSec() * error_threshold;
86  if ((time_smoothing_factor > 0) && (fabs(err) < time_error_threshold)){
87  ros::Duration correction = ros::Duration(err * (1 - time_smoothing_factor));
88  smoothed_timestamp += correction;
89  } else {
90  // error too high, or smoothing disabled - set smoothtime to last timestamp
91  smoothed_timestamp = recv_timestamp;
92  }
93  }
94  smoothtime_prev = smoothed_timestamp;
95  return smoothed_timestamp;
96  }
97 };
98 
99 class averager {
100  protected:
101  std::deque<double> deq;
102  unsigned int max_len;
103  double sum;
104  public:
105  averager(int max_len = 50){
106  this->max_len = max_len;
107  }
108  void add_new(double data) {
109  deq.push_back(data);
110  sum += data;
111  if (deq.size() > max_len) {
112  sum -= deq.front();
113  deq.pop_front();
114  }
115  }
116  double get_mean() {
117  return sum/deq.size();
118  }
119 };
120 
121 
122 int main(int argc, char *argv[]) {
123  ros::init(argc, argv, "sickld");
124  int port;
125  std::string ipaddress;
126  std::string frame_id;
127  bool inverted;
128  int sick_motor_speed = 5;//10; // Hz
129  double sick_step_angle = 1.5;//0.5;//0.25; // deg (0.125 = no gaps between spots)
130  double active_sector_start_angle = 0;
131  double active_sector_stop_angle = 300;//269.75;
132  double smoothing_factor, error_threshold;
133  ros::NodeHandle nh;
134  ros::NodeHandle nh_ns("~");
135  ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
136  nh_ns.param("port", port, DEFAULT_SICK_TCP_PORT);
137  nh_ns.param("ipaddress", ipaddress, (std::string)DEFAULT_SICK_IP_ADDRESS);
138  nh_ns.param("inverted", inverted, false);
139  nh_ns.param<std::string>("frame_id", frame_id, "laser");
140  nh_ns.param("timer_smoothing_factor", smoothing_factor, 0.97);
141  nh_ns.param("timer_error_threshold", error_threshold, 0.5);
142  nh_ns.param("resolution", sick_step_angle, 1.0);
143  nh_ns.param("start_angle", active_sector_start_angle, 0.);
144  nh_ns.param("stop_angle", active_sector_stop_angle, 300.);
145  nh_ns.param("scan_rate", sick_motor_speed, 10);
146  /* Define buffers for return values */
147  double range_values[SickLD::SICK_MAX_NUM_MEASUREMENTS] = {0};
148  unsigned int intensity_values[SickLD::SICK_MAX_NUM_MEASUREMENTS] = {0};
149  /* Define buffers to hold sector specific data */
150  unsigned int num_measurements = {0};
151  unsigned int sector_start_timestamp = {0};
152  unsigned int sector_stop_timestamp = {0};
153  double sector_step_angle = {0};
154  double sector_start_angle = {0};
155  double sector_stop_angle = {0};
156  /* Instantiate the object */
157  SickLD sick_ld(ipaddress.c_str(),port);
158  try {
159  /* Initialize the device */
161  // TODO: do some calls to setup the device - e.g. scan rate.
162  try {
163  sick_ld.SetSickGlobalParamsAndScanAreas((unsigned int)sick_motor_speed,
164  sick_step_angle,
165  &active_sector_start_angle,
166  &active_sector_stop_angle,
167  (unsigned int)1);
168  } catch (...) {
169  ROS_ERROR("Configuration error");
170  return -1;
171  }
172  smoothtime smoothtimer;
173  averager avg_fulldur, avg_scandur;
174  smoothtimer.set_smoothing_factor(smoothing_factor);
175  smoothtimer.set_error_threshold(error_threshold);
176  ros::Time last_start_scan_time;
177  unsigned int last_sector_stop_timestamp = 0;
178  double full_duration;
179  while (ros::ok()) {
180  /* Grab the measurements (from all sectors) */
181  sick_ld.GetSickMeasurements(range_values,
182  intensity_values,
183  &num_measurements,
184  NULL,
185  NULL,
186  &sector_step_angle,
187  &sector_start_angle,
188  &sector_stop_angle,
189  &sector_start_timestamp,
190  &sector_stop_timestamp
191  );
192  ros::Time end_scan_time = ros::Time::now();
193 
194  double scan_duration = (sector_stop_timestamp - sector_start_timestamp) * 1e-3;
195  avg_scandur.add_new(scan_duration);
196  scan_duration = avg_scandur.get_mean();
197 
198  if (last_sector_stop_timestamp == 0) {
199  full_duration = 1./((double)sick_motor_speed);
200  } else {
201  full_duration = (sector_stop_timestamp - last_sector_stop_timestamp) * 1e-3;
202  }
203  avg_fulldur.add_new(full_duration);
204  full_duration = avg_fulldur.get_mean();
205 
206  ros::Time smoothed_end_scan_time = smoothtimer.smooth_timestamp(end_scan_time, ros::Duration(full_duration));
207  ros::Time start_scan_time = smoothed_end_scan_time - ros::Duration(scan_duration);
208 
209  publish_scan(&scan_pub, range_values, num_measurements, intensity_values,
210  num_measurements, start_scan_time, scan_duration, inverted,
211  DEG2RAD((float)sector_start_angle), DEG2RAD((float)sector_stop_angle), frame_id);
212 
213  ROS_DEBUG_STREAM("Num meas: " << num_measurements
214  << " smoothed start T: " << start_scan_time
215  << " smoothed rate: " << 1./(start_scan_time - last_start_scan_time).toSec()
216  << " raw start T: " << sector_start_timestamp
217  << " raw stop T: " << sector_stop_timestamp
218  << " dur: " << full_duration
219  << " step A: " << sector_step_angle
220  << " start A: " << sector_start_angle
221  << " stop A: " << sector_stop_angle);
222  last_start_scan_time = start_scan_time;
223  last_sector_stop_timestamp = sector_stop_timestamp;
224  ros::spinOnce();
225  }
226  /* Uninitialize the device */
228  }
229  catch(...) {
230  ROS_ERROR("Error");
231  return -1;
232  }
233  return 0;
234 }
void set_smoothing_factor(double smoothing_factor)
Between 0 and 1, bigger is smoother.
Definition: sickld.cpp:72
ros::Time smoothtime_prev
Definition: sickld.cpp:62
void publish_scan(ros::Publisher *pub, double *range_values, uint32_t n_range_values, unsigned int *intensity_values, uint32_t n_intensity_values, ros::Time start, double scan_time, bool inverted, float angle_min, float angle_max, std::string frame_id)
Definition: sickld.cpp:22
double time_smoothing_factor
Definition: sickld.cpp:63
void publish(const boost::shared_ptr< M > &message) const
ros::Time smooth_timestamp(ros::Time recv_timestamp, ros::Duration expctd_dur)
Definition: sickld.cpp:79
unsigned int max_len
Definition: sickld.cpp:102
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
Definition: sickld.cpp:122
double get_mean()
Definition: sickld.cpp:116
double sum
Definition: sickld.cpp:103
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
smoothtime()
Definition: sickld.cpp:67
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void SetSickGlobalParamsAndScanAreas(const unsigned int sick_motor_speed, const double sick_step_angle, const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors)
void set_error_threshold(double err_threshold)
Between 0 and 1, threshold on jitter acceptability, higher accepts more jitter before discarding...
Definition: sickld.cpp:76
#define DEFAULT_SICK_IP_ADDRESS
#define ROS_DEBUG_STREAM(args)
void add_new(double data)
Definition: sickld.cpp:108
double error_threshold
Definition: sickld.cpp:64
void GetSickMeasurements(double *const range_measurements, unsigned int *const echo_measurements=NULL, unsigned int *const num_measurements=NULL, unsigned int *const sector_ids=NULL, unsigned int *const sector_data_offsets=NULL, double *const sector_step_angles=NULL, double *const sector_start_angles=NULL, double *const sector_stop_angles=NULL, unsigned int *const sector_start_timestamps=NULL, unsigned int *const sector_stop_timestamps=NULL)
#define DEG2RAD(x)
Definition: sickld.cpp:16
static Time now()
#define DEFAULT_SICK_TCP_PORT
SickLD * sick_ld
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
averager(int max_len=50)
Definition: sickld.cpp:105
std::deque< double > deq
Definition: sickld.cpp:101


sicktoolbox_wrapper
Author(s): Morgan Quigley
autogenerated on Mon Jun 10 2019 15:03:33