Skip to content

Commit 8264866

Browse files
author
asarazin
committed
Collision monitor: select specific observation sources for polygon
Signed-off-by: asarazin <[email protected]>
1 parent ebe60dc commit 8264866

File tree

3 files changed

+68
-5
lines changed

3 files changed

+68
-5
lines changed

nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -126,6 +126,12 @@ class Polygon
126126
*/
127127
virtual void getPolygon(std::vector<Point> & poly) const;
128128

129+
/**
130+
* @brief Obtains the name of the observation sources for current polygon.
131+
* @return Names of the observation sources
132+
*/
133+
std::vector<std::string> getSourcesNames() const;
134+
129135
/**
130136
* @brief Returns true if polygon points were set.
131137
* Otherwise, prints a warning and returns false.
@@ -269,6 +275,8 @@ class Polygon
269275
rclcpp::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_sub_;
270276
/// @brief Footprint subscriber
271277
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
278+
/// @brief Name of the observation sources to check for polygon
279+
std::vector<std::string> sources_names_;
272280

273281
// Global variables
274282
/// @brief TF buffer

nav2_collision_monitor/src/collision_monitor_node.cpp

Lines changed: 34 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -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

nav2_collision_monitor/src/polygon.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -157,6 +157,11 @@ double Polygon::getTimeBeforeCollision() const
157157
return time_before_collision_;
158158
}
159159

160+
std::vector<std::string> Polygon::getSourcesNames() const
161+
{
162+
return sources_names_;
163+
}
164+
160165
void Polygon::getPolygon(std::vector<Point> & poly) const
161166
{
162167
poly = poly_;
@@ -392,6 +397,27 @@ bool Polygon::getCommonParameters(
392397
node->get_parameter(polygon_name_ + ".footprint_topic").as_string();
393398
}
394399
}
400+
401+
// By default, use all observation sources for polygon
402+
nav2_util::declare_parameter_if_not_declared(
403+
node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
404+
std::vector<std::string> source_names =
405+
node->get_parameter("observation_sources").as_string_array();
406+
nav2_util::declare_parameter_if_not_declared(
407+
node, polygon_name_ + ".sources_names", rclcpp::ParameterValue(source_names));
408+
sources_names_ = node->get_parameter(polygon_name_ + ".sources_names").as_string_array();
409+
410+
// Check the observation sources configured for polygon are defined
411+
for (auto source_name : sources_names_) {
412+
if (std::find(source_names.begin(), source_names.end(), source_name) == source_names.end()) {
413+
RCLCPP_ERROR_STREAM(
414+
logger_,
415+
"Observation source [" << source_name <<
416+
"] configured for polygon [" << getName() <<
417+
"] is not defined!");
418+
return false;
419+
}
420+
}
395421
} catch (const std::exception & ex) {
396422
RCLCPP_ERROR(
397423
logger_,

0 commit comments

Comments
 (0)