Skip to content

Commit

Permalink
continue if points are not defined
Browse files Browse the repository at this point in the history
  • Loading branch information
kaichie committed Sep 26, 2023
1 parent b97cbb7 commit 5dc403b
Showing 1 changed file with 18 additions and 9 deletions.
27 changes: 18 additions & 9 deletions nav2_collision_monitor/src/velocity_polygon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,18 +48,27 @@ bool VelocityPolygon::getParameters()
}

try {
nav2_util::declare_parameter_if_not_declared(
node, polygon_name_ + "." + velocity_polygon_name_ + ".points",
rclcpp::PARAMETER_DOUBLE_ARRAY);
std::vector<double> polygon_points = node->get_parameter(
polygon_name_ + "." + velocity_polygon_name_ + ".points").as_double_array();

if (!Polygon::setPolygonShape(polygon_points, poly_)) {
RCLCPP_ERROR(
try {
// Leave it uninitialized: it will throw an inner exception if the parameter is not set
nav2_util::declare_parameter_if_not_declared(
node, polygon_name_ + "." + velocity_polygon_name_ + ".points",
rclcpp::PARAMETER_DOUBLE_ARRAY);
std::vector<double> polygon_points = node->get_parameter(
polygon_name_ + "." + velocity_polygon_name_ + ".points").as_double_array();

if (!Polygon::setPolygonShape(polygon_points, poly_)) {
RCLCPP_ERROR(
logger_,
"[%s][%s]: Polygon has incorrect points description",
polygon_name_.c_str(), velocity_polygon_name_.c_str());
return false;
}
} catch (const rclcpp::exceptions::ParameterUninitializedException &) {
RCLCPP_INFO(
logger_,
"[%s][%s]: Polygon has incorrect points description",
"[%s][%s]: Polygon points are not defined. Will wait for dynamic subscription instead.",
polygon_name_.c_str(), velocity_polygon_name_.c_str());
return false;
}

std::string polygon_sub_topic = "/collision_monitor/" + polygon_name_ + "/" +
Expand Down

0 comments on commit 5dc403b

Please sign in to comment.