Skip to content

Commit ee1c5d1

Browse files
chore(autoware_ndt_scan_matcher): move header files from include to src (#866)
* chore(ndt_scan_matcher): move headers from `include` to `src` not to be public Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp> * bug(`ndt_omp`): fix a missing copyright Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp> * bug(ndt_scan_matcher): remove unnecessary lines in `CMakeLists.txt` Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp> * style(pre-commit): autofix * bug: fix by `pre-commit` Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp> * bug: fix by `cppcheck` Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp> * style(pre-commit): autofix * bug: fix by `pre-commit` Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp> --------- Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 273b8ac commit ee1c5d1

20 files changed

+57
-43
lines changed

localization/autoware_ndt_scan_matcher/CMakeLists.txt

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,10 @@ ament_auto_add_library(multigrid_ndt_omp SHARED
3434
src/ndt_omp/multigrid_ndt_omp.cpp
3535
src/ndt_omp/estimate_covariance.cpp
3636
)
37+
target_include_directories(multigrid_ndt_omp
38+
PUBLIC
39+
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src>
40+
)
3741
target_link_libraries(multigrid_ndt_omp ${PCL_LIBRARIES})
3842

3943
if(OpenMP_CXX_FOUND)
@@ -47,6 +51,10 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
4751
src/ndt_scan_matcher_core.cpp
4852
src/particle.cpp
4953
)
54+
target_include_directories(${PROJECT_NAME}
55+
PUBLIC
56+
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src>
57+
)
5058

5159
link_directories(${PCL_LIBRARY_DIRS})
5260
target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES} multigrid_ndt_omp)

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/hyper_parameters.hpp renamed to localization/autoware_ndt_scan_matcher/src/hyper_parameters.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__NDT_SCAN_MATCHER__HYPER_PARAMETERS_HPP_
16-
#define AUTOWARE__NDT_SCAN_MATCHER__HYPER_PARAMETERS_HPP_
15+
#ifndef HYPER_PARAMETERS_HPP_
16+
#define HYPER_PARAMETERS_HPP_
1717

1818
#include "ndt_omp/multigrid_ndt_omp.h"
1919

@@ -196,4 +196,4 @@ struct HyperParameters
196196

197197
} // namespace autoware::ndt_scan_matcher
198198

199-
#endif // AUTOWARE__NDT_SCAN_MATCHER__HYPER_PARAMETERS_HPP_
199+
#endif // HYPER_PARAMETERS_HPP_

localization/autoware_ndt_scan_matcher/src/map_update_module.cpp

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <autoware/ndt_scan_matcher/map_update_module.hpp>
15+
#include "map_update_module.hpp"
1616

1717
#include <memory>
1818
#include <string>
@@ -22,19 +22,17 @@ namespace autoware::ndt_scan_matcher
2222

2323
MapUpdateModule::MapUpdateModule(
2424
rclcpp::Node * node, std::mutex * ndt_ptr_mutex, NdtPtrType & ndt_ptr,
25-
HyperParameters::DynamicMapLoading param)
26-
: ndt_ptr_(ndt_ptr),
25+
const HyperParameters::DynamicMapLoading & param)
26+
: loaded_pcd_pub_(node->create_publisher<sensor_msgs::msg::PointCloud2>(
27+
"debug/loaded_pointcloud_map", rclcpp::QoS{1}.transient_local())),
28+
pcd_loader_client_(node->create_client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>(
29+
"pcd_loader_service")),
30+
ndt_ptr_(ndt_ptr),
2731
ndt_ptr_mutex_(ndt_ptr_mutex),
2832
logger_(node->get_logger()),
2933
clock_(node->get_clock()),
3034
param_(param)
3135
{
32-
loaded_pcd_pub_ = node->create_publisher<sensor_msgs::msg::PointCloud2>(
33-
"debug/loaded_pointcloud_map", rclcpp::QoS{1}.transient_local());
34-
35-
pcd_loader_client_ =
36-
node->create_client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>("pcd_loader_service");
37-
3836
secondary_ndt_ptr_.reset(new NdtType);
3937

4038
if (ndt_ptr_) {

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp renamed to localization/autoware_ndt_scan_matcher/src/map_update_module.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_
16-
#define AUTOWARE__NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_
15+
#ifndef MAP_UPDATE_MODULE_HPP_
16+
#define MAP_UPDATE_MODULE_HPP_
1717

1818
#include "hyper_parameters.hpp"
1919
#include "ndt_omp/multigrid_ndt_omp.h"
@@ -54,7 +54,7 @@ class MapUpdateModule
5454
public:
5555
MapUpdateModule(
5656
rclcpp::Node * node, std::mutex * ndt_ptr_mutex, NdtPtrType & ndt_ptr,
57-
HyperParameters::DynamicMapLoading param);
57+
const HyperParameters::DynamicMapLoading & param);
5858

5959
bool out_of_map_range(const geometry_msgs::msg::Point & position);
6060

@@ -101,4 +101,4 @@ class MapUpdateModule
101101

102102
} // namespace autoware::ndt_scan_matcher
103103

