Skip to content

Commit

Permalink
Support Noetic (#297)
Browse files Browse the repository at this point in the history
* Enable C++14 to support PCL 1.10
* Fix new lint errors
  • Loading branch information
at-wat committed Apr 6, 2020
1 parent 5787c19 commit 484f788
Show file tree
Hide file tree
Showing 8 changed files with 13 additions and 4 deletions.
5 changes: 3 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.0.2)
cmake_minimum_required(VERSION 3.1.3)
project(mcl_3dl)

set(CATKIN_DEPENDS
Expand Down Expand Up @@ -34,8 +34,9 @@ catkin_package(
CATKIN_DEPENDS ${CATKIN_DEPENDS}
)

set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

add_compile_options(-std=c++11)
include_directories(include ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR} ${Boost_INCLUDE_DIRS} ${PCL_INCLUDE_DIR})
add_definitions(${PCL_DEFINITIONS})

Expand Down
1 change: 1 addition & 0 deletions include/mcl_3dl/chunked_kdtree.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#define MCL_3DL_CHUNKED_KDTREE_H

#include <cmath>
#include <memory>
#include <stdexcept>
#include <unordered_map>
#include <vector>
Expand Down
5 changes: 3 additions & 2 deletions include/mcl_3dl/cloud_accum.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,10 @@
#ifndef MCL_3DL_CLOUD_ACCUM_H
#define MCL_3DL_CLOUD_ACCUM_H

#include <vector>
#include <string>
#include <functional>
#include <memory>
#include <string>
#include <vector>

#include <sensor_msgs/PointCloud2.h>

Expand Down
1 change: 1 addition & 0 deletions include/mcl_3dl/lidar_measurement_model_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#ifndef MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
#define MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H

#include <memory>
#include <string>
#include <utility>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#ifndef MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H
#define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H

#include <memory>
#include <string>
#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#ifndef MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H
#define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H

#include <memory>
#include <string>
#include <vector>

Expand Down
2 changes: 2 additions & 0 deletions include/mcl_3dl/parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@
#ifndef MCL_3DL_PARAMETERS_H
#define MCL_3DL_PARAMETERS_H

#include <memory>

namespace mcl_3dl
{
class Parameters
Expand Down
1 change: 1 addition & 0 deletions include/mcl_3dl/point_cloud_random_sampler.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#ifndef MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H
#define MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H

#include <memory>
#include <random>

#include <pcl/point_types.h>
Expand Down

0 comments on commit 484f788

Please sign in to comment.