diff --git a/rct_common/CMakeLists.txt b/rct_common/CMakeLists.txt index 4cfe7000..83eb5290 100644 --- a/rct_common/CMakeLists.txt +++ b/rct_common/CMakeLists.txt @@ -19,7 +19,7 @@ endif() find_gtest() add_library(${PROJECT_NAME} INTERFACE) -target_compile_features(${PROJECT_NAME} INTERFACE cxx_std_11) +target_compile_features(${PROJECT_NAME} INTERFACE cxx_std_17) target_include_directories(${PROJECT_NAME} INTERFACE "$" "$") target_link_libraries(${PROJECT_NAME} INTERFACE Eigen3::Eigen) diff --git a/rct_optimizations/CMakeLists.txt b/rct_optimizations/CMakeLists.txt index 238fb71b..157f8bf3 100644 --- a/rct_optimizations/CMakeLists.txt +++ b/rct_optimizations/CMakeLists.txt @@ -40,7 +40,7 @@ add_library( # DH Chain Kinematic Calibration src/${PROJECT_NAME}/dh_chain.cpp src/${PROJECT_NAME}/dh_chain_kinematic_calibration.cpp) -target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_11) +target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17) target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra) target_include_directories(${PROJECT_NAME} PUBLIC "$" "$") diff --git a/rct_optimizations/include/rct_optimizations/dh_chain_kinematic_calibration.h b/rct_optimizations/include/rct_optimizations/dh_chain_kinematic_calibration.h index 59b1c667..36a36124 100644 --- a/rct_optimizations/include/rct_optimizations/dh_chain_kinematic_calibration.h +++ b/rct_optimizations/include/rct_optimizations/dh_chain_kinematic_calibration.h @@ -400,7 +400,7 @@ class DualDHChainCostPose6D : public DualDHChainCost T rot_diff = Eigen::Quaternion(camera_to_target_measured_.cast().linear()) .angularDistance(Eigen::Quaternion(camera_to_target.linear())); - residual[3] = ceres::IsNaN(rot_diff) ? T(0.0) : T(orientation_weight_) * rot_diff; + residual[3] = ceres::isnan(rot_diff) ? T(0.0) : T(orientation_weight_) * rot_diff; return true; } diff --git a/rct_optimizations/include/rct_optimizations/local_parameterization.h b/rct_optimizations/include/rct_optimizations/local_parameterization.h index b907048a..8bcd15a7 100644 --- a/rct_optimizations/include/rct_optimizations/local_parameterization.h +++ b/rct_optimizations/include/rct_optimizations/local_parameterization.h @@ -2,7 +2,7 @@ #include #include -#include +#include #include // Ceres Solver - A fast non-linear least squares minimizer @@ -126,8 +126,8 @@ void addSubsetParameterization(ceres::Problem& problem, const std::map> mask; EXPECT_NO_THROW(addSubsetParameterization(problem, mask)); // An empty mask should not have added any local parameterization - EXPECT_EQ(problem.GetParameterization(params.data()), nullptr); + EXPECT_EQ(problem.GetManifold(params.data()), nullptr); } // Hold the zero-th row constant @@ -73,7 +73,7 @@ TEST(LocalParameterizationTests, SubsetParameterization) mask[params.data()].push_back(i * params.rows()); } EXPECT_NO_THROW(addSubsetParameterization(problem, mask)); - EXPECT_NE(problem.GetParameterization(params.data()), nullptr); + EXPECT_NE(problem.GetManifold(params.data()), nullptr); } // Solve the optimization