diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index 85dc80b39cb..dd03b3be022 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -1167,7 +1167,7 @@ AmclNode::dynamicParametersCallback( if (param_type == ParameterType::PARAMETER_DOUBLE) { if (param_name == "alpha1") { alpha1_ = parameter.as_double(); - // alpha restricted to be non-negative + //alpha restricted to be non-negative if (alpha1_ < 0.0) { RCLCPP_WARN( get_logger(), "You've set alpha1 to be negative," @@ -1177,7 +1177,7 @@ AmclNode::dynamicParametersCallback( reinit_odom = true; } else if (param_name == "alpha2") { alpha2_ = parameter.as_double(); - // alpha restricted to be non-negative + //alpha restricted to be non-negative if (alpha2_ < 0.0) { RCLCPP_WARN( get_logger(), "You've set alpha2 to be negative," @@ -1187,7 +1187,7 @@ AmclNode::dynamicParametersCallback( reinit_odom = true; } else if (param_name == "alpha3") { alpha3_ = parameter.as_double(); - // alpha restricted to be non-negative + //alpha restricted to be non-negative if (alpha3_ < 0.0) { RCLCPP_WARN( get_logger(), "You've set alpha3 to be negative," @@ -1197,7 +1197,7 @@ AmclNode::dynamicParametersCallback( reinit_odom = true; } else if (param_name == "alpha4") { alpha4_ = parameter.as_double(); - // alpha restricted to be non-negative + //alpha restricted to be non-negative if (alpha4_ < 0.0) { RCLCPP_WARN( get_logger(), "You've set alpha4 to be negative," @@ -1207,7 +1207,7 @@ AmclNode::dynamicParametersCallback( reinit_odom = true; } else if (param_name == "alpha5") { alpha5_ = parameter.as_double(); - // alpha restricted to be non-negative + //alpha restricted to be non-negative if (alpha5_ < 0.0) { RCLCPP_WARN( get_logger(), "You've set alpha5 to be negative," diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 0e3427a17b8..5f0e6e775d1 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -277,34 +277,12 @@ planner_server: ros__parameters: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] - GridBased: - plugin: "nav2_smac_planner/SmacPlannerLattice" - allow_unknown: true # Allow traveling in unknown space - tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found. - max_iterations: 1000000 # Maximum total iterations to search for before failing (in case unreachable), set to -1 to disable - max_on_approach_iterations: 1000 # Maximum number of iterations after within tolerances to continue to try to find exact solution - max_planning_time: 5.0 # Max time in s for planner to plan, smooth - analytic_expansion_ratio: 3.5 # The ratio to attempt analytic expansions during search for final approach. - analytic_expansion_max_length: 3.0 # For Hybrid/Lattice nodes: The maximum length of the analytic expansion to be considered valid to prevent unsafe shortcutting - reverse_penalty: 2.0 # Penalty to apply if motion is reversing, must be => 1 - change_penalty: 0.05 # Penalty to apply if motion is changing directions (L to R), must be >= 0 - non_straight_penalty: 1.05 # Penalty to apply if motion is non-straight, must be => 1 - cost_penalty: 2.0 # Penalty to apply to higher cost areas when adding into the obstacle map dynamic programming distance expansion heuristic. This drives the robot more towards the center of passages. A value between 1.3 - 3.5 is reasonable. - rotation_penalty: 5.0 # Penalty to apply to in-place rotations, if minimum control set contains them - retrospective_penalty: 0.015 - lookup_table_size: 20.0 # Size of the dubin/reeds-sheep distance window to cache, in meters. - cache_obstacle_heuristic: false # Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static. - allow_reverse_expansion: false # If true, allows the robot to use the primitives to expand in the mirrored opposite direction of the current robot's orientation (to reverse). - debug_visualizations: true - smooth_path: True # If true, does a simple and quick smoothing post-processing to the path - smoother: - max_iterations: 1000 - w_smooth: 0.3 - w_data: 0.2 - tolerance: 1.0e-10 - do_refinement: true - refinement_num: 2 + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + smoother_server: ros__parameters: smoother_plugins: ["simple_smoother"] diff --git a/nav2_collision_monitor/src/polygon.cpp b/nav2_collision_monitor/src/polygon.cpp index 53480a0974f..f78f9291efe 100644 --- a/nav2_collision_monitor/src/polygon.cpp +++ b/nav2_collision_monitor/src/polygon.cpp @@ -409,6 +409,7 @@ bool Polygon::getParameters( // Do not need to proceed further, if "points" parameter is defined. // Static polygon will be used. return getPolygonFromString(poly_string, poly_); + } catch (const rclcpp::exceptions::ParameterUninitializedException &) { RCLCPP_INFO( logger_, diff --git a/nav2_collision_monitor/test/collision_detector_node_test.cpp b/nav2_collision_monitor/test/collision_detector_node_test.cpp index e36ef6e583e..1ac519111f1 100644 --- a/nav2_collision_monitor/test/collision_detector_node_test.cpp +++ b/nav2_collision_monitor/test/collision_detector_node_test.cpp @@ -162,9 +162,9 @@ class Tester : public ::testing::Test nav2_msgs::msg::CollisionDetectorState::SharedPtr state_msg_; // CollisionMonitor collision points markers - rclcpp::Subscription::SharedPtr - collision_points_marker_sub_; + rclcpp::Subscription::SharedPtr collision_points_marker_sub_; visualization_msgs::msg::MarkerArray::SharedPtr collision_points_marker_msg_; + }; // Tester Tester::Tester() diff --git a/nav2_collision_monitor/test/collision_monitor_node_test.cpp b/nav2_collision_monitor/test/collision_monitor_node_test.cpp index 757956f3f8c..242b9f72db9 100644 --- a/nav2_collision_monitor/test/collision_monitor_node_test.cpp +++ b/nav2_collision_monitor/test/collision_monitor_node_test.cpp @@ -195,8 +195,7 @@ class Tester : public ::testing::Test nav2_msgs::msg::CollisionMonitorState::SharedPtr action_state_; // CollisionMonitor collision points markers - rclcpp::Subscription::SharedPtr - collision_points_marker_sub_; + rclcpp::Subscription::SharedPtr collision_points_marker_sub_; visualization_msgs::msg::MarkerArray::SharedPtr collision_points_marker_msg_; // Service client for setting CollisionMonitor parameters diff --git a/nav2_common/nav2_common/launch/rewritten_yaml.py b/nav2_common/nav2_common/launch/rewritten_yaml.py index 11aa77227e3..c28dc88cc00 100644 --- a/nav2_common/nav2_common/launch/rewritten_yaml.py +++ b/nav2_common/nav2_common/launch/rewritten_yaml.py @@ -20,7 +20,6 @@ class DictItemReference: - def __init__(self, dictionary, key): self.dictionary = dictionary self.dictKey = key diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 69f2cfefa15..b1ddedceeb2 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -77,7 +77,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode * @brief Constructor for the wrapper * @param options Additional options to control creation of the node. */ - explicit Costmap2DROS(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + Costmap2DROS(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); /** * @brief Constructor for the wrapper, the node will @@ -399,12 +399,12 @@ class Costmap2DROS : public nav2_util::LifecycleNode double resolution_{0}; std::string robot_base_frame_; ///< The frame_id of the robot base double robot_radius_; - bool rolling_window_{false}; ///< Whether to use a rolling window version of the costmap + bool rolling_window_{false}; ///< Whether to use a rolling window version of the costmap bool track_unknown_space_{false}; double transform_tolerance_{0}; ///< The timeout before transform errors double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors - bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node + bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node // Derived parameters bool use_radius_{false}; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp index 3a2f6a77d25..99d24240d2c 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp @@ -81,7 +81,7 @@ void morphologyOperation( using ShapeBuffer3x3 = std::array; // NOLINT inline Image createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity); -} // namespace imgproc_impl +} // namespace imgproc_impl /** * @brief Perform morphological dilation diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp index 6590a4682ec..8a5fc206f16 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp @@ -40,7 +40,6 @@ #include #include -#include #include "rclcpp/rclcpp.hpp" #include "geometry_msgs/msg/polygon.hpp" diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp index 0ce4b008d98..aa0e0f13c23 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.hpp @@ -131,7 +131,7 @@ class InflationLayer : public Layer /** * @brief If clearing operations should be processed on this layer or not */ - bool isClearable() override {return false;} + virtual bool isClearable() override {return false;} /** * @brief Reset this costmap diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 2a36bab959c..501f675736e 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -289,9 +289,7 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/) // Check timeout if (now() > initial_transform_timeout_point) { RCLCPP_ERROR( - get_logger(), - "Failed to activate %s because " - "transform from %s to %s did not become available before timeout", + get_logger(), "Failed to activate %s because transform from %s to %s did not become available before timeout", get_name(), robot_base_frame_.c_str(), global_frame_.c_str()); return nav2_util::CallbackReturn::FAILURE; @@ -525,7 +523,7 @@ Costmap2DROS::mapUpdateLoop(double frequency) layered_costmap_->getBounds(&x0, &xn, &y0, &yn); costmap_publisher_->updateBounds(x0, xn, y0, yn); - for (auto & layer_pub : layer_publishers_) { + for (auto & layer_pub: layer_publishers_) { layer_pub->updateBounds(x0, xn, y0, yn); } @@ -537,7 +535,7 @@ Costmap2DROS::mapUpdateLoop(double frequency) RCLCPP_DEBUG(get_logger(), "Publish costmap at %s", name_.c_str()); costmap_publisher_->publishCostmap(); - for (auto & layer_pub : layer_publishers_) { + for (auto & layer_pub: layer_publishers_) { layer_pub->publishCostmap(); } diff --git a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp index 68a9875ef61..790466f38b0 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp @@ -162,7 +162,7 @@ TEST_F(CostmapRosTestFixture, costmap_pub_test) auto costmap_raw = future.get(); // Check first 20 cells of the 10by10 map - ASSERT_EQ(costmap_raw->data.size(), 100u); + ASSERT_TRUE(costmap_raw->data.size() == 100); unsigned int i = 0; for (; i < 7; ++i) { EXPECT_EQ(costmap_raw->data.at(i), nav2_costmap_2d::FREE_SPACE); diff --git a/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp b/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp index d674ee76691..65fa120cd60 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp @@ -1,17 +1,3 @@ -// Copyright (c) 2020 Samsung Research -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - #include #include "rclcpp/rclcpp.hpp" @@ -133,7 +119,7 @@ TEST_F(TestCostmapSubscriberShould, handleFullCostmapMsgs) node, costmapToSend.get(), "", topicName, always_send_full_costmap); costmapPublisher->on_activate(); - for (const auto & mapChange : mapChanges) { + for (const auto & mapChange :mapChanges) { for (const auto & observation : mapChange.observations) { costmapToSend->setCost(observation.x, observation.y, observation.cost); } @@ -167,7 +153,7 @@ TEST_F(TestCostmapSubscriberShould, handleCostmapUpdateMsgs) node, costmapToSend.get(), "", topicName, always_send_full_costmap); costmapPublisher->on_activate(); - for (const auto & mapChange : mapChanges) { + for (const auto & mapChange :mapChanges) { for (const auto & observation : mapChange.observations) { costmapToSend->setCost(observation.x, observation.y, observation.cost); } diff --git a/nav2_costmap_2d/test/regression/order_layer.hpp b/nav2_costmap_2d/test/regression/order_layer.hpp index 01955f0ba9c..35bb2aeabb7 100644 --- a/nav2_costmap_2d/test/regression/order_layer.hpp +++ b/nav2_costmap_2d/test/regression/order_layer.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef REGRESSION__ORDER_LAYER_HPP_ -#define REGRESSION__ORDER_LAYER_HPP_ +#ifndef NAV2_COSTMAP_2D__ORDER_LAYER_HPP_ +#define NAV2_COSTMAP_2D__ORDER_LAYER_HPP_ #include "nav2_costmap_2d/layer.hpp" @@ -43,4 +43,4 @@ class OrderLayer : public nav2_costmap_2d::Layer } // namespace nav2_costmap_2d -#endif // REGRESSION__ORDER_LAYER_HPP_ +#endif // NAV2_COSTMAP_2D__ORDER_LAYER_HPP_ diff --git a/nav2_costmap_2d/test/regression/plugin_api_order.cpp b/nav2_costmap_2d/test/regression/plugin_api_order.cpp index f7a00e90d24..c7baf34453a 100644 --- a/nav2_costmap_2d/test/regression/plugin_api_order.cpp +++ b/nav2_costmap_2d/test/regression/plugin_api_order.cpp @@ -16,8 +16,8 @@ #include #include -#include "gtest/gtest.h" -#include "nav2_costmap_2d/costmap_2d_ros.hpp" +#include +#include TEST(CostmapPluginsTester, checkPluginAPIOrder) { diff --git a/nav2_costmap_2d/test/unit/denoise_layer_test.cpp b/nav2_costmap_2d/test/unit/denoise_layer_test.cpp index 558fb26361b..37c277f900d 100644 --- a/nav2_costmap_2d/test/unit/denoise_layer_test.cpp +++ b/nav2_costmap_2d/test/unit/denoise_layer_test.cpp @@ -102,9 +102,9 @@ class DenoiseLayerTester : public ::testing::Test nav2_costmap_2d::DenoiseLayer denoise_; }; -} // namespace nav2_costmap_2d +} -using namespace nav2_costmap_2d; // NOLINT +using namespace nav2_costmap_2d; TEST_F(DenoiseLayerTester, removeSinglePixels4way) { const auto in = imageFromString( diff --git a/nav2_costmap_2d/test/unit/image_processing_test.cpp b/nav2_costmap_2d/test/unit/image_processing_test.cpp index f56ca581498..cc177d699a2 100644 --- a/nav2_costmap_2d/test/unit/image_processing_test.cpp +++ b/nav2_costmap_2d/test/unit/image_processing_test.cpp @@ -18,8 +18,8 @@ #include "nav2_costmap_2d/denoise/image_processing.hpp" #include "image_tests_helper.hpp" -using namespace nav2_costmap_2d; // NOLINT -using namespace imgproc_impl; // NOLINT +using namespace nav2_costmap_2d; +using namespace imgproc_impl; struct ImageProcTester : public ::testing::Test { diff --git a/nav2_costmap_2d/test/unit/image_test.cpp b/nav2_costmap_2d/test/unit/image_test.cpp index 7ab796e155c..83912d06228 100644 --- a/nav2_costmap_2d/test/unit/image_test.cpp +++ b/nav2_costmap_2d/test/unit/image_test.cpp @@ -17,7 +17,7 @@ #include "nav2_costmap_2d/denoise/image.hpp" #include "image_tests_helper.hpp" -using namespace nav2_costmap_2d; // NOLINT +using namespace nav2_costmap_2d; struct ImageTester : public ::testing::Test { diff --git a/nav2_costmap_2d/test/unit/image_tests_helper.hpp b/nav2_costmap_2d/test/unit/image_tests_helper.hpp index 2ffe8196baa..3eee735f7ea 100644 --- a/nav2_costmap_2d/test/unit/image_tests_helper.hpp +++ b/nav2_costmap_2d/test/unit/image_tests_helper.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UNIT__IMAGE_TESTS_HELPER_HPP_ -#define UNIT__IMAGE_TESTS_HELPER_HPP_ +#ifndef NAV2_COSTMAP_2D__IMAGE_TESTS_HELPER_HPP_ +#define NAV2_COSTMAP_2D__IMAGE_TESTS_HELPER_HPP_ #include "nav2_costmap_2d/denoise/image.hpp" #include @@ -121,4 +121,4 @@ std::ostream & operator<<(std::ostream & out, const Image & image) } // namespace nav2_costmap_2d -#endif // UNIT__IMAGE_TESTS_HELPER_HPP_ +#endif // NAV2_COSTMAP_2D__IMAGE_TESTS_HELPER_HPP_ diff --git a/nav2_costmap_2d/test/unit/lifecycle_test.cpp b/nav2_costmap_2d/test/unit/lifecycle_test.cpp index e54264ebeae..a8ab817df3e 100644 --- a/nav2_costmap_2d/test/unit/lifecycle_test.cpp +++ b/nav2_costmap_2d/test/unit/lifecycle_test.cpp @@ -1,5 +1,3 @@ -// Copyright (c) 2020 Samsung Research -// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -10,7 +8,7 @@ // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and -// limitations under the License. Reserved. +// limitations under the License. #include diff --git a/nav2_simple_commander/nav2_simple_commander/costmap_2d.py b/nav2_simple_commander/nav2_simple_commander/costmap_2d.py index 2ddc9cb00fc..1ae7e808b6a 100644 --- a/nav2_simple_commander/nav2_simple_commander/costmap_2d.py +++ b/nav2_simple_commander/nav2_simple_commander/costmap_2d.py @@ -34,6 +34,14 @@ class PyCostmap2D: """ def __init__(self, occupancy_map): + """ + Initialize costmap2D. + + Args: + ---- + occupancy_map (OccupancyGrid): 2D OccupancyGrid Map + + """ self.size_x = occupancy_map.info.width self.size_y = occupancy_map.info.height self.resolution = occupancy_map.info.resolution diff --git a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py index 5f9e355a2fe..17d2f130e84 100644 --- a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py +++ b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py @@ -51,7 +51,6 @@ class TaskResult(Enum): class BasicNavigator(Node): - def __init__(self, node_name='basic_navigator', namespace=''): super().__init__(node_name=node_name, namespace=namespace) self.initial_pose = PoseStamped() diff --git a/nav2_simple_commander/test/test_footprint_collision_checker.py b/nav2_simple_commander/test/test_footprint_collision_checker.py index 8ffc4b653b9..070a7bc6e4b 100644 --- a/nav2_simple_commander/test/test_footprint_collision_checker.py +++ b/nav2_simple_commander/test/test_footprint_collision_checker.py @@ -23,7 +23,6 @@ class TestFootprintCollisionChecker(unittest.TestCase): - def test_no_costmap(self): # Test if a type error raised when costmap is not specified yet fcc_ = FootprintCollisionChecker() diff --git a/nav2_simple_commander/test/test_line_iterator.py b/nav2_simple_commander/test/test_line_iterator.py index 8bfb91588b1..1360c183e7d 100644 --- a/nav2_simple_commander/test/test_line_iterator.py +++ b/nav2_simple_commander/test/test_line_iterator.py @@ -19,7 +19,6 @@ class TestLineIterator(unittest.TestCase): - def test_type_error(self): # Test if a type error raised when passing invalid arguements types self.assertRaises(TypeError, LineIterator, 0, 0, '10', 10, '1') diff --git a/nav2_system_tests/src/costmap_filters/tester_node.py b/nav2_system_tests/src/costmap_filters/tester_node.py index 3b3f723095b..da8ab82a20b 100755 --- a/nav2_system_tests/src/costmap_filters/tester_node.py +++ b/nav2_system_tests/src/costmap_filters/tester_node.py @@ -47,7 +47,6 @@ class TestType(Enum): class FilterMask: - def __init__(self, filter_mask: OccupancyGrid): self.filter_mask = filter_mask diff --git a/nav2_system_tests/src/gps_navigation/tester.py b/nav2_system_tests/src/gps_navigation/tester.py index b9fb4725efb..5e765981ab2 100755 --- a/nav2_system_tests/src/gps_navigation/tester.py +++ b/nav2_system_tests/src/gps_navigation/tester.py @@ -30,7 +30,6 @@ class GpsWaypointFollowerTest(Node): - def __init__(self): super().__init__(node_name='nav2_gps_waypoint_tester', namespace='') self.waypoints = None diff --git a/nav2_system_tests/src/system/nav_through_poses_tester_node.py b/nav2_system_tests/src/system/nav_through_poses_tester_node.py index 2bcea319313..5e587ad8fa9 100755 --- a/nav2_system_tests/src/system/nav_through_poses_tester_node.py +++ b/nav2_system_tests/src/system/nav_through_poses_tester_node.py @@ -37,7 +37,6 @@ class NavTester(Node): - def __init__(self, initial_pose: Pose, goal_pose: Pose, namespace: str = ''): super().__init__(node_name='nav2_tester', namespace=namespace) self.initial_pose_pub = self.create_publisher( diff --git a/nav2_system_tests/src/system/nav_to_pose_tester_node.py b/nav2_system_tests/src/system/nav_to_pose_tester_node.py index 8fd1bc60342..cbb2ac20e6b 100755 --- a/nav2_system_tests/src/system/nav_to_pose_tester_node.py +++ b/nav2_system_tests/src/system/nav_to_pose_tester_node.py @@ -38,7 +38,6 @@ class NavTester(Node): - def __init__(self, initial_pose: Pose, goal_pose: Pose, namespace: str = ''): super().__init__(node_name='nav2_tester', namespace=namespace) self.initial_pose_pub = self.create_publisher( diff --git a/nav2_system_tests/src/system_failure/tester_node.py b/nav2_system_tests/src/system_failure/tester_node.py index 9cea2f6118d..765535c6e5b 100755 --- a/nav2_system_tests/src/system_failure/tester_node.py +++ b/nav2_system_tests/src/system_failure/tester_node.py @@ -37,7 +37,6 @@ class NavTester(Node): - def __init__(self, initial_pose: Pose, goal_pose: Pose, namespace: str = ''): super().__init__(node_name='nav2_tester', namespace=namespace) self.initial_pose_pub = self.create_publisher( diff --git a/nav2_system_tests/src/waypoint_follower/tester.py b/nav2_system_tests/src/waypoint_follower/tester.py index 2a3ef3df537..7eb46457065 100755 --- a/nav2_system_tests/src/waypoint_follower/tester.py +++ b/nav2_system_tests/src/waypoint_follower/tester.py @@ -31,7 +31,6 @@ class WaypointFollowerTest(Node): - def __init__(self): super().__init__(node_name='nav2_waypoint_tester', namespace='') self.waypoints = None