@@ -270,17 +270,17 @@ bool CollisionMonitor::getParameters(
270270 stop_pub_timeout_ =
271271 rclcpp::Duration::from_seconds (get_parameter (" stop_pub_timeout" ).as_double ());
272272
273- if (!configurePolygons (base_frame_id, transform_tolerance)) {
274- return false ;
275- }
276-
277273 if (
278274 !configureSources (
279275 base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
280276 {
281277 return false ;
282278 }
283279
280+ if (!configurePolygons (base_frame_id, transform_tolerance)) {
281+ return false ;
282+ }
283+
284284 return true ;
285285}
286286
@@ -412,7 +412,14 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in, const std_msgs::msg:
412412 }
413413
414414 // Points array collected from different data sources in a robot base frame
415- std::vector<Point> collision_points;
415+ std::unordered_map<std::string, std::vector<Point>> sources_collision_points_map;
416+
417+ // Fill collision_points array from different data sources
418+ for (std::shared_ptr<Source> source : sources_) {
419+ std::vector<Point> collision_points;
420+ source->getData (curr_time, collision_points);
421+ sources_collision_points_map.insert ({source->getSourceName (), collision_points});
422+ }
416423
417424 // By default - there is no action
418425 Action robot_action{DO_NOTHING, cmd_vel_in, " " };
@@ -476,6 +483,28 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in, const std_msgs::msg:
476483 // Update polygon coordinates
477484 polygon->updatePolygon (cmd_vel_in);
478485
486+ // Get collision points for sources associated to polygon
487+ std::vector<std::string> sources_names = polygon->getSourcesNames ();
488+ std::vector<Point> collision_points;
489+ for (auto source_name : sources_names) {
490+ try {
491+ // Get vector for source
492+ auto source_collision_points = sources_collision_points_map.at (source_name);
493+ // Concatenate vectors
494+ collision_points.insert (
495+ collision_points.end (),
496+ source_collision_points.begin (),
497+ source_collision_points.end ());
498+ } catch (std::exception & e) {
499+ RCLCPP_ERROR_STREAM_THROTTLE (
500+ get_logger (),
501+ *get_clock (),
502+ 1000 ,
503+ " Observation source [" << source_name <<
504+ " ] configured for polygon [" << polygon->getName () << " ] is not defined!" );
505+ }
506+ }
507+
479508 const ActionType at = polygon->getActionType ();
480509 if (at == STOP || at == SLOWDOWN || at == LIMIT) {
481510 // Process STOP/SLOWDOWN for the selected polygon
0 commit comments