Skip to content

Commit 7f9f55a

Browse files
committed
update naming and linting
1 parent f6b2b19 commit 7f9f55a

File tree

3 files changed

+8
-7
lines changed

3 files changed

+8
-7
lines changed

nav2_collision_monitor/params/collision_monitor_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ collision_monitor:
4848
min_points: 6
4949
visualize: True
5050
polygon_pub_topic: "polygon_approach"
51-
velocity_polygon: ["rotation", "translation_forward", "translation_backward", "stop"] # third priority
51+
velocity_polygons: ["rotation", "translation_forward", "translation_backward", "stop"] # third priority
5252
rotation:
5353
points: [0.3, 0.3, 0.3, -0.3, -0.3, -0.3, -0.3, 0.3]
5454
holonomic: false

nav2_collision_monitor/src/polygon.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -474,11 +474,11 @@ bool Polygon::getParameters(
474474

475475
// Velocity polygon will be used
476476
nav2_util::declare_parameter_if_not_declared(
477-
node, polygon_name_ + ".velocity_polygon", rclcpp::PARAMETER_STRING_ARRAY);
478-
std::vector<std::string> velocity_polygon_array = node->get_parameter(
479-
polygon_name_ + ".velocity_polygon").as_string_array();
477+
node, polygon_name_ + ".velocity_polygons", rclcpp::PARAMETER_STRING_ARRAY);
478+
std::vector<std::string> velocity_polygons = node->get_parameter(
479+
polygon_name_ + ".velocity_polygons").as_string_array();
480480

481-
for (std::string velocity_polygon_name : velocity_polygon_array) {
481+
for (std::string velocity_polygon_name : velocity_polygons) {
482482
auto velocity_polygon = std::make_shared<VelocityPolygon>(
483483
node_, polygon_name_,
484484
velocity_polygon_name,

nav2_collision_monitor/src/velocity_polygon.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,9 @@ bool VelocityPolygon::getParameters()
7676
// polygon_sub_topic param
7777
nav2_util::declare_parameter_if_not_declared(
7878
node, polygon_name_ + "." + velocity_polygon_name_ + ".polygon_sub_topic",
79-
rclcpp::ParameterValue("/collision_monitor/"+polygon_name_ +"/"+velocity_polygon_name_+"/set_polygon"));
79+
rclcpp::ParameterValue(
80+
"/collision_monitor/" + polygon_name_ + "/" + velocity_polygon_name_ +
81+
"/set_polygon"));
8082
polygon_sub_topic_ =
8183
node->get_parameter(
8284
polygon_name_ + "." + velocity_polygon_name_ +
@@ -198,7 +200,6 @@ void VelocityPolygon::updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSha
198200
}
199201

200202

201-
202203
bool VelocityPolygon::isInRange(const Velocity & cmd_vel_in)
203204
{
204205
if (holonomic_) {

0 commit comments

Comments
 (0)