Skip to content

Commit

Permalink
Merge pull request #24 from koide3/const
Browse files Browse the repository at this point in the history
add const to NearestNeighborSearch
  • Loading branch information
koide3 authored Sep 12, 2024
2 parents e1a5407 + 9c2e0c4 commit 51df146
Show file tree
Hide file tree
Showing 11 changed files with 29 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ IntegratedCT_GICPFactor_<TargetFrame, SourceFrame>::IntegratedCT_GICPFactor_(
gtsam::Key source_t1_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_tree)
: IntegratedCT_ICPFactor_<TargetFrame, SourceFrame>(source_t0_key, source_t1_key, target, source, target_tree) {
//
if (!frame::has_points(*target) || !frame::has_covs(*target)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ IntegratedCT_ICPFactor_<TargetFrame, SourceFrame>::IntegratedCT_ICPFactor_(
gtsam::Key source_t1_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_tree)
: gtsam::NonlinearFactor(gtsam::KeyVector{source_t0_key, source_t1_key}),
num_threads(1),
max_correspondence_distance_sq(1.0),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ IntegratedGICPFactor_<TargetFrame, SourceFrame>::IntegratedGICPFactor_(
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_tree)
: gtsam_points::IntegratedMatchingCostFactor(target_key, source_key),
num_threads(1),
max_correspondence_distance_sq(1.0),
Expand Down Expand Up @@ -56,7 +56,7 @@ IntegratedGICPFactor_<TargetFrame, SourceFrame>::IntegratedGICPFactor_(
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_tree)
: gtsam_points::IntegratedMatchingCostFactor(fixed_target_pose, source_key),
num_threads(1),
max_correspondence_distance_sq(1.0),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ IntegratedICPFactor_<TargetFrame, SourceFrame>::IntegratedICPFactor_(
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree,
const std::shared_ptr<const NearestNeighborSearch>& target_tree,
bool use_point_to_plane)
: gtsam_points::IntegratedMatchingCostFactor(target_key, source_key),
num_threads(1),
Expand Down Expand Up @@ -60,7 +60,7 @@ IntegratedICPFactor_<TargetFrame, SourceFrame>::IntegratedICPFactor_(
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree,
const std::shared_ptr<const NearestNeighborSearch>& target_tree,
bool use_point_to_plane)
: gtsam_points::IntegratedMatchingCostFactor(fixed_target_pose, source_key),
num_threads(1),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ IntegratedPointToPlaneFactor_<TargetFrame, SourceFrame>::IntegratedPointToPlaneF
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_tree)
: gtsam_points::IntegratedMatchingCostFactor(target_key, source_key),
num_threads(1),
max_correspondence_distance_sq(1.0),
Expand Down Expand Up @@ -185,7 +185,7 @@ IntegratedPointToEdgeFactor_<TargetFrame, SourceFrame>::IntegratedPointToEdgeFac
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_tree)
: gtsam_points::IntegratedMatchingCostFactor(target_key, source_key),
num_threads(1),
max_correspondence_distance_sq(1.0),
Expand Down Expand Up @@ -358,8 +358,8 @@ IntegratedLOAMFactor_<TargetFrame, SourceFrame>::IntegratedLOAMFactor_(
const std::shared_ptr<const TargetFrame>& target_planes,
const std::shared_ptr<const SourceFrame>& source_edges,
const std::shared_ptr<const SourceFrame>& source_planes,
const std::shared_ptr<NearestNeighborSearch>& target_edges_tree,
const std::shared_ptr<NearestNeighborSearch>& target_planes_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_edges_tree,
const std::shared_ptr<const NearestNeighborSearch>& target_planes_tree)
: gtsam_points::IntegratedMatchingCostFactor(target_key, source_key),
enable_correspondence_validation(false) {
//
Expand Down
2 changes: 1 addition & 1 deletion include/gtsam_points/factors/integrated_ct_gicp_factor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class IntegratedCT_GICPFactor_ : public IntegratedCT_ICPFactor_<TargetFrame, Sou
gtsam::Key source_t1_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree);
const std::shared_ptr<const NearestNeighborSearch>& target_tree);

