diff --git a/.cspell.json b/.cspell.json index 2d024a5ca589d..f338e72d194e3 100644 --- a/.cspell.json +++ b/.cspell.json @@ -4,5 +4,5 @@ "planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/**" ], "ignoreRegExpList": [], - "words": ["dltype", "tvmgen", "fromarray", "soblin"] + "words": ["dltype", "tvmgen", "fromarray", "soblin", "brkay54"] } diff --git a/common/autoware_trajectory/include/autoware/trajectory/point.hpp b/common/autoware_trajectory/include/autoware/trajectory/point.hpp index e9d985a85194a..3e763e2428f1b 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/point.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/point.hpp @@ -122,7 +122,7 @@ class Trajectory using trajectory::detail::to_point; Eigen::Vector2d point(to_point(p).x, to_point(p).y); std::vector distances_from_segments; - std::vector lengthes_from_start_points; + std::vector lengths_from_start_points; auto axis = detail::crop_bases(bases_, start_, end_); @@ -149,7 +149,7 @@ class Trajectory } if (constraints(length_from_start_point)) { distances_from_segments.push_back(distance_from_segment); - lengthes_from_start_points.push_back(length_from_start_point); + lengths_from_start_points.push_back(length_from_start_point); } } if (distances_from_segments.empty()) { @@ -158,7 +158,7 @@ class Trajectory auto min_it = std::min_element(distances_from_segments.begin(), distances_from_segments.end()); - return lengthes_from_start_points[std::distance(distances_from_segments.begin(), min_it)] - + return lengths_from_start_points[std::distance(distances_from_segments.begin(), min_it)] - start_; } diff --git a/common/autoware_trajectory/test/test_trajectory_container.cpp b/common/autoware_trajectory/test/test_trajectory_container.cpp index b3e4c16a09999..028d36d98a954 100644 --- a/common/autoware_trajectory/test/test_trajectory_container.cpp +++ b/common/autoware_trajectory/test/test_trajectory_container.cpp @@ -106,9 +106,9 @@ TEST_F(TrajectoryTest, direction) TEST_F(TrajectoryTest, curvature) { - double curv = trajectory->curvature(0.0); - EXPECT_LT(-1.0, curv); - EXPECT_LT(curv, 1.0); + double curvature_val = trajectory->curvature(0.0); + EXPECT_LT(-1.0, curvature_val); + EXPECT_LT(curvature_val, 1.0); } TEST_F(TrajectoryTest, restore) diff --git a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml index e458edaf6c471..0de08076b8c06 100644 --- a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml +++ b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml @@ -258,7 +258,7 @@ - + @@ -268,7 +268,7 @@ - + @@ -286,7 +286,7 @@ - + diff --git a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp index 072d3b661b8b3..4cb8c0083a148 100644 --- a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp +++ b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp @@ -140,7 +140,7 @@ void TrtShapeEstimator::preprocess(const DetectedObjectsWithFeature & input) } int iter_count = static_cast(input_pc_size) / point_size_of_cloud; - int remainer_count = static_cast(input_pc_size) % point_size_of_cloud; + int remaining_points_count = static_cast(input_pc_size) % point_size_of_cloud; for (int j = 1; j < iter_count; j++) { for (int k = 0; k < point_size_of_cloud; k++) { @@ -155,7 +155,7 @@ void TrtShapeEstimator::preprocess(const DetectedObjectsWithFeature & input) } } - for (int j = 0; j < remainer_count; j++) { + for (int j = 0; j < remaining_points_count; j++) { input_pc_h_[i * input_chan * input_pc_size + 0 + iter_count * point_size_of_cloud + j] = input_pc_h_[i * input_chan * input_pc_size + j]; diff --git a/planning/autoware_costmap_generator/src/costmap_generator.cpp b/planning/autoware_costmap_generator/src/costmap_generator.cpp index d791836fa0a08..4092acae9b51c 100644 --- a/planning/autoware_costmap_generator/src/costmap_generator.cpp +++ b/planning/autoware_costmap_generator/src/costmap_generator.cpp @@ -324,8 +324,8 @@ bool CostmapGenerator::isActive() if (param_->activate_by_scenario) { if (!scenario_) return false; const auto & s = scenario_->activating_scenarios; - return std::any_of(s.begin(), s.end(), [](const auto scen) { - return scen == tier4_planning_msgs::msg::Scenario::PARKING; + return std::any_of(s.begin(), s.end(), [](const auto scenario) { + return scenario == tier4_planning_msgs::msg::Scenario::PARKING; }); } diff --git a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp index a2ed4c3e7e0fc..a46b8bba58920 100644 --- a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp +++ b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp @@ -231,9 +231,9 @@ std::unique_ptr configure_astar(bool use_multi) obstacle_distance_weight, goal_lat_distance_weight}; - auto clock_shrd_ptr = std::make_shared(RCL_ROS_TIME); - auto algo = std::make_unique( - planner_common_param, vehicle_shape, astar_param, clock_shrd_ptr); + auto clock_ptr = std::make_shared(RCL_ROS_TIME); + auto algo = + std::make_unique(planner_common_param, vehicle_shape, astar_param, clock_ptr); return algo; } @@ -247,9 +247,9 @@ std::unique_ptr configure_rrtstar(bool informed, const double max_planning_time = 200; const auto rrtstar_param = fpa::RRTStarParam{update, informed, max_planning_time, mu, margin}; - auto clock_shrd_ptr = std::make_shared(RCL_ROS_TIME); - auto algo = std::make_unique( - planner_common_param, vehicle_shape, rrtstar_param, clock_shrd_ptr); + auto clock_ptr = std::make_shared(RCL_ROS_TIME); + auto algo = + std::make_unique(planner_common_param, vehicle_shape, rrtstar_param, clock_ptr); return algo; } diff --git a/planning/autoware_path_smoother/src/elastic_band.cpp b/planning/autoware_path_smoother/src/elastic_band.cpp index 0bec4e46c8b42..0bdf83c9d3b7c 100644 --- a/planning/autoware_path_smoother/src/elastic_band.cpp +++ b/planning/autoware_path_smoother/src/elastic_band.cpp @@ -34,9 +34,9 @@ Eigen::SparseMatrix makePMatrix(const int num_points) { std::vector> triplet_vec; const auto assign_value_to_triplet_vec = - [&](const double row, const double colum, const double value) { - triplet_vec.push_back(Eigen::Triplet(row, colum, value)); - triplet_vec.push_back(Eigen::Triplet(row + num_points, colum + num_points, value)); + [&](const double row, const double column, const double value) { + triplet_vec.push_back(Eigen::Triplet(row, column, value)); + triplet_vec.push_back(Eigen::Triplet(row + num_points, column + num_points, value)); }; for (int r = 0; r < num_points; ++r) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index b694c8aaa2e3e..402f3c1d22cc7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -938,7 +938,7 @@ std::vector IntersectionModule::generateDetectionLan if (detection_lanelets.empty()) { // NOTE(soblin): due to the above filtering detection_lanelets may be empty or do not contain // conflicting_detection_lanelets - // OK to return empty detction_divsions + // OK to return empty detection_divisions return detection_divisions; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp index d9ef145eb5ce9..6ee31c3712b47 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp @@ -89,7 +89,7 @@ TEST(TestUtil, retrievePathsBackward) } /* - TOOD(Mamoru Sobue): instantiating intersection_module and PlannerData is a messy + TODO(Mamoru Sobue): instantiating intersection_module and PlannerData is a messy class TestWithMap : public ::testing::Test { protected: diff --git a/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp index 6c5f43e929766..caf50473cde18 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp @@ -103,9 +103,9 @@ TEST(splineTransform, benchFrenet) EXPECT_NEAR(frenet_naive.d, frenet_lut.d, precision); } std::cout << "size = " << size << std::endl; - std::cout << "\tnaive: " << std::chrono::duration_cast(naive).count() - << "ms\n"; - std::cout << "\tlut : " << std::chrono::duration_cast(lut).count() + std::cout << "\t naive: " + << std::chrono::duration_cast(naive).count() << "ms\n"; + std::cout << "\t lut : " << std::chrono::duration_cast(lut).count() << "ms\n"; } } diff --git a/simulator/autoware_carla_interface/README.md b/simulator/autoware_carla_interface/README.md index a44cb4708b5c3..2513364178693 100644 --- a/simulator/autoware_carla_interface/README.md +++ b/simulator/autoware_carla_interface/README.md @@ -136,14 +136,14 @@ The maps provided by the Carla Simulator ([Carla Lanelet2 Maps](https://bitbucke - Options to Modify the Map - A. Create a New Map from Scratch - - Use the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/) to create a new map. + - Use the [TIER IV Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/) to create a new map. - B. Modify the Existing Carla Lanelet2 Maps - Adjust the longitude and latitude of the [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) to align with the PCD (origin). - Use this [tool](https://github.com/mraditya01/offset_lanelet2/tree/main) to modify the coordinates. - - Snap Lanelet with PCD and add the traffic lights using the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/). + - Snap Lanelet with PCD and add the traffic lights using the [TIER IV Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/). -- When using the Tier4 Vector Map Builder, you must convert the PCD format from `binary_compressed` to `ascii`. You can use `pcl_tools` for this conversion. +- When using the TIER IV Vector Map Builder, you must convert the PCD format from `binary_compressed` to `ascii`. You can use `pcl_tools` for this conversion. - For reference, an example of Town01 with added traffic lights at one intersection can be downloaded [here](https://drive.google.com/drive/folders/1QFU0p3C8NW71sT5wwdnCKXoZFQJzXfTG?usp=sharing). ## Tips