104-
#endif // AUTOWARE__NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_
104+
#endif // MAP_UPDATE_MODULE_HPP_

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/LICENSE renamed to localization/autoware_ndt_scan_matcher/src/ndt_omp/LICENSE

File renamed without changes.

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/README.md renamed to localization/autoware_ndt_scan_matcher/src/ndt_omp/README.md

File renamed without changes.

localization/autoware_ndt_scan_matcher/src/ndt_omp/estimate_covariance.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <autoware/ndt_scan_matcher/ndt_omp/estimate_covariance.hpp>
15+
#include "ndt_omp/estimate_covariance.hpp"
1616

1717
#include <algorithm>
1818
#include <fstream>

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/estimate_covariance.hpp renamed to localization/autoware_ndt_scan_matcher/src/ndt_omp/estimate_covariance.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__NDT_SCAN_MATCHER__NDT_OMP__ESTIMATE_COVARIANCE_HPP_
16-
#define AUTOWARE__NDT_SCAN_MATCHER__NDT_OMP__ESTIMATE_COVARIANCE_HPP_
15+
#ifndef NDT_OMP__ESTIMATE_COVARIANCE_HPP_
16+
#define NDT_OMP__ESTIMATE_COVARIANCE_HPP_
1717

1818
#include "multigrid_ndt_omp.h"
1919

@@ -79,4 +79,4 @@ Eigen::Matrix2d adjust_diagonal_covariance(
7979

8080
} // namespace pclomp
8181

82-
#endif // AUTOWARE__NDT_SCAN_MATCHER__NDT_OMP__ESTIMATE_COVARIANCE_HPP_
82+
#endif // NDT_OMP__ESTIMATE_COVARIANCE_HPP_

localization/autoware_ndt_scan_matcher/src/ndt_omp/multi_voxel_grid_covariance_omp.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include "ndt_omp/multi_voxel_grid_covariance_omp.h"
16+
1517
#include "multi_voxel_grid_covariance_omp_impl.hpp"
1618

1719
template class pclomp::MultiVoxelGridCovariance<pcl::PointXYZ>;

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h renamed to localization/autoware_ndt_scan_matcher/src/ndt_omp/multi_voxel_grid_covariance_omp.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,8 @@
4949
*
5050
*/
5151

52-
#ifndef AUTOWARE__NDT_SCAN_MATCHER__NDT_OMP__MULTI_VOXEL_GRID_COVARIANCE_OMP_H_
53-
#define AUTOWARE__NDT_SCAN_MATCHER__NDT_OMP__MULTI_VOXEL_GRID_COVARIANCE_OMP_H_
52+
#ifndef NDT_OMP__MULTI_VOXEL_GRID_COVARIANCE_OMP_H_
53+
#define NDT_OMP__MULTI_VOXEL_GRID_COVARIANCE_OMP_H_
5454

5555
// cspell:ignore Magnusson, Okorn, evecs, evals, covar, eigvalue, futs
5656

@@ -391,4 +391,4 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid<PointT>
391391
};
392392
} // namespace pclomp
393393

394-
#endif // AUTOWARE__NDT_SCAN_MATCHER__NDT_OMP__MULTI_VOXEL_GRID_COVARIANCE_OMP_H_
394+
#endif // NDT_OMP__MULTI_VOXEL_GRID_COVARIANCE_OMP_H_

0 commit comments

Comments
 (0)