/**
* @brief Constructor
Expand Down
4 changes: 2 additions & 2 deletions include/gtsam_points/factors/integrated_ct_icp_factor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class IntegratedCT_ICPFactor_ : public gtsam::NonlinearFactor {
gtsam::Key source_t1_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree);
const std::shared_ptr<const NearestNeighborSearch>& target_tree);

/**
* @brief Constructor
Expand Down Expand Up @@ -75,7 +75,7 @@ class IntegratedCT_ICPFactor_ : public gtsam::NonlinearFactor {
int num_threads;
double max_correspondence_distance_sq;

std::shared_ptr<NearestNeighborSearch> target_tree;
std::shared_ptr<const NearestNeighborSearch> target_tree;

std::vector<double> time_table;
mutable std::vector<gtsam::Pose3> source_poses;
Expand Down
6 changes: 3 additions & 3 deletions include/gtsam_points/factors/integrated_gicp_factor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class IntegratedGICPFactor_ : public gtsam_points::IntegratedMatchingCostFactor
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree);
const std::shared_ptr<const NearestNeighborSearch>& target_tree);

///< Create a binary ICP factor between target and source poses.
IntegratedGICPFactor_(
Expand All @@ -58,7 +58,7 @@ class IntegratedGICPFactor_ : public gtsam_points::IntegratedMatchingCostFactor
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree);
const std::shared_ptr<const NearestNeighborSearch>& target_tree);

///< Create a unary GICP factor between a fixed target pose and an active source pose.
IntegratedGICPFactor_(
Expand Down Expand Up @@ -107,7 +107,7 @@ class IntegratedGICPFactor_ : public gtsam_points::IntegratedMatchingCostFactor
int num_threads;
double max_correspondence_distance_sq;

std::shared_ptr<NearestNeighborSearch> target_tree;
std::shared_ptr<const NearestNeighborSearch> target_tree;

// I'm unhappy to have mutable members...
double correspondence_update_tolerance_rot;
Expand Down
8 changes: 4 additions & 4 deletions include/gtsam_points/factors/integrated_icp_factor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class IntegratedICPFactor_ : public gtsam_points::IntegratedMatchingCostFactor {
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree,
const std::shared_ptr<const NearestNeighborSearch>& target_tree,
bool use_point_to_plane = false);

/// Create a binary ICP factor between two poses.
Expand All @@ -62,7 +62,7 @@ class IntegratedICPFactor_ : public gtsam_points::IntegratedMatchingCostFactor {
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree,
const std::shared_ptr<const NearestNeighborSearch>& target_tree,
bool use_point_to_plane = false);

/// Create a unary ICP factor between a fixed target pose and an active source pose.
Expand Down Expand Up @@ -110,7 +110,7 @@ class IntegratedICPFactor_ : public gtsam_points::IntegratedMatchingCostFactor {
double max_correspondence_distance_sq;
bool use_point_to_plane;

std::shared_ptr<NearestNeighborSearch> target_tree;
std::shared_ptr<const NearestNeighborSearch> target_tree;

// I'm unhappy to have mutable members...
double correspondence_update_tolerance_rot;
Expand All @@ -135,7 +135,7 @@ class IntegratedPointToPlaneICPFactor_ : public gtsam_points::IntegratedICPFacto
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree)
const std::shared_ptr<const NearestNeighborSearch>& target_tree)
: IntegratedICPFactor_<TargetFrame, SourceFrame>(target_key, source_key, target, source, target_tree, true) {}

IntegratedPointToPlaneICPFactor_(
Expand Down
12 changes: 6 additions & 6 deletions include/gtsam_points/factors/integrated_loam_factor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@ class IntegratedLOAMFactor_ : public gtsam_points::IntegratedMatchingCostFactor
const std::shared_ptr<const TargetFrame>& target_planes,
const std::shared_ptr<const SourceFrame>& source_edges,
const std::shared_ptr<const SourceFrame>& source_planes,
const std::shared_ptr<NearestNeighborSearch>& target_edges_tree,
const std::shared_ptr<NearestNeighborSearch>& target_planes_tree);
const std::shared_ptr<const NearestNeighborSearch>& target_edges_tree,
const std::shared_ptr<const NearestNeighborSearch>& target_planes_tree);

IntegratedLOAMFactor_(
gtsam::Key target_key,
Expand Down Expand Up @@ -95,7 +95,7 @@ class IntegratedPointToPlaneFactor_ : public gtsam_points::IntegratedMatchingCos
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree);
const std::shared_ptr<const NearestNeighborSearch>& target_tree);

IntegratedPointToPlaneFactor_(
gtsam::Key target_key,
Expand Down Expand Up @@ -127,7 +127,7 @@ class IntegratedPointToPlaneFactor_ : public gtsam_points::IntegratedMatchingCos
int num_threads;
double max_correspondence_distance_sq;

std::shared_ptr<NearestNeighborSearch> target_tree;
std::shared_ptr<const NearestNeighborSearch> target_tree;

// I'm unhappy to have mutable members...
double correspondence_update_tolerance_rot;
Expand All @@ -153,7 +153,7 @@ class IntegratedPointToEdgeFactor_ : public gtsam_points::IntegratedMatchingCost
gtsam::Key source_key,
const std::shared_ptr<const TargetFrame>& target,
const std::shared_ptr<const SourceFrame>& source,
const std::shared_ptr<NearestNeighborSearch>& target_tree);
const std::shared_ptr<const NearestNeighborSearch>& target_tree);

IntegratedPointToEdgeFactor_(
gtsam::Key target_key,
Expand Down Expand Up @@ -185,7 +185,7 @@ class IntegratedPointToEdgeFactor_ : public gtsam_points::IntegratedMatchingCost
int num_threads;
double max_correspondence_distance_sq;

std::shared_ptr<NearestNeighborSearch> target_tree;
std::shared_ptr<const NearestNeighborSearch> target_tree;

// I'm unhappy to have mutable members...
double correspondence_update_tolerance_rot;
Expand Down
6 changes: 3 additions & 3 deletions include/gtsam_points/util/read_points.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

namespace gtsam_points {

std::vector<float> read_times(const std::string& path) {
static std::vector<float> read_times(const std::string& path) {
std::ifstream ifs(path, std::ios::binary | std::ios::ate);
if (!ifs) {
std::cerr << "error: failed to open " << path << std::endl;
Expand All @@ -27,7 +27,7 @@ std::vector<float> read_times(const std::string& path) {
return times;
}

std::vector<Eigen::Vector3f> read_points(const std::string& path) {
static std::vector<Eigen::Vector3f> read_points(const std::string& path) {
std::ifstream ifs(path, std::ios::binary | std::ios::ate);
if (!ifs) {
std::cerr << "error: failed to open " << path << std::endl;
Expand All @@ -44,7 +44,7 @@ std::vector<Eigen::Vector3f> read_points(const std::string& path) {
return points;
}

std::vector<Eigen::Vector4f> read_points4(const std::string& path) {
static std::vector<Eigen::Vector4f> read_points4(const std::string& path) {
std::ifstream ifs(path, std::ios::binary | std::ios::ate);
if (!ifs) {
std::cerr << "error: failed to open " << path << std::endl;
Expand Down

0 comments on commit 51df146

Please sign in to comment.