18 CeresSolver::CeresSolver() :
19 nodes_(new
std::unordered_map<int,
Eigen::Vector3d>()),
20 blocks_(new
std::unordered_map<
std::size_t,
21 ceres::ResidualBlockId>()),
22 problem_(NULL), was_constant_set_(false)
26 std::string solver_type, preconditioner_type, dogleg_type,
27 trust_strategy, loss_fn, mode;
28 nh.
getParam(
"ceres_linear_solver", solver_type);
29 nh.
getParam(
"ceres_preconditioner", preconditioner_type);
30 nh.
getParam(
"ceres_dogleg_type", dogleg_type);
31 nh.
getParam(
"ceres_trust_strategy", trust_strategy);
32 nh.
getParam(
"ceres_loss_function", loss_fn);
44 if (loss_fn ==
"HuberLoss")
46 ROS_INFO(
"CeresSolver: Using HuberLoss loss function.");
49 else if (loss_fn ==
"CauchyLoss")
51 ROS_INFO(
"CeresSolver: Using CauchyLoss loss function.");
56 options_.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
57 if (solver_type ==
"SPARSE_SCHUR")
59 ROS_INFO(
"CeresSolver: Using SPARSE_SCHUR solver.");
60 options_.linear_solver_type = ceres::SPARSE_SCHUR;
62 else if (solver_type ==
"ITERATIVE_SCHUR")
64 ROS_INFO(
"CeresSolver: Using ITERATIVE_SCHUR solver.");
65 options_.linear_solver_type = ceres::ITERATIVE_SCHUR;
67 else if (solver_type ==
"CGNR")
69 ROS_INFO(
"CeresSolver: Using CGNR solver.");
70 options_.linear_solver_type = ceres::CGNR;
74 options_.preconditioner_type = ceres::JACOBI;
75 if (preconditioner_type ==
"IDENTITY")
77 ROS_INFO(
"CeresSolver: Using IDENTITY preconditioner.");
78 options_.preconditioner_type = ceres::IDENTITY;
80 else if (preconditioner_type ==
"SCHUR_JACOBI")
82 ROS_INFO(
"CeresSolver: Using SCHUR_JACOBI preconditioner.");
83 options_.preconditioner_type = ceres::SCHUR_JACOBI;
86 if (
options_.preconditioner_type == ceres::CLUSTER_JACOBI ||
87 options_.preconditioner_type == ceres::CLUSTER_TRIDIAGONAL)
91 options_.visibility_clustering_type = ceres::SINGLE_LINKAGE;
95 options_.trust_region_strategy_type = ceres::LEVENBERG_MARQUARDT;
96 if (trust_strategy ==
"DOGLEG")
98 ROS_INFO(
"CeresSolver: Using DOGLEG trust region strategy.");
99 options_.trust_region_strategy_type = ceres::DOGLEG;
103 if(
options_.trust_region_strategy_type == ceres::DOGLEG)
105 options_.dogleg_type = ceres::TRADITIONAL_DOGLEG;
106 if (dogleg_type ==
"SUBSPACE_DOGLEG")
108 ROS_INFO(
"CeresSolver: Using SUBSPACE_DOGLEG dogleg type.");
109 options_.dogleg_type = ceres::SUBSPACE_DOGLEG;
116 options_.parameter_tolerance = 1e-3;
118 options_.sparse_linear_algebra_library_type = ceres::SUITE_SPARSE;
119 options_.max_num_consecutive_invalid_steps = 3;
120 options_.max_consecutive_nonmonotonic_steps =
121 options_.max_num_consecutive_invalid_steps;
123 options_.use_nonmonotonic_steps =
true;
126 options_.min_relative_decrease = 1e-3;
128 options_.initial_trust_region_radius = 1e4;
129 options_.max_trust_region_radius = 1e8;
130 options_.min_trust_region_radius = 1e-16;
135 if(
options_.linear_solver_type == ceres::SPARSE_NORMAL_CHOLESKY)
140 if (mode == std::string(
"localization"))
177 ROS_ERROR(
"CeresSolver: Ceres was called when there are no nodes."
178 " This shouldn't happen.");
185 ROS_DEBUG(
"CeresSolver: Setting first node as a constant pose:"
195 ceres::Solver::Summary summary;
199 std::cout << summary.FullReport() <<
'\n';
202 if (!summary.IsSolutionUsable())
205 "Ceres could not find a usable solution to optimize.");
217 for ( iter; iter !=
nodes_->end(); ++iter )
219 pose.
SetX(iter->second(0));
220 pose.
SetY(iter->second(1));
222 corrections_.push_back(std::make_pair(iter->first, pose));
266 nodes_ =
new std::unordered_map<int, Eigen::Vector3d>();
267 blocks_ =
new std::unordered_map<std::size_t, ceres::ResidualBlockId>();
290 nodes_->insert(std::pair<int,Eigen::Vector3d>(
id,pose2d));
315 if (node1it ==
nodes_->end() ||
316 node2it ==
nodes_->end() || node1it == node2it)
318 ROS_WARN(
"CeresSolver: Failed to add constraint, could not find nodes.");
328 Eigen::Matrix3d information;
329 information(0, 0) = precisionMatrix(0, 0);
330 information(0, 1) = information(1, 0) = precisionMatrix(0, 1);
331 information(0, 2) = information(2, 0) = precisionMatrix(0, 2);
332 information(1, 1) = precisionMatrix(1, 1);
333 information(1, 2) = information(2, 1) = precisionMatrix(1, 2);
334 information(2, 2) = precisionMatrix(2, 2);
335 Eigen::Matrix3d sqrt_information = information.llt().matrixU();
339 pose2d(1), pose2d(2), sqrt_information);
340 ceres::ResidualBlockId block =
problem_->AddResidualBlock(
342 &node1it->second(0), &node1it->second(1), &node1it->second(2),
343 &node2it->second(0), &node2it->second(1), &node2it->second(2));
344 problem_->SetParameterization(&node1it->second(2),
346 problem_->SetParameterization(&node2it->second(2),
349 blocks_->insert(std::pair<std::size_t, ceres::ResidualBlockId>(
350 GetHash(node1, node2), block));
360 if (nodeit !=
nodes_->end())
362 if (
problem_->HasParameterBlock(&nodeit->second(0)) &&
363 problem_->HasParameterBlock(&nodeit->second(1)) &&
364 problem_->HasParameterBlock(&nodeit->second(2)))
366 problem_->RemoveParameterBlock(&nodeit->second(0));
367 problem_->RemoveParameterBlock(&nodeit->second(1));
368 problem_->RemoveParameterBlock(&nodeit->second(2));
369 ROS_DEBUG(
"RemoveNode: Removed node id %d", nodeit->first);
373 ROS_DEBUG(
"RemoveNode: Failed to remove parameter blocks for node id %d", nodeit->first);
379 ROS_ERROR(
"RemoveNode: Failed to find node matching id %i", (
int)
id);
388 std::unordered_map<std::size_t, ceres::ResidualBlockId>::iterator it_a =
390 std::unordered_map<std::size_t, ceres::ResidualBlockId>::iterator it_b =
394 problem_->RemoveResidualBlock(it_a->second);
397 else if (it_b !=
blocks_->end())
399 problem_->RemoveResidualBlock(it_b->second);
404 ROS_ERROR(
"RemoveConstraint: Failed to find residual block for %i %i",
405 (
int)sourceId, (
int)targetId);
417 double yaw_init = it->second(2);
419 it->second(2) += yaw_init;
431 pose = it->second(2);