Closed immanueln98 closed 1 year ago
It builds in CI, my machine, and the build farm, so I think its something on your side.
It is because of a new ceres version, i could build after making this changes:
index 1828ed8..8540a17 100644
--- a/solvers/ceres_solver.cpp
+++ b/solvers/ceres_solver.cpp
@@ -3,6 +3,7 @@
* Author: Steve Macenski (stevenmacenski@gmail.com)
*/
+#include <ceres/manifold.h>
#include <unordered_map>
#include <string>
#include <utility>
@@ -46,7 +47,7 @@ void CeresSolver::Configure(rclcpp::Node::SharedPtr node)
first_node_ = nodes_->end();
// formulate problem
- angle_local_parameterization_ = AngleLocalParameterization::Create();
+ angle_local_parameterization_ = AngleManifold::Create();
// choose loss function default squared loss (NULL)
loss_function_ = NULL;
@@ -267,7 +268,7 @@ void CeresSolver::Reset()
problem_ = new ceres::Problem(options_problem_);
first_node_ = nodes_->end();
- angle_local_parameterization_ = AngleLocalParameterization::Create();
+ angle_local_parameterization_ = AngleManifold::Create();
}
/*****************************************************************************/
@@ -338,10 +339,16 @@ void CeresSolver::AddConstraint(karto::Edge<karto::LocalizedRangeScan> * pEdge)
cost_function, loss_function_,
&node1it->second(0), &node1it->second(1), &node1it->second(2),
&node2it->second(0), &node2it->second(1), &node2it->second(2));
- problem_->SetParameterization(&node1it->second(2),
- angle_local_parameterization_);
- problem_->SetParameterization(&node2it->second(2),
- angle_local_parameterization_);
+ // Create a local parameterization for angles (assuming angle_local_parameterization_ is already defined)
+ ceres::Manifold* angle_parameterization = angle_local_parameterization_;
+
+ // Add parameters to the problem with local parameterization
+ problem_->AddParameterBlock(&node1it->second(2), 1, angle_parameterization);
+ problem_->AddParameterBlock(&node2it->second(2), 1, angle_parameterization);
+// problem_->SetParameterization(&node1it->second(2),
+// angle_local_parameterization_);
+// problem_->SetParameterization(&node2it->second(2),
+// angle_local_parameterization_);
blocks_->insert(std::pair<std::size_t, ceres::ResidualBlockId>(
GetHash(node1, node2), block));
diff --git a/solvers/ceres_solver.hpp b/solvers/ceres_solver.hpp
index 162b559..023b7c9 100644
--- a/solvers/ceres_solver.hpp
+++ b/solvers/ceres_solver.hpp
@@ -7,7 +7,7 @@
#define SOLVERS__CERES_SOLVER_HPP_
#include <math.h>
-#include <ceres/local_parameterization.h>
+#include <ceres/manifold.h>
#include <ceres/ceres.h>
#include <vector>
#include <unordered_map>
@@ -65,7 +65,7 @@ private:
ceres::Problem::Options options_problem_;
ceres::LossFunction * loss_function_;
ceres::Problem * problem_;
- ceres::LocalParameterization * angle_local_parameterization_;
+ ceres::Manifold * angle_local_parameterization_;
bool was_constant_set_, debug_logging_;
// graph
diff --git a/solvers/ceres_utils.h b/solvers/ceres_utils.h
index 42c2fad..a044b9d 100644
--- a/solvers/ceres_utils.h
+++ b/solvers/ceres_utils.h
@@ -7,7 +7,7 @@
#define SOLVERS__CERES_UTILS_H_
#include <ceres/ceres.h>
-#include <ceres/local_parameterization.h>
+#include <ceres/manifold.h>
#include <cmath>
#include <utility>
@@ -35,7 +35,7 @@ inline T NormalizeAngle(const T & angle_radians)
/*****************************************************************************/
/*****************************************************************************/
-class AngleLocalParameterization
+class AngleManifold
{
public:
template<typename T>
@@ -47,9 +47,21 @@ public:
return true;
}
- static ceres::LocalParameterization * Create()
+ template<typename T>
+ bool Plus(const T* theta_radians, const T* delta_theta_radians, T* theta_radians_plus_delta) const {
+ *theta_radians_plus_delta = NormalizeAngle(*theta_radians + *delta_theta_radians);
+ return true;
+ }
+
+ template<typename T>
+ bool Minus(const T* theta_radians_plus_delta, const T* theta_radians, T* delta_theta_radians) const {
+ *delta_theta_radians = NormalizeAngle(*theta_radians_plus_delta - *theta_radians);
+ return true;
+ }
+
+ static ceres::Manifold * Create()
{
- return new ceres::AutoDiffLocalParameterization<AngleLocalParameterization, 1, 1>;
+ return new ceres::AutoDiffManifold<AngleManifold, 1, 1>;
}
};
slam_toolbox: 2.6.8 ceres: 2.2.0
Required Info:
Steps to reproduce issue
I had cloned the repo into a src folder and ran colcon build. The build failed and the corresponding terminal output is shown below.
Expected behavior
Actual behavior
`Starting >>> slam_toolbox [Processing: slam_toolbox]
[Processing: slam_toolbox]
--- stderr: slam_toolbox
CMake Warning (dev) at /opt/ros/humble/share/rosidl_generator_py/cmake/rosidl_generator_py_generate_interfaces.cmake:20 (find_package): Policy CMP0148 is not set: The FindPythonInterp and FindPythonLibs modules are removed. Run "cmake --help-policy CMP0148" for policy details. Use the cmake_policy command to set the policy and suppress this warning.
Call Stack (most recent call first): /opt/ros/humble/share/ament_cmake_core/cmake/core/ament_execute_extensions.cmake:48 (include) /opt/ros/humble/share/rosidl_cmake/cmake/rosidl_generate_interfaces.cmake:286 (ament_execute_extensions) CMakeLists.txt:96 (rosidl_generate_interfaces) This warning is for project developers. Use -Wno-dev to suppress it.
CMake Warning (dev) at /opt/ros/humble/share/python_cmake_module/cmake/Modules/FindPythonExtra.cmake:52 (find_package): Policy CMP0148 is not set: The FindPythonInterp and FindPythonLibs modules are removed. Run "cmake --help-policy CMP0148" for policy details. Use the cmake_policy command to set the policy and suppress this warning.
Call Stack (most recent call first): /opt/ros/humble/share/rosidl_generator_py/cmake/rosidl_generator_py_generate_interfaces.cmake:23 (find_package) /opt/ros/humble/share/ament_cmake_core/cmake/core/ament_execute_extensions.cmake:48 (include) /opt/ros/humble/share/rosidl_cmake/cmake/rosidl_generate_interfaces.cmake:286 (ament_execute_extensions) CMakeLists.txt:96 (rosidl_generate_interfaces) This warning is for project developers. Use -Wno-dev to suppress it.
CMake Warning (dev) at /opt/ros/humble/share/python_cmake_module/cmake/Modules/FindPythonExtra.cmake:140 (find_package): Policy CMP0148 is not set: The FindPythonInterp and FindPythonLibs modules are removed. Run "cmake --help-policy CMP0148" for policy details. Use the cmake_policy command to set the policy and suppress this warning.
Call Stack (most recent call first): /opt/ros/humble/share/rosidl_generator_py/cmake/rosidl_generator_py_generate_interfaces.cmake:23 (find_package) /opt/ros/humble/share/ament_cmake_core/cmake/core/ament_execute_extensions.cmake:48 (include) /opt/ros/humble/share/rosidl_cmake/cmake/rosidl_generate_interfaces.cmake:286 (ament_execute_extensions) CMakeLists.txt:96 (rosidl_generate_interfaces) This warning is for project developers. Use -Wno-dev to suppress it.
In file included from /home/imanuel/SLAM/src/solvers/ceres_solver.hpp:17, from /home/imanuel/SLAM/src/solvers/ceres_solver.cpp:9: /home/imanuel/SLAM/src/solvers/ceres_utils.h:50:48: warning: ‘LocalParameterization’ is deprecated: LocalParameterizations will be removed from the Ceres Solver API in version 2.2.0. Use Manifolds instead. [-Wdeprecated-declarations] 50 | static ceres::LocalParameterization Create() | ^ In file included from /home/imanuel/SLAM/src/solvers/ceres_solver.hpp:10, from /home/imanuel/SLAM/src/solvers/ceres_solver.cpp:9: /usr/local/include/ceres/local_parameterization.h:121:18: note: declared here 121 | CERES_EXPORT LocalParameterization { | ^ )’:
/home/imanuel/SLAM/src/solvers/ceressolver.cpp:341:13: error: ‘class ceres::Problem’ has no member named ‘SetParameterization’; did you mean ‘SetParameterLowerBound’?
341 | problem->SetParameterization(&node1it->second(2),
| ^
~~~~In file included from /home/imanuel/SLAM/src/solvers/ceres_solver.hpp:17, from /home/imanuel/SLAM/src/solvers/ceres_solver.cpp:9: /home/imanuel/SLAM/src/solvers/ceres_utils.h: In static member function ‘static ceres::LocalParameterization AngleLocalParameterization::Create()’: /home/imanuel/SLAM/src/solvers/ceres_utils.h:52:23: error: ‘AutoDiffLocalParameterization’ in namespace ‘ceres’ does not name a template type; did you mean ‘LocalParameterization’? 52 | return new ceres::AutoDiffLocalParameterization<AngleLocalParameterization, 1, 1>; | ^~~~~~~~~ | LocalParameterization /home/imanuel/SLAM/src/solvers/ceres_utils.h:52:79: error: expected primary-expression before ‘,’ token 52 | return new ceres::AutoDiffLocalParameterization<AngleLocalParameterization, 1, 1>; | ^ /home/imanuel/SLAM/src/solvers/ceres_utils.h:52:86: error: expected primary-expression before ‘;’ token 52 | return new ceres::AutoDiffLocalParameterization<AngleLocalParameterization, 1, 1>; | ^ In file included from /home/imanuel/SLAM/src/solvers/ceres_solver.cpp:9: /home/imanuel/SLAM/src/solvers/ceres_solver.hpp: At global scope: /home/imanuel/SLAM/src/solvers/ceres_solver.hpp:68:34: warning: ‘LocalParameterization’ is deprecated: LocalParameterizations will be removed from the Ceres Solver API in version 2.2.0. Use Manifolds instead. [-Wdeprecated-declarations] 68 | ceres::LocalParameterization angle_localparameterization; | ^~~~~~~~~ In file included from /home/imanuel/SLAM/src/solvers/ceres_solver.hpp:10, from /home/imanuel/SLAM/src/solvers/ceres_solver.cpp:9: /usr/local/include/ceres/local_parameterization.h:121:18: note: declared here 121 | CERES_EXPORT LocalParameterization { | ^~~~~/home/imanuel/SLAM/src/solvers/ceres_solver.cpp: In member function ‘virtual void solver_plugins::CeresSolver::AddConstraint(karto::Edge~~~~~~ | SetParameterLowerBound /home/imanuel/SLAM/src/solvers/ceressolver.cpp:343:13: error: ‘class ceres::Problem’ has no member named ‘SetParameterization’; did you mean ‘SetParameterLowerBound’? 343 | problem->SetParameterization(&node2it->second(2), | ^~~~~~~ | SetParameterLowerBound gmake[2]: [CMakeFiles/ceres_solver_plugin.dir/build.make:76: CMakeFiles/ceres_solver_plugin.dir/solvers/ceres_solver.cpp.o] Error 1 gmake[1]: [CMakeFiles/Makefile2:665: CMakeFiles/ceres_solver_plugin.dir/all] Error 2 gmake[1]: Waiting for unfinished jobs.... gmake: [Makefile:146: all] Error 2Failed <<< slam_toolbox [1min 4s, exited with code 2]
Summary: 0 packages finished [1min 5s] 1 package failed: slam_toolbox 1 package had stderr output: slam_toolbox `
Additional information
I had installed SLAM via the apt repo and tried running SLAM on clearpath's husky robot. It failed with the following terminal [output:]