Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Aug 7, 2023
1 parent 6ba3ebb commit 2759e85
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@
#include <lidar_centerpoint/preprocess/pointcloud_densification.hpp>
#include <lidar_centerpoint/ros_utils.hpp>
#include <lidar_centerpoint/utils.hpp>
#include <pcl_ros/transforms.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/math/constants.hpp>
#include <pcl_ros/transforms.hpp>

#include <omp.h>

Expand Down Expand Up @@ -115,9 +115,12 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
const std::string head_engine_path = this->declare_parameter("head_engine_path", "");

class_names_ = this->declare_parameter<std::vector<std::string>>("class_names");
const auto paint_class_names = this->declare_parameter<std::vector<std::string>>("paint_class_names");
const auto paint_class_names =
this->declare_parameter<std::vector<std::string>>("paint_class_names");
std::vector<std::string> classes_{"CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"};
if (std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") != paint_class_names.end()) {
if (
std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") !=
paint_class_names.end()) {
isClassTable_["CAR"] = std::bind(&isCar, std::placeholders::_1);
} else {
isClassTable_["CAR"] = std::bind(&isVehicle, std::placeholders::_1);
Expand Down Expand Up @@ -321,7 +324,7 @@ dc | dc dc dc dc ||zc|
float p_y = *reinterpret_cast<const float *>(&data[stride + y_offset]);
float p_z = *reinterpret_cast<const float *>(&data[stride + z_offset]);
point_lidar << p_x, p_y, p_z;
point_camera = lidar2cam_affine * point_lidar;
point_camera = lidar2cam_affine * point_lidar;
p_x = point_camera.x();
p_y = point_camera.y();
p_z = point_camera.z();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ const std::size_t MAX_POINT_IN_VOXEL_SIZE = 32; // the same as max_point_in_vox
const std::size_t WARPS_PER_BLOCK = 4;
const std::size_t ENCODER_IN_FEATURE_SIZE = 12; // same as encoder_in_feature_size_ in config.hpp
const int POINT_FEATURE_SIZE = 7;
// const std::size_t ENCODER_IN_FEATURE_SIZE = 14; // same as encoder_in_feature_size_ in config.hpp
// const int POINT_FEATURE_SIZE = 9;
// const std::size_t ENCODER_IN_FEATURE_SIZE = 14; // same as encoder_in_feature_size_ in
// config.hpp const int POINT_FEATURE_SIZE = 9;

// cspell: ignore divup
std::size_t divup(const std::size_t a, const std::size_t b)
Expand Down

0 comments on commit 2759e85

Please sign in to comment.