Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor: correct spelling #9528

Merged
merged 13 commits into from
Dec 2, 2024
2 changes: 1 addition & 1 deletion .cspell.json
Original file line number Diff line number Diff line change
Expand Up @@ -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"]
}
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ class Trajectory<geometry_msgs::msg::Point>
using trajectory::detail::to_point;
Eigen::Vector2d point(to_point(p).x, to_point(p).y);
std::vector<double> distances_from_segments;
std::vector<double> lengthes_from_start_points;
std::vector<double> lengths_from_start_points;

auto axis = detail::crop_bases(bases_, start_, end_);

Expand All @@ -149,7 +149,7 @@ class Trajectory<geometry_msgs::msg::Point>
}
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()) {
Expand All @@ -158,7 +158,7 @@ class Trajectory<geometry_msgs::msg::Point>

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_;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@
<parameters delimiter="0" time_axis=""/>
</plugin>
<plugin ID="DataLoad MCAP"/>
<plugin ID="DataLoad ROS2 bags">
<plugin ID="DataLoad ROS 2 bags">
<use_header_stamp value="false"/>
<discard_large_arrays value="true"/>
<max_array_size value="100"/>
Expand All @@ -268,7 +268,7 @@
</plugin>
<plugin ID="DataLoad ULog"/>
<plugin ID="MQTT Subscriber (Mosquitto)"/>
<plugin ID="ROS2 Topic Subscriber">
<plugin ID="ROS 2 Topic Subscriber">
<use_header_stamp value="false"/>
<discard_large_arrays value="false"/>
<max_array_size value="100"/>
Expand All @@ -286,7 +286,7 @@
<scripts/>
</plugin>
<plugin ID="CSV Exporter"/>
<plugin ID="ROS2 Topic Re-Publisher"/>
<plugin ID="ROS 2 Topic Re-Publisher"/>
</Plugins>
<!-- - - - - - - - - - - - - - - -->
<previouslyLoaded_Datafiles/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@
}

int iter_count = static_cast<int>(input_pc_size) / point_size_of_cloud;
int remainer_count = static_cast<int>(input_pc_size) % point_size_of_cloud;
int remaining_points_count = static_cast<int>(input_pc_size) % point_size_of_cloud;

Check warning on line 143 in perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp#L143

Added line #L143 was not covered by tests

for (int j = 1; j < iter_count; j++) {
for (int k = 0; k < point_size_of_cloud; k++) {
Expand All @@ -155,7 +155,7 @@
}
}

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];

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
});
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -231,9 +231,9 @@ std::unique_ptr<fpa::AbstractPlanningAlgorithm> configure_astar(bool use_multi)
obstacle_distance_weight,
goal_lat_distance_weight};

auto clock_shrd_ptr = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
auto algo = std::make_unique<fpa::AstarSearch>(
planner_common_param, vehicle_shape, astar_param, clock_shrd_ptr);
auto clock_ptr = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
auto algo =
std::make_unique<fpa::AstarSearch>(planner_common_param, vehicle_shape, astar_param, clock_ptr);
return algo;
}

Expand All @@ -247,9 +247,9 @@ std::unique_ptr<fpa::AbstractPlanningAlgorithm> 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<rclcpp::Clock>(RCL_ROS_TIME);
auto algo = std::make_unique<fpa::RRTStar>(
planner_common_param, vehicle_shape, rrtstar_param, clock_shrd_ptr);
auto clock_ptr = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
auto algo =
std::make_unique<fpa::RRTStar>(planner_common_param, vehicle_shape, rrtstar_param, clock_ptr);
return algo;
}

Expand Down
6 changes: 3 additions & 3 deletions planning/autoware_path_smoother/src/elastic_band.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@ Eigen::SparseMatrix<double> makePMatrix(const int num_points)
{
std::vector<Eigen::Triplet<double>> triplet_vec;
const auto assign_value_to_triplet_vec =
[&](const double row, const double colum, const double value) {
triplet_vec.push_back(Eigen::Triplet<double>(row, colum, value));
triplet_vec.push_back(Eigen::Triplet<double>(row + num_points, colum + num_points, value));
[&](const double row, const double column, const double value) {
triplet_vec.push_back(Eigen::Triplet<double>(row, column, value));
triplet_vec.push_back(Eigen::Triplet<double>(row + num_points, column + num_points, value));
};

for (int r = 0; r < num_points; ++r) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -938,7 +938,7 @@ std::vector<lanelet::ConstLineString3d> 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;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::chrono::milliseconds>(naive).count()
<< "ms\n";
std::cout << "\tlut : " << std::chrono::duration_cast<std::chrono::milliseconds>(lut).count()
std::cout << "\t naive: "
<< std::chrono::duration_cast<std::chrono::milliseconds>(naive).count() << "ms\n";
std::cout << "\t lut : " << std::chrono::duration_cast<std::chrono::milliseconds>(lut).count()
<< "ms\n";
}
}
6 changes: 3 additions & 3 deletions simulator/autoware_carla_interface/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Loading