Skip to content

Commit

Permalink
Merge branch 'master' into map-loading
Browse files Browse the repository at this point in the history
  • Loading branch information
TirelessDev committed Sep 2, 2021
2 parents 83527f9 + 3a12a13 commit a85a854
Show file tree
Hide file tree
Showing 9 changed files with 53 additions and 45 deletions.
33 changes: 33 additions & 0 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
name: Build

on:
push:
branches: [ master ]
pull_request:
branches: [ master ]

# Allows you to run this workflow manually from the Actions tab
workflow_dispatch:

jobs:
build:
runs-on: ubuntu-latest
strategy:
matrix:
ROS_DISTRO: [melodic, melodic_llvm, noetic, noetic_llvm]

steps:
- uses: actions/checkout@v2

- name: Docker login
uses: docker/login-action@v1
with:
username: ${{ secrets.DOCKER_USERNAME }}
password: ${{ secrets.DOCKER_TOKEN }}

- name: Docker build
uses: docker/build-push-action@v2
with:
file: ${{github.workspace}}/docker/${{ matrix.ROS_DISTRO }}/Dockerfile
context: .
push: false
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
.vscode/*
imgui.ini
rviz/*
26 changes: 0 additions & 26 deletions .travis.yml

This file was deleted.

2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

[video](https://drive.google.com/open?id=0B9f5zFkpn4soSG96Tkt4SFFTbms)

[![Codacy Badge](https://api.codacy.com/project/badge/Grade/1175635f00394e789b457b44690ce72c)](https://app.codacy.com/app/koide3/hdl_graph_slam?utm_source=github.com&utm_medium=referral&utm_content=koide3/hdl_graph_slam&utm_campaign=Badge_Grade_Dashboard) [![Build Status](https://travis-ci.org/koide3/hdl_graph_slam.svg?branch=master)](https://travis-ci.org/koide3/hdl_graph_slam) on melodic & noetic
[![Build](https://github.com/koide3/hdl_graph_slam/actions/workflows/build.yml/badge.svg)](https://github.com/koide3/hdl_graph_slam/actions/workflows/build.yml) on melodic & noetic

## Nodelets
***hdl_graph_slam*** consists of four nodelets.
Expand Down
6 changes: 3 additions & 3 deletions apps/prefiltering_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,12 +53,12 @@ class PrefilteringNodelet : public nodelet::Nodelet {

if(downsample_method == "VOXELGRID") {
std::cout << "downsample: VOXELGRID " << downsample_resolution << std::endl;
boost::shared_ptr<pcl::VoxelGrid<PointT>> voxelgrid(new pcl::VoxelGrid<PointT>());
auto voxelgrid = new pcl::VoxelGrid<PointT>();
voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
downsample_filter = voxelgrid;
downsample_filter.reset(voxelgrid);
} else if(downsample_method == "APPROX_VOXELGRID") {
std::cout << "downsample: APPROX_VOXELGRID " << downsample_resolution << std::endl;
boost::shared_ptr<pcl::ApproximateVoxelGrid<PointT>> approx_voxelgrid(new pcl::ApproximateVoxelGrid<PointT>());
pcl::ApproximateVoxelGrid<PointT>::Ptr approx_voxelgrid(new pcl::ApproximateVoxelGrid<PointT>());
approx_voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
downsample_filter = approx_voxelgrid;
} else {
Expand Down
8 changes: 4 additions & 4 deletions apps/scan_matching_odometry_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,12 +85,12 @@ class ScanMatchingOdometryNodelet : public nodelet::Nodelet {
double downsample_resolution = pnh.param<double>("downsample_resolution", 0.1);
if(downsample_method == "VOXELGRID") {
std::cout << "downsample: VOXELGRID " << downsample_resolution << std::endl;
boost::shared_ptr<pcl::VoxelGrid<PointT>> voxelgrid(new pcl::VoxelGrid<PointT>());
auto voxelgrid = new pcl::VoxelGrid<PointT>();
voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
downsample_filter = voxelgrid;
downsample_filter.reset(voxelgrid);
} else if(downsample_method == "APPROX_VOXELGRID") {
std::cout << "downsample: APPROX_VOXELGRID " << downsample_resolution << std::endl;
boost::shared_ptr<pcl::ApproximateVoxelGrid<PointT>> approx_voxelgrid(new pcl::ApproximateVoxelGrid<PointT>());
pcl::ApproximateVoxelGrid<PointT>::Ptr approx_voxelgrid(new pcl::ApproximateVoxelGrid<PointT>());
approx_voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
downsample_filter = approx_voxelgrid;
} else {
Expand All @@ -99,7 +99,7 @@ class ScanMatchingOdometryNodelet : public nodelet::Nodelet {
std::cerr << " : use passthrough filter" << std::endl;
}
std::cout << "downsample: NONE" << std::endl;
boost::shared_ptr<pcl::PassThrough<PointT>> passthrough(new pcl::PassThrough<PointT>());
pcl::PassThrough<PointT>::Ptr passthrough(new pcl::PassThrough<PointT>());
downsample_filter = passthrough;
}

Expand Down
2 changes: 1 addition & 1 deletion docker/melodic/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \
RUN mkdir -p /root/catkin_ws/src
WORKDIR /root/catkin_ws/src
RUN /bin/bash -c '. /opt/ros/melodic/setup.bash; catkin_init_workspace'
RUN git clone -b melodic https://github.com/koide3/ndt_omp.git
RUN git clone https://github.com/koide3/ndt_omp.git
RUN git clone https://github.com/SMRT-AIST/fast_gicp.git --recursive

COPY . /root/catkin_ws/src/hdl_graph_slam/
Expand Down
2 changes: 1 addition & 1 deletion include/hdl_graph_slam/registrations.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace hdl_graph_slam {
* @param pnh
* @return selected scan matching
*/
boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_registration_method(ros::NodeHandle& pnh);
pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>::Ptr select_registration_method(ros::NodeHandle& pnh);

} // namespace hdl_graph_slam

