static code analysis (#20)

This commit is contained in:
koide3 2024-04-08 17:58:50 +09:00 committed by GitHub
parent 47d90853e2
commit ff8269ec09
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
19 changed files with 29 additions and 25 deletions

View File

@ -40,7 +40,7 @@ public:
/// @brief Constructor
/// @param leaf_size Voxel size
IncrementalVoxelMap(double leaf_size) : inv_leaf_size(1.0 / leaf_size), lru_horizon(100), lru_clear_cycle(10), lru_counter(0) {}
explicit IncrementalVoxelMap(double leaf_size) : inv_leaf_size(1.0 / leaf_size), lru_horizon(100), lru_clear_cycle(10), lru_counter(0) {}
/// @brief Number of points in the voxelmap
size_t size() const { return flat_voxels.size(); }

View File

@ -23,12 +23,14 @@ public:
/// @brief Constructor
/// @param points Input points
UnsafeKdTreeGeneric(const PointCloud& points) : points(points), index(3, *this, nanoflann::KDTreeSingleIndexAdaptorParams(10)) { index.buildIndex(); }
explicit UnsafeKdTreeGeneric(const PointCloud& points) : points(points), index(3, *this, nanoflann::KDTreeSingleIndexAdaptorParams(10)) { index.buildIndex(); }
/// @brief Constructor
/// @param points Input points
/// @params num_threads Number of threads used for building the index (This argument is only valid for OMP implementation)
UnsafeKdTreeGeneric(const PointCloud& points, int num_threads) : points(points), index(3, *this, nanoflann::KDTreeSingleIndexAdaptorParams(10)) { index.buildIndex(num_threads); }
explicit UnsafeKdTreeGeneric(const PointCloud& points, int num_threads) : points(points), index(3, *this, nanoflann::KDTreeSingleIndexAdaptorParams(10)) {
index.buildIndex(num_threads);
}
~UnsafeKdTreeGeneric() {}
@ -58,11 +60,11 @@ public:
/// @brief Constructor
/// @param points Input points
KdTreeGeneric(const std::shared_ptr<const PointCloud>& points) : points(points), tree(*points) {}
explicit KdTreeGeneric(const std::shared_ptr<const PointCloud>& points) : points(points), tree(*points) {}
/// @brief Constructor
/// @param points Input points
KdTreeGeneric(const std::shared_ptr<const PointCloud>& points, int num_threads) : points(points), tree(*points, num_threads) {}
explicit KdTreeGeneric(const std::shared_ptr<const PointCloud>& points, int num_threads) : points(points), tree(*points, num_threads) {}
~KdTreeGeneric() {}

View File

@ -95,7 +95,7 @@ std::string summarize(const Container& container, const Transform& transform) {
struct KittiDataset {
public:
KittiDataset(const std::string& dataset_path, size_t max_num_data = std::numeric_limits<size_t>::max()) {
explicit KittiDataset(const std::string& dataset_path, size_t max_num_data = 1000000) {
std::vector<std::string> filenames;
for (auto path : std::filesystem::directory_iterator(dataset_path)) {
if (path.path().extension() != ".bin") {

View File

@ -41,15 +41,15 @@ struct PointToPlaneICPFactor {
const auto& target_normal = traits::normal(target, target_index);
const Eigen::Vector4d residual = traits::point(target, target_index) - transed_source_pt;
const Eigen::Vector4d error = target_normal.array() * residual.array();
const Eigen::Vector4d err = target_normal.array() * residual.array();
Eigen::Matrix<double, 4, 6> J = Eigen::Matrix<double, 4, 6>::Zero();
J.block<3, 3>(0, 0) = target_normal.template head<3>().asDiagonal() * T.linear() * skew(traits::point(source, source_index).template head<3>());
J.block<3, 3>(0, 3) = target_normal.template head<3>().asDiagonal() * (-T.linear());
*H = J.transpose() * J;
*b = J.transpose() * error;
*e = 0.5 * error.squaredNorm();
*b = J.transpose() * err;
*e = 0.5 * err.squaredNorm();
return true;
}

View File

@ -23,7 +23,7 @@ public:
/// @brief Constructor
/// @param points Points to initialize the point cloud
template <typename T, int D, typename Allocator>
PointCloud(const std::vector<Eigen::Matrix<T, D, 1>, Allocator>& points) {
explicit PointCloud(const std::vector<Eigen::Matrix<T, D, 1>, Allocator>& points) {
this->resize(points.size());
for (size_t i = 0; i < points.size(); i++) {
this->point(i) << points[i].template cast<double>().template head<3>(), 1.0;

View File

@ -136,6 +136,10 @@ struct LevenbergMarquardtOptimizer {
result.H = H;
result.b = b;
result.error = e;
if (!success) {
break;
}
}
result.num_inliers = std::count_if(factors.begin(), factors.end(), [](const auto& factor) { return factor.inlier(); });

View File

@ -50,16 +50,14 @@ inline Eigen::Matrix3d skew(const Eigen::Vector3d& x) {
inline Eigen::Quaterniond so3_exp(const Eigen::Vector3d& omega) {
double theta_sq = omega.dot(omega);
double theta;
double imag_factor;
double real_factor;
if (theta_sq < 1e-10) {
theta = 0;
double theta_quad = theta_sq * theta_sq;
imag_factor = 0.5 - 1.0 / 48.0 * theta_sq + 1.0 / 3840.0 * theta_quad;
real_factor = 1.0 - 1.0 / 8.0 * theta_sq + 1.0 / 384.0 * theta_quad;
} else {
theta = std::sqrt(theta_sq);
double theta = std::sqrt(theta_sq);
double half_theta = 0.5 * theta;
imag_factor = std::sin(half_theta) / theta;
real_factor = std::cos(half_theta);

View File

@ -14,7 +14,7 @@ namespace small_gicp {
class FastGICPOdometryEstimation : public OnlineOdometryEstimation {
public:
FastGICPOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
explicit FastGICPOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
gicp.setCorrespondenceRandomness(params.num_neighbors);
gicp.setMaxCorrespondenceDistance(params.max_correspondence_distance);
gicp.setNumThreads(params.num_threads);

View File

@ -16,7 +16,7 @@ namespace small_gicp {
class FastVGICPOdometryEstimation : public OnlineOdometryEstimation {
public:
FastVGICPOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
explicit FastVGICPOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
vgicp.setCorrespondenceRandomness(params.num_neighbors);
vgicp.setResolution(params.voxel_resolution);
vgicp.setMaxCorrespondenceDistance(params.max_correspondence_distance);

View File

@ -10,7 +10,7 @@ namespace small_gicp {
class PCLOnlineOdometryEstimation : public OnlineOdometryEstimation {
public:
PCLOnlineOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
explicit PCLOnlineOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
gicp.setCorrespondenceRandomness(params.num_neighbors);
gicp.setMaxCorrespondenceDistance(params.max_correspondence_distance);
}

View File

@ -11,7 +11,7 @@ namespace small_gicp {
class SmallGICPOnlineOdometryEstimation : public OnlineOdometryEstimation {
public:
SmallGICPOnlineOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {}
explicit SmallGICPOnlineOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {}
Eigen::Isometry3d estimate(const PointCloud::Ptr& points) override {
Stopwatch sw;

View File

@ -14,7 +14,7 @@ namespace small_gicp {
class SmallGICPModelOnlineOdometryEstimationTBB : public OnlineOdometryEstimation {
public:
SmallGICPModelOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
explicit SmallGICPModelOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
: OnlineOdometryEstimation(params),
control(tbb::global_control::max_allowed_parallelism, params.num_threads),
T_world_lidar(Eigen::Isometry3d::Identity()) {}

View File

@ -11,7 +11,7 @@ namespace small_gicp {
class SmallGICPOnlineOdometryEstimationOMP : public OnlineOdometryEstimation {
public:
SmallGICPOnlineOdometryEstimationOMP(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T_world_lidar(Eigen::Isometry3d::Identity()) {}
explicit SmallGICPOnlineOdometryEstimationOMP(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T_world_lidar(Eigen::Isometry3d::Identity()) {}
Eigen::Isometry3d estimate(const PointCloud::Ptr& points) override {
Stopwatch sw;

View File

@ -12,7 +12,7 @@ namespace small_gicp {
class SmallGICPPCLOdometryEstimation : public OnlineOdometryEstimation {
public:
SmallGICPPCLOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
explicit SmallGICPPCLOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {
gicp.setCorrespondenceRandomness(params.num_neighbors);
gicp.setMaxCorrespondenceDistance(params.max_correspondence_distance);
gicp.setNumThreads(params.num_threads);

View File

@ -14,7 +14,7 @@ namespace small_gicp {
class SmallGICPOnlineOdometryEstimationTBB : public OnlineOdometryEstimation {
public:
SmallGICPOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
explicit SmallGICPOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
: OnlineOdometryEstimation(params),
control(tbb::global_control::max_allowed_parallelism, params.num_threads),
T(Eigen::Isometry3d::Identity()) {}

View File

@ -27,7 +27,7 @@ public:
InputFrame::Ptr source; // Source frame
};
SmallGICPFlowEstimationTBB(const OdometryEstimationParams& params)
explicit SmallGICPFlowEstimationTBB(const OdometryEstimationParams& params)
: OdometryEstimation(params),
control(tbb::global_control::max_allowed_parallelism, params.num_threads),
throughput(0.0) {

View File

@ -14,7 +14,7 @@ namespace small_gicp {
class SmallVGICPModelOnlineOdometryEstimationTBB : public OnlineOdometryEstimation {
public:
SmallVGICPModelOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
explicit SmallVGICPModelOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
: OnlineOdometryEstimation(params),
control(tbb::global_control::max_allowed_parallelism, params.num_threads),
T_world_lidar(Eigen::Isometry3d::Identity()) {}

View File

@ -12,7 +12,7 @@ namespace small_gicp {
class SmallVGICPOnlineOdometryEstimationOMP : public OnlineOdometryEstimation {
public:
SmallVGICPOnlineOdometryEstimationOMP(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {}
explicit SmallVGICPOnlineOdometryEstimationOMP(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) {}
Eigen::Isometry3d estimate(const PointCloud::Ptr& points) override {
Stopwatch sw;

View File

@ -14,7 +14,7 @@ namespace small_gicp {
class SmallVGICPOnlineOdometryEstimationTBB : public OnlineOdometryEstimation {
public:
SmallVGICPOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
explicit SmallVGICPOnlineOdometryEstimationTBB(const OdometryEstimationParams& params)
: OnlineOdometryEstimation(params),
control(tbb::global_control::max_allowed_parallelism, params.num_threads),
T(Eigen::Isometry3d::Identity()) {}