Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update for Ceres 2.2 and Ubuntu Noble #115

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion rct_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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 "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")
target_link_libraries(${PROJECT_NAME} INTERFACE Eigen3::Eigen)
Expand Down
2 changes: 1 addition & 1 deletion rct_optimizations/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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 "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -400,7 +400,7 @@ class DualDHChainCostPose6D : public DualDHChainCost
T rot_diff = Eigen::Quaternion<T>(camera_to_target_measured_.cast<T>().linear())
.angularDistance(Eigen::Quaternion<T>(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;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <Eigen/Core>
#include <ceres/problem.h>
#include <ceres/local_parameterization.h>
#include <ceres/manifold.h>
#include <rct_optimizations/types.h>

// Ceres Solver - A fast non-linear least squares minimizer
Expand Down Expand Up @@ -126,8 +126,8 @@ void addSubsetParameterization(ceres::Problem& problem, const std::map<const dou
}
else
{
ceres::LocalParameterization* lp = new ceres::SubsetParameterization(block_size, mask);
problem.SetParameterization(p, lp);
ceres::Manifold* lp = new ceres::SubsetManifold(block_size, mask);
problem.SetManifold(p, lp);
}
}
}
Expand Down
8 changes: 4 additions & 4 deletions rct_optimizations/test/local_parameterization_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ TEST(LocalParameterizationTests, SubsetParameterization)
EXPECT_NO_THROW(addSubsetParameterization(problem, mask));

// Expect there to be no parameterization, but the entire block should be constant
EXPECT_EQ(problem.GetParameterization(params.data()), nullptr);
EXPECT_EQ(problem.GetManifold(params.data()), nullptr);
EXPECT_TRUE(problem.IsParameterBlockConstant(params.data()));
}

Expand All @@ -51,15 +51,15 @@ TEST(LocalParameterizationTests, SubsetParameterization)
int bad_idx = params.size() * 2;
mask[params.data()].insert(mask[params.data()].begin(), { bad_idx, 0, 1, 2 });
EXPECT_THROW(addSubsetParameterization(problem, mask), OptimizationException);
EXPECT_EQ(problem.GetParameterization(params.data()), nullptr);
EXPECT_EQ(problem.GetManifold(params.data()), nullptr);
}

// Empty mask
{
std::map<const double*, std::vector<int>> 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
Expand All @@ -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
Expand Down
Loading