Expand Down
18 changes: 9 additions & 9 deletions src/hdl_graph_slam/registrations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,14 @@

namespace hdl_graph_slam {

boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_registration_method(ros::NodeHandle& pnh) {
pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>::Ptr select_registration_method(ros::NodeHandle& pnh) {
using PointT = pcl::PointXYZI;

// select a registration method (ICP, GICP, NDT)
std::string registration_method = pnh.param<std::string>("registration_method", "NDT_OMP");
if(registration_method == "FAST_GICP") {
std::cout << "registration: FAST_GICP" << std::endl;
boost::shared_ptr<fast_gicp::FastGICP<PointT, PointT>> gicp(new fast_gicp::FastGICP<PointT, PointT>());
fast_gicp::FastGICP<PointT, PointT>::Ptr gicp(new fast_gicp::FastGICP<PointT, PointT>());
gicp->setNumThreads(pnh.param<int>("reg_num_threads", 0));
gicp->setTransformationEpsilon(pnh.param<double>("reg_transformation_epsilon", 0.01));
gicp->setMaximumIterations(pnh.param<int>("reg_maximum_iterations", 64));
Expand All @@ -37,7 +37,7 @@ boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_regi
#ifdef USE_VGICP_CUDA
else if(registration_method == "FAST_VGICP_CUDA") {
std::cout << "registration: FAST_VGICP_CUDA" << std::endl;
boost::shared_ptr<fast_gicp::FastVGICPCuda<PointT, PointT>> vgicp(new fast_gicp::FastVGICPCuda<PointT, PointT>());
fast_gicp::FastVGICPCuda<PointT, PointT>::Ptr vgicp(new fast_gicp::FastVGICPCuda<PointT, PointT>());
vgicp->setResolution(pnh.param<double>("reg_resolution", 1.0));
vgicp->setTransformationEpsilon(pnh.param<double>("reg_transformation_epsilon", 0.01));
vgicp->setMaximumIterations(pnh.param<int>("reg_maximum_iterations", 64));
Expand All @@ -47,7 +47,7 @@ boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_regi
#endif
else if(registration_method == "FAST_VGICP") {
std::cout << "registration: FAST_VGICP" << std::endl;
boost::shared_ptr<fast_gicp::FastVGICP<PointT, PointT>> vgicp(new fast_gicp::FastVGICP<PointT, PointT>());
fast_gicp::FastVGICP<PointT, PointT>::Ptr vgicp(new fast_gicp::FastVGICP<PointT, PointT>());
vgicp->setNumThreads(pnh.param<int>("reg_num_threads", 0));
vgicp->setResolution(pnh.param<double>("reg_resolution", 1.0));
vgicp->setTransformationEpsilon(pnh.param<double>("reg_transformation_epsilon", 0.01));
Expand All @@ -56,7 +56,7 @@ boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_regi
return vgicp;
} else if(registration_method == "ICP") {
std::cout << "registration: ICP" << std::endl;
boost::shared_ptr<pcl::IterativeClosestPoint<PointT, PointT>> icp(new pcl::IterativeClosestPoint<PointT, PointT>());
pcl::IterativeClosestPoint<PointT, PointT>::Ptr icp(new pcl::IterativeClosestPoint<PointT, PointT>());
icp->setTransformationEpsilon(pnh.param<double>("reg_transformation_epsilon", 0.01));
icp->setMaximumIterations(pnh.param<int>("reg_maximum_iterations", 64));
icp->setMaxCorrespondenceDistance(pnh.param<double>("reg_max_correspondence_distance", 2.5));
Expand All @@ -65,7 +65,7 @@ boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_regi
} else if(registration_method.find("GICP") != std::string::npos) {
if(registration_method.find("OMP") == std::string::npos) {
std::cout << "registration: GICP" << std::endl;
boost::shared_ptr<pcl::GeneralizedIterativeClosestPoint<PointT, PointT>> gicp(new pcl::GeneralizedIterativeClosestPoint<PointT, PointT>());
pcl::GeneralizedIterativeClosestPoint<PointT, PointT>::Ptr gicp(new pcl::GeneralizedIterativeClosestPoint<PointT, PointT>());
gicp->setTransformationEpsilon(pnh.param<double>("reg_transformation_epsilon", 0.01));
gicp->setMaximumIterations(pnh.param<int>("reg_maximum_iterations", 64));
gicp->setUseReciprocalCorrespondences(pnh.param<bool>("reg_use_reciprocal_correspondences", false));
Expand All @@ -75,7 +75,7 @@ boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_regi
return gicp;
} else {
std::cout << "registration: GICP_OMP" << std::endl;
boost::shared_ptr<pclomp::GeneralizedIterativeClosestPoint<PointT, PointT>> gicp(new pclomp::GeneralizedIterativeClosestPoint<PointT, PointT>());
pclomp::GeneralizedIterativeClosestPoint<PointT, PointT>::Ptr gicp(new pclomp::GeneralizedIterativeClosestPoint<PointT, PointT>());
gicp->setTransformationEpsilon(pnh.param<double>("reg_transformation_epsilon", 0.01));
gicp->setMaximumIterations(pnh.param<int>("reg_maximum_iterations", 64));
gicp->setUseReciprocalCorrespondences(pnh.param<bool>("reg_use_reciprocal_correspondences", false));
Expand All @@ -93,7 +93,7 @@ boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_regi
double ndt_resolution = pnh.param<double>("reg_resolution", 0.5);
if(registration_method.find("OMP") == std::string::npos) {
std::cout << "registration: NDT " << ndt_resolution << std::endl;
boost::shared_ptr<pcl::NormalDistributionsTransform<PointT, PointT>> ndt(new pcl::NormalDistributionsTransform<PointT, PointT>());
pcl::NormalDistributionsTransform<PointT, PointT>::Ptr ndt(new pcl::NormalDistributionsTransform<PointT, PointT>());
ndt->setTransformationEpsilon(pnh.param<double>("reg_transformation_epsilon", 0.01));
ndt->setMaximumIterations(pnh.param<int>("reg_maximum_iterations", 64));
ndt->setResolution(ndt_resolution);
Expand All @@ -102,7 +102,7 @@ boost::shared_ptr<pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>> select_regi
int num_threads = pnh.param<int>("reg_num_threads", 0);
std::string nn_search_method = pnh.param<std::string>("reg_nn_search_method", "DIRECT7");
std::cout << "registration: NDT_OMP " << nn_search_method << " " << ndt_resolution << " (" << num_threads << " threads)" << std::endl;
boost::shared_ptr<pclomp::NormalDistributionsTransform<PointT, PointT>> ndt(new pclomp::NormalDistributionsTransform<PointT, PointT>());
pclomp::NormalDistributionsTransform<PointT, PointT>::Ptr ndt(new pclomp::NormalDistributionsTransform<PointT, PointT>());
if(num_threads > 0) {
ndt->setNumThreads(num_threads);
}
Expand Down

0 comments on commit a85a854

Please sign in to comment.