Skip to content

Commit

Permalink
refactor: fix spell-check (autowarefoundation#4289)
Browse files Browse the repository at this point in the history
* refactor: fix spell-check

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* fix spell-check

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* fix typo

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* Fix obvious typo, shortened words

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* Fix obvious typo, shortened words, in common directory

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* add cspell ignore

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* Update perception/tensorrt_classifier/CMakeLists.txt

Co-authored-by: Yusuke Muramatsu <yukke42@users.noreply.github.com>

---------

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>
Co-authored-by: Yusuke Muramatsu <yukke42@users.noreply.github.com>
  • Loading branch information
miursh and yukke42 authored Jul 26, 2023
1 parent d20adaa commit 13b96ad
Show file tree
Hide file tree
Showing 37 changed files with 277 additions and 263 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ class PrimeSynchronizer
* @tparam Idx
* @param argv
* @return true All messages are not nullptr
* @return false At least one message in the tuplc is nullptr
* @return false At least one message in the topic is nullptr
*/
template <std::size_t Idx = 0>
bool isArgvValid(
Expand Down
1 change: 1 addition & 0 deletions common/tensorrt_common/src/tensorrt_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -416,6 +416,7 @@ bool TrtCommon::buildEngineFromOnnx(
first = false;
}
if (last) {
// cspell: ignore preds
if (
contain(name, "reg_preds") || contain(name, "cls_preds") ||
contain(name, "obj_preds")) {
Expand Down
1 change: 1 addition & 0 deletions common/tvm_utility/tvm_utility-extras.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY)
set(PREPROCESSING "")

# Prioritize user-provided models.
# cspell: ignore COPYONLY
if(IS_DIRECTORY "${DATA_PATH}/user/${MODEL_NAME}")
message(STATUS "Using user-provided model from ${DATA_PATH}/user/${MODEL_NAME}")
file(REMOVE_RECURSE "${DATA_PATH}/models/${MODEL_NAME}/")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,13 +109,13 @@ TEST_F(RayGroundFilterComponentTestSuite, TestCase1)
// check out_cloud
int effect_num = 0;
int total_num = 0;
const float min_noground_point_z = 0.1; // z in base_frame
const float min_no_ground_point_z = 0.1; // z in base_frame
for (sensor_msgs::PointCloud2ConstIterator<float> iter_x(out_cloud, "x"), iter_y(out_cloud, "y"),
iter_z(out_cloud, "z");
iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
const float z = *iter_z;
total_num += 1;
if (z > min_noground_point_z) {
if (z > min_no_ground_point_z) {
effect_num += 1;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class ScanGroundFilterTest : public ::testing::Test
output_pointcloud_pub_ = rclcpp::create_publisher<sensor_msgs::msg::PointCloud2>(
dummy_node_, "/test_scan_ground_filter/output_cloud", 1);

// no real uages,ScanGroundFilterComponent cosntruct need these params
// no real usages, ScanGroundFilterComponent constructor need these params
rclcpp::NodeOptions options;
std::vector<rclcpp::Parameter> parameters;
parameters.emplace_back(rclcpp::Parameter("wheel_radius", 0.39));
Expand Down Expand Up @@ -173,13 +173,13 @@ TEST_F(ScanGroundFilterTest, TestCase1)
// check out_cloud
int effect_num = 0;
int total_num = 0;
const float min_noground_point_z = 0.1;
const float min_no_ground_point_z = 0.1;
for (sensor_msgs::PointCloud2ConstIterator<float> iter_x(out_cloud, "x"), iter_y(out_cloud, "y"),
iter_z(out_cloud, "z");
iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
const float z = *iter_z;
total_num += 1;
if (z > min_noground_point_z) {
if (z > min_no_ground_point_z) {
effect_num += 1;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -146,28 +146,28 @@ void generateDetectedBoxes3D(
// construct boxes3d failed
std::cerr << "lidar_centerpoint_tvm: construct boxes3d failed" << std::endl;
}
std::vector<Box3D> det_boxes3d_nonms(num_det_boxes3d);
std::vector<Box3D> det_boxes3d_no_nms(num_det_boxes3d);
std::copy_if(
boxes3d.begin(), boxes3d.end(), det_boxes3d_nonms.begin(),
boxes3d.begin(), boxes3d.end(), det_boxes3d_no_nms.begin(),
is_score_greater(config.score_threshold_));

// sort by score
std::sort(det_boxes3d_nonms.begin(), det_boxes3d_nonms.end(), score_greater());
std::sort(det_boxes3d_no_nms.begin(), det_boxes3d_no_nms.end(), score_greater());

// suppress by NMS
std::vector<bool> final_keep_mask(num_det_boxes3d);
const auto num_final_det_boxes3d =
circleNMS(det_boxes3d_nonms, config.circle_nms_dist_threshold_, final_keep_mask);
circleNMS(det_boxes3d_no_nms, config.circle_nms_dist_threshold_, final_keep_mask);

det_boxes3d.resize(num_final_det_boxes3d);
std::size_t box_id = 0;
for (std::size_t idx = 0; idx < final_keep_mask.size(); idx++) {
if (final_keep_mask[idx]) {
det_boxes3d[box_id] = det_boxes3d_nonms[idx];
det_boxes3d[box_id] = det_boxes3d_no_nms[idx];
box_id++;
}
}
// std::copy_if(det_boxes3d_nonms.begin(), det_boxes3d_nonms.end(), final_keep_mask.begin(),
// std::copy_if(det_boxes3d_no_nms.begin(), det_boxes3d_no_nms.end(), final_keep_mask.begin(),
// det_boxes3d.begin(), is_kept());
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ std::size_t VoxelGenerator::pointsToVoxels(
auto pc_msg = pc_cache_iter->pointcloud_msg;
auto affine_past2current =
pd_ptr_->getAffineWorldToCurrent() * pc_cache_iter->affine_past2world;
float timelag = static_cast<float>(
float time_lag = static_cast<float>(
pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_msg.header.stamp).seconds());

for (sensor_msgs::PointCloud2ConstIterator<float> x_iter(pc_msg, "x"), y_iter(pc_msg, "y"),
Expand All @@ -87,7 +87,7 @@ std::size_t VoxelGenerator::pointsToVoxels(
point[0] = point_current.x();
point[1] = point_current.y();
point[2] = point_current.z();
point[3] = timelag;
point[3] = time_lag;

out_of_range = false;
for (std::size_t di = 0; di < config_.point_dim_size_; di++) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -550,7 +550,7 @@ ObjectClassification::_label_type changeLabelForPrediction(
label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE) {
// if object is within road lanelet and satisfies yaw constraints
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
const float high_speed_threshold = 25.0 / 18.0 * 5.0; // High speed bycicle 25 km/h
const float high_speed_threshold = 25.0 / 18.0 * 5.0; // High speed bicycle 25 km/h
const bool high_speed_object =
object.kinematics.twist_with_covariance.twist.linear.x > high_speed_threshold;

Expand Down
Loading

0 comments on commit 13b96ad

Please sign in to comment.