laserscan_interpreter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2018, Andreas Gustavsson.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *
34 * Author: Andreas Gustavsson
35 *********************************************************************/
36 
37 /* ROS */
38 #include <ros/ros.h>
39 #include <tf2_ros/buffer.h>
41 #include <tf2_ros/message_filter.h>
44 #include <sensor_msgs/LaserScan.h>
45 
46 #ifdef NODELET
48 #endif
49 
50 /* C/C++ */
51 #include <iostream>
52 #include <cmath>
53 #include <pthread.h>
54 
55 // #ifdef LSARRAY
56 // #include <omp.h>
57 // #endif
58 
59 /* LOCAL INCLUDES */
62 
63 
64 #ifdef NODELET
65 /* TELL ROS ABOUT THIS NODELET PLUGIN */
66 # ifdef LSARRAY
67 PLUGINLIB_EXPORT_CLASS(find_moving_objects::LaserScanArrayInterpreterNodelet, nodelet::Nodelet)
68 # else
69 PLUGINLIB_EXPORT_CLASS(find_moving_objects::LaserScanInterpreterNodelet, nodelet::Nodelet)
70 # endif
71 #endif
72 
73 
74 namespace find_moving_objects
75 {
76 
77 /*
78  * Standard Units of Measure and Coordinate Conventions: http://www.ros.org/reps/rep-0103.html
79  * Coordinate Frames for Mobile Platforms: http://www.ros.org/reps/rep-0105.html
80  */
81 
82 
83 /* CONFIDENCE CALCULATION FOR BANK */
84 double a_factor = -20 / 3;
85 double root_1=0.35, root_2=0.65; // optimized for bank coverage of 0.5s, adapted in hz calculation
86 double width_factor = 0.0;
87 double Bank::calculateConfidence(const MovingObject & mo,
88  const BankArgument & ba,
89  const double dt,
90  const double mo_old_width)
91 {
92  return /*ba.ema_alpha **/ // Using weighting decay decreases the confidence while,
93  (ba.base_confidence // how much we trust the sensor itself,
94  + a_factor * (dt-root_1) * (dt-root_2) // a well-adapted bank size in relation to the sensor rate and environmental context
95  - width_factor * fabs(mo.seen_width - mo_old_width)); // and low difference in width between old and new object,
96  // make us more confident
97 }
98 
99 
100 
101 /* CONSTRUCTOR */
102 #ifdef NODELET
103 # ifdef LSARRAY
104 LaserScanArrayInterpreterNodelet::LaserScanArrayInterpreterNodelet()
105 # else
106 LaserScanInterpreterNodelet::LaserScanInterpreterNodelet()
107 # endif
108 #endif
109 #ifdef NODE
110 # ifdef LSARRAY
111 LaserScanArrayInterpreterNode::LaserScanArrayInterpreterNode()
112 # else
113 LaserScanInterpreterNode::LaserScanInterpreterNode()
114 # endif
115 #endif
118 {
119 #ifdef NODELET
120  // Wait for time to become valid, then start bank
122 #endif
123 
124  tf_filter = NULL;
125  tf_listener = NULL;
126  tf_buffer = NULL;
127 
128 #ifdef NODE
129  onInit();
130 #endif
131 }
132 
133 
134 
135 /* DESTRUCTOR */
136 #ifdef LSARRAY
137 # ifdef NODELET
138 LaserScanArrayInterpreterNodelet::~LaserScanArrayInterpreterNodelet()
139 # endif
140 # ifdef NODE
141 LaserScanArrayInterpreterNode::~LaserScanArrayInterpreterNode()
142 # endif
143 #else
144 # ifdef NODELET
145 LaserScanInterpreterNodelet::~LaserScanInterpreterNodelet()
146 # endif
147 # ifdef NODE
148 LaserScanInterpreterNode::~LaserScanInterpreterNode()
149 # endif
150 #endif
151 {
152  int nr_banks = banks.size();
153  for (int i=0; i<nr_banks; ++i)
154  {
155  delete banks[i];
156  }
157  banks.clear();
158 
159  if (tf_filter != NULL) delete tf_filter;
160  if (tf_buffer != NULL) delete tf_buffer;
161 }
162 
163 
164 
165 /* CALLBACK */
166 #ifdef LSARRAY
167 # ifdef NODELET
168 void LaserScanArrayInterpreterNodelet::laserScanArrayCallback(const find_moving_objects::LaserScanArray::ConstPtr & msg)
169 # endif
170 # ifdef NODE
171 void LaserScanArrayInterpreterNode::laserScanArrayCallback(const find_moving_objects::LaserScanArray::ConstPtr & msg)
172 # endif
173 #else
174 # ifdef NODELET
175 void LaserScanInterpreterNodelet::laserScanCallback(const sensor_msgs::LaserScan::ConstPtr & msg)
176 # endif
177 # ifdef NODE
178 void LaserScanInterpreterNode::laserScanCallback(const sensor_msgs::LaserScan::ConstPtr & msg)
179 # endif
180 #endif
181 {
182  switch (state)
183  {
184  /*
185  * MAIN STATE - WHEN ALL IS INITIALIZED
186  */
187  case FIND_MOVING_OBJECTS:
188  {
189 #ifdef LSARRAY
190  // Consider the msgs of msg in parallel
191 // #pragma omp parallel for
192  for (int i=0; i<msg->msgs.size(); ++i)
193  {
194  // Can message be added to bank?
195  if (banks[i]->addMessage(&(msg->msgs[i])) != 0)
196  {
197  // Adding message failed (should never happen for LaserScan), try the next one
198  continue;
199  }
200 
201  // If so, then find and report objects
202  banks[i]->findAndReportMovingObjects();
203  }
204 #else
205  // Can message be added to bank?
206  if (banks[0]->addMessage(&(*msg)) != 0) // De-reference ConstPtr object and take reference of result to get a
207  // pointer to a PointCloud2 object
208  {
209  // Adding message failed (should never happen for LaserScan)
210  break;
211  }
212 
213  // If so, then find and report objects
214  banks[0]->findAndReportMovingObjects();
215 #endif
216  break;
217  }
218 
219 
220  /*
221  * BEFORE MAIN STATE CAN BE SET, THIS CASE MUST HAVE BEEN EXECUTED
222  */
223  case INIT_BANKS:
224  {
225  // Debug frame to see e.g. if we are dealing with an optical frame
226 #ifdef NODELET
227  NODELET_DEBUG_STREAM("LaserScanArray sensor is using frame: " << msg->header.frame_id);
228 #endif
229 #ifdef NODE
230  ROS_DEBUG_STREAM("LaserScanArray sensor is using frame: " << msg->header.frame_id);
231 #endif
232 
233 #ifdef LSARRAY
234  // Create banks
235  const int nr_msgs = msg->msgs.size();
236  if (banks.size() == 0)
237  {
238  // If reaching this point, then this block has not been executed before
239  // If it has, then it will not be executed again, and the modifications to banks and bank_arguments are hence
240  // maintained valid, assuming that the new message contains the same number of messages in the array
241  bank_arguments.resize(nr_msgs);
242  banks.resize(nr_msgs);
243  for (int i=0; i<nr_msgs; ++i)
244  {
245  // Create bank and start listening to tf data
247 
248  // Copy first bank argument
250  }
251 
252  // Modify bank arguments
253  for (int i=0; i<nr_msgs; ++i)
254  {
255  const std::string append_str = "_" + std::to_string(i);
256  bank_arguments[i].topic_ema.append(append_str);
257  bank_arguments[i].topic_objects_closest_point_markers.append(append_str);
258  bank_arguments[i].topic_objects_velocity_arrows.append(append_str);
259  bank_arguments[i].topic_objects_delta_position_lines.append(append_str);
260  bank_arguments[i].topic_objects_width_lines.append(append_str);
261 
262  bank_arguments[i].velocity_arrow_ns.append(append_str);
263  bank_arguments[i].delta_position_line_ns.append(append_str);
264  bank_arguments[i].width_line_ns.append(append_str);
265 
266  bank_arguments[i].node_name_suffix.append(append_str);
267  }
268  }
269 
270  // Init banks
271  for (int i=0; i<nr_msgs; ++i)
272  {
273  banks[i]->init(bank_arguments[i], &(msg->msgs[i])); // addFirstMessage always succeeds, no bool needed for init!
274  }
275 #else
276  // Create banks
277  if (banks.size() == 0)
278  {
279  banks.resize(1);
281  }
282 
283  // Init bank
284  if (banks[0]->init(bank_arguments[0], &(*msg)) != 0)
285  {
286  // If init fails (should never happen for LaserScan) we do not change state, but use this one again
287  break;
288  }
289 #endif
290 
291  // Change state
293  break;
294  }
295 
296 
297  /*
298  * CALCULATE HZ OF TOPIC AND UPDATE SIZE OF BANK
299  */
300  case CALCULATE_HZ:
301  {
302  // spin until target is reached
304  const double elapsed_time = ros::Time::now().toSec() - start_time;
305 
306  // Are we done?
307  if (max_time <= elapsed_time ||
309  {
310  // Calculate HZ
311  const double hz = received_messages / elapsed_time;
312 
313  // Set nr of messages in bank
314  const double nr_scans = optimize_nr_scans_in_bank * hz;
315  bank_arguments[0].nr_scans_in_bank = nr_scans - ((long) nr_scans) == 0.0 ? nr_scans + 1 : ceil(nr_scans);
316 
317  // Sanity check
318  if (bank_arguments[0].nr_scans_in_bank < 2)
319  {
320  bank_arguments[0].nr_scans_in_bank = 2;
321  }
322 
323  // Update confidence roots and amplitude factor
324  root_1 = optimize_nr_scans_in_bank * 0.6;
326  a_factor = 4 * max_confidence_for_dt_match / (2*root_1*root_2 - root_1*root_1 - root_2*root_2);
327 
328 #ifdef NODELET
329  NODELET_INFO_STREAM("Topic " << subscribe_topic << " has rate " << hz << "Hz" <<
330  " (based on " << received_messages << " msgs during " << elapsed_time << " seconds)");
331  NODELET_INFO_STREAM("Optimized bank size is " << bank_arguments[0].nr_scans_in_bank);
332 #endif
333 #ifdef NODE
334  ROS_INFO_STREAM("Topic " << subscribe_topic << " has rate " << hz << "Hz" <<
335  " (based on " << received_messages << " msgs during " << elapsed_time << " seconds)");
336  ROS_INFO_STREAM("Optimized bank size is " << bank_arguments[0].nr_scans_in_bank);
337 #endif
338 
339  // Change state since we are done
340  state = INIT_BANKS;
341  }
342  break;
343  }
344 
345 
346  /*
347  * WHEN CALCULATING HZ OF TOPIC, WAIT FOR A MESSAGE TO ARRIVE AND SAVE THE TIME
348  */
350  {
351  // Set start time
353 
354  // Change state
356  break;
357  }
358 
359 
360  /*
361  * THERE ARE NO MORE STATES - TERMINATE, THIS IS AN ERROR
362  */
363  default:
364  {
365  ROS_ERROR("Message callback is in an unknown state");
366  ROS_BREAK();
367  }
368  }
369 }
370 
371 
372 
373 /* ENTRY POINT FOR NODELET AND INIT FOR NODE */
374 #ifdef NODELET
375 # ifdef LSARRAY
376 void LaserScanArrayInterpreterNodelet::onInit()
377 # else
378 void LaserScanInterpreterNodelet::onInit()
379 # endif
380 {
381  // Node handles
382  nh = getNodeHandle();
383  nh_priv = getPrivateNodeHandle();
384 #endif
385 #ifdef NODE
386 # ifdef LSARRAY
387 void LaserScanArrayInterpreterNode::onInit()
388 # else
389 void LaserScanInterpreterNode::onInit()
390 # endif
391 {
392  // Node handles
393  nh = ros::NodeHandle();
394  nh_priv = ros::NodeHandle("~");
395 #endif
396 
397  // Init bank_argument with parameters
401  nh_priv.param("ema_alpha", bank_argument.ema_alpha, default_ema_alpha);
402  nh_priv.param("nr_scans_in_bank", bank_argument.nr_scans_in_bank, default_nr_scans_in_bank);
403  nh_priv.param("object_threshold_edge_max_delta_range", bank_argument.object_threshold_edge_max_delta_range, default_object_threshold_edge_max_delta_range);
404  nh_priv.param("object_threshold_min_nr_points", bank_argument.object_threshold_min_nr_points, default_object_threshold_min_nr_points);
405  nh_priv.param("object_threshold_max_distance", bank_argument.object_threshold_max_distance, default_object_threshold_max_distance);
406  nh_priv.param("object_threshold_min_speed", bank_argument.object_threshold_min_speed, default_object_threshold_min_speed);
407  nh_priv.param("object_threshold_max_delta_width_in_points", bank_argument.object_threshold_max_delta_width_in_points, default_object_threshold_max_delta_width_in_points);
408  nh_priv.param("object_threshold_bank_tracking_max_delta_distance", bank_argument.object_threshold_bank_tracking_max_delta_distance, default_object_threshold_bank_tracking_max_delta_distance);
409  nh_priv.param("object_threshold_min_confidence", bank_argument.object_threshold_min_confidence, default_object_threshold_min_confidence);
410  nh_priv.param("base_confidence", bank_argument.base_confidence, default_base_confidence);
411  nh_priv.param("publish_ema", bank_argument.publish_ema, default_publish_ema);
412  nh_priv.param("publish_objects_closest_points_markers", bank_argument.publish_objects_closest_point_markers, default_publish_objects_closest_points_markers);
413  nh_priv.param("publish_objects_velocity_arrows", bank_argument.publish_objects_velocity_arrows, default_publish_objects_velocity_arrows);
414  nh_priv.param("publish_objects_delta_position_lines", bank_argument.publish_objects_delta_position_lines, default_publish_objects_delta_position_lines);
415  nh_priv.param("publish_objects_width_lines", bank_argument.publish_objects_width_lines, default_publish_objects_width_lines);
416  nh_priv.param("velocity_arrows_use_full_gray_scale", bank_argument.velocity_arrows_use_full_gray_scale, default_velocity_arrows_use_full_gray_scale);
417  nh_priv.param("velocity_arrows_use_sensor_frame", bank_argument.velocity_arrows_use_sensor_frame, default_velocity_arrows_use_sensor_frame);
418  nh_priv.param("velocity_arrows_use_base_frame", bank_argument.velocity_arrows_use_base_frame, default_velocity_arrows_use_base_frame);
419  nh_priv.param("velocity_arrows_use_fixed_frame", bank_argument.velocity_arrows_use_fixed_frame, default_velocity_arrows_use_fixed_frame);
420  nh_priv.param("publish_objects", bank_argument.publish_objects, default_publish_objects);
421  nh_priv.param("map_frame", bank_argument.map_frame, default_map_frame);
422  nh_priv.param("fixed_frame", bank_argument.fixed_frame, default_fixed_frame);
423  nh_priv.param("base_frame", bank_argument.base_frame, default_base_frame);
424  nh_priv.param("ns_velocity_arrows", bank_argument.velocity_arrow_ns, default_ns_velocity_arrows);
425  nh_priv.param("ns_delta_position_lines", bank_argument.delta_position_line_ns, default_ns_delta_position_lines);
426  nh_priv.param("ns_width_lines", bank_argument.width_line_ns, default_ns_width_lines);
427  nh_priv.param("topic_ema", bank_argument.topic_ema, default_topic_ema);
428  nh_priv.param("topic_objects_closest_points_markers", bank_argument.topic_objects_closest_point_markers, default_topic_objects_closest_points_markers);
429  nh_priv.param("topic_objects_velocity_arrows", bank_argument.topic_objects_velocity_arrows, default_topic_objects_velocity_arrows);
430  nh_priv.param("topic_objects_delta_position_lines", bank_argument.topic_objects_delta_position_lines, default_topic_objects_delta_position_lines);
431  nh_priv.param("topic_objects_width_lines", bank_argument.topic_objects_width_lines, default_topic_objects_width_lines);
432  nh_priv.param("topic_objects", bank_argument.topic_objects, default_topic_objects);
433  nh_priv.param("publish_buffer_size", bank_argument.publish_buffer_size, default_publish_buffer_size);
434 
435  // Add this as the first bank_argument
436  bank_arguments.push_back(bank_argument);
437 
438  // Optimize bank size?
441 
442  // If optimize_nr_scans_in_bank != 0, then yes
444  {
446  }
447  else
448  {
449  state = INIT_BANKS;
450  }
451 
452  // Delta width confidence factor
453  nh_priv.param("delta_width_confidence_decrease_factor", width_factor, default_delta_width_confidence_decrease_factor);
454 
455  // Set up target frames for message filter
456  tf_filter_target_frames.push_back(bank_argument.map_frame);
457  if (strcmp(bank_argument.map_frame.c_str(), bank_argument.fixed_frame.c_str()) != 0)
458  {
459  tf_filter_target_frames.push_back(bank_argument.fixed_frame);
460  }
461  if (strcmp(bank_argument.map_frame.c_str(), bank_argument.base_frame.c_str()) != 0 &&
462  strcmp(bank_argument.fixed_frame.c_str(), bank_argument.base_frame.c_str()) != 0)
463  {
464  tf_filter_target_frames.push_back(bank_argument.base_frame);
465  }
466 
467  // Create tf2 buffer, listener, subscriber and filter
470 #ifdef LSARRAY
474 #else
476  tf_subscriber->subscribe(nh, subscribe_topic, subscribe_buffer_size);
478 #endif
479  tf_filter->setTargetFrames(tf_filter_target_frames);
480 
481  // Register callback in filter
482  tf_filter->registerCallback( boost::bind(
483 #ifdef NODELET
484 # ifdef LSARRAY
485  &LaserScanArrayInterpreterNodelet::laserScanArrayCallback,
486 # else
488 # endif
489 #endif
490 #ifdef NODE
491 # ifdef LSARRAY
492  &LaserScanArrayInterpreterNode::laserScanArrayCallback,
493 # else
495 # endif
496 #endif
497  this, _1) );
498 }
499 
500 } // namespace find_moving_objects
501 
502 
503 
504 #ifdef NODE
505 using namespace find_moving_objects;
506 
507 /* ENTRY POINT */
508 int main (int argc, char ** argv)
509 {
510 # ifdef LSARRAY
511  // Init ROS
512  ros::init(argc, argv, "laserscanarray_interpreter", ros::init_options::AnonymousName);
513 
514  // Create and init node object
515  LaserScanArrayInterpreterNode ls_interpreter;
516 # else
517  // Init ROS
518  ros::init(argc, argv, "laserscan_interpreter", ros::init_options::AnonymousName);
519 
520  // Create and init node object
521  LaserScanInterpreterNode ls_interpreter;
522 # endif
523 
524  // Enter receive loop
525  ros::spin();
526 
527  return 0;
528 }
529 #endif
#define NODELET_INFO_STREAM(...)
const bool default_publish_objects_width_lines
const bool default_publish_objects_closest_points_markers
const std::string default_ns_velocity_arrows
const double default_object_threshold_edge_max_delta_range
const bool default_velocity_arrows_use_fixed_frame
std::string topic_objects_closest_point_markers
Definition: bank.h:209
std::string delta_position_line_ns
Definition: bank.h:193
const bool default_publish_objects_delta_position_lines
double object_threshold_bank_tracking_max_delta_distance
Definition: bank.h:129
BankArgument bank_argument
Definition: bank.h:360
virtual long init(BankArgument bank_argument, const sensor_msgs::LaserScan *msg)
Definition: bank.cpp:2740
virtual long addMessage(const sensor_msgs::LaserScan *msg)
Definition: bank.cpp:2820
message_filters::Subscriber< sensor_msgs::LaserScan > * tf_subscriber
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const double default_base_confidence
const std::string default_topic_objects_closest_points_markers
const double default_ema_alpha
const std::string default_subscribe_topic
const std::string default_topic_objects
const int default_subscribe_buffer_size
const bool default_velocity_arrows_use_full_gray_scale
void laserScanCallback(const sensor_msgs::LaserScan::ConstPtr &msg)
const bool default_velocity_arrows_use_base_frame
ROSCPP_DECL void spin(Spinner &spinner)
const std::string default_topic_objects_width_lines
const double default_object_threshold_min_speed
double object_threshold_edge_max_delta_range
Definition: bank.h:104
std::string topic_objects_width_lines
Definition: bank.h:221
const double default_max_confidence_for_dt_match
const std::string default_ns_delta_position_lines
const std::string default_ns_width_lines
const int default_object_threshold_max_delta_width_in_points
const double default_delta_width_confidence_decrease_factor
const std::string default_topic_ema
std::vector< BankArgument > bank_arguments
const double default_optimize_nr_scans_in_bank
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const double default_object_threshold_bank_tracking_max_delta_distance
const double default_object_threshold_min_confidence
const std::string default_fixed_frame
const int default_object_threshold_min_nr_points
int main(int argc, char **argv)
const std::string default_topic_objects_delta_position_lines
std::string topic_objects_velocity_arrows
Definition: bank.h:213
virtual double calculateConfidence(const find_moving_objects::MovingObject &mo, const find_moving_objects::BankArgument &ba, const double delta_time, const double mo_old_width)
std::string topic_objects_delta_position_lines
Definition: bank.h:217
const double default_object_threshold_max_distance
#define ROS_DEBUG_STREAM(args)
const bool default_publish_objects
#define NODELET_DEBUG_STREAM(...)
tf2_ros::Buffer * tf_buffer
Definition: bank.h:378
tf2_ros::TransformListener * tf_listener
tf2_ros::MessageFilter< sensor_msgs::LaserScan > * tf_filter
const std::string default_base_frame
std::vector< Bank * > banks
const std::string default_map_frame
const bool default_velocity_arrows_use_sensor_frame
const int default_publish_buffer_size
#define ROS_INFO_STREAM(args)
int object_threshold_max_delta_width_in_points
Definition: bank.h:120
static Time now()
const bool default_publish_objects_velocity_arrows
static bool waitForValid()
#define ROS_BREAK()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
std::vector< std::string > tf_filter_target_frames
const std::string default_topic_objects_velocity_arrows


find_moving_objects
Author(s): Andreas Gustavsson
autogenerated on Mon Jun 10 2019 13:13:19