30 #include <boost/math/special_functions.hpp> 43 for(
const auto& factor: g) {
45 double rotationPrecision = 1.0;
49 Rij = pose3Between->
measured().rotation().matrix();
50 Vector precisions = Vector::Zero(6);
52 pose3Between->noiseModel()->whitenInPlace(precisions);
53 rotationPrecision = precisions[0];
55 cout <<
"Error in buildLinearOrientationGraph" << endl;
58 const auto&
keys = factor->keys();
61 M9.block(0,0,3,3) = Rij;
62 M9.block(3,3,3,3) = Rij;
63 M9.block(6,6,3,3) = Rij;
64 linearGraph.
add(key1, -I_9x9, key2, M9, Z_9x1, noiseModel::Isotropic::Precision(9, rotationPrecision));
69 (
Vector(9) << 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0)
71 noiseModel::Isotropic::Precision(9, 1));
77 Values InitializePose3::normalizeRelaxedRotations(
79 gttic(InitializePose3_computeOrientationsChordal);
82 for(
const auto& it: relaxedRot3) {
89 Rot3 initRot = Rot3::ClosestTo(M.transpose());
90 validRot3.
insert(key, initRot);
99 gttic(InitializePose3_buildPose3graph);
100 return initialize::buildPoseGraph<Pose3>(
graph);
104 Values InitializePose3::computeOrientationsChordal(
106 gttic(InitializePose3_computeOrientationsChordal);
115 return normalizeRelaxedRotations(relaxedRot3);
119 Values InitializePose3::computeOrientationsGradient(
121 const size_t maxIter,
const bool setRefFrame) {
122 gttic(InitializePose3_computeOrientationsGradient);
127 for(
const auto key_value: givenGuess) {
137 createSymbolicGraph(pose3Graph, &adjEdgesMap, &factorId2RotMap);
140 size_t maxNodeDeg = 0;
142 for(
const auto key_value: inverseRot) {
145 size_t currNodeDeg = (adjEdgesMap.at(key)).
size();
146 if(currNodeDeg > maxNodeDeg)
147 maxNodeDeg = currNodeDeg;
153 double a = (M_PI*
M_PI)/(2*f0);
155 double mu_max = maxNodeDeg * rho;
156 double stepsize = 2/mu_max;
161 for (it = 0; it < maxIter; it++) {
165 for (
const auto key_value : inverseRot) {
169 for (
const size_t& factorId : adjEdgesMap.at(key)) {
170 Rot3 Rij = factorId2RotMap.at(factorId);
172 auto factor = pose3Graph.
at(factorId);
173 const auto&
keys = factor->keys();
174 if (key ==
keys[0]) {
177 gradKey = gradKey + gradientTron(Ri, Rij * Rj, a, b);
178 }
else if (key ==
keys[1]) {
180 Rot3 Rj = inverseRot.at<
Rot3>(key0);
181 gradKey = gradKey + gradientTron(Ri, Rij.
between(Rj),
a,
b);
183 cout <<
"Error in gradient computation" << endl;
186 grad.
at(key) = stepsize * gradKey;
188 double normGradKey = (gradKey).norm();
189 if(normGradKey>maxGrad)
190 maxGrad = normGradKey;
195 inverseRot = inverseRot.retract(grad);
199 if (it>20 && maxGrad < 5
e-3)
206 for(
const auto key_value: inverseRot) {
213 estimateRot.insert(key, R.
inverse());
220 void InitializePose3::createSymbolicGraph(
224 for (
const auto& factor : pose3Graph) {
228 Rot3 Rij = pose3Between->measured().rotation();
229 factorId2RotMap->emplace(factorId, Rij);
231 Key key1 = pose3Between->key1();
232 if (adjEdgesMap->find(key1) != adjEdgesMap->end()) {
233 adjEdgesMap->at(key1).push_back(factorId);
235 vector<size_t> edge_id;
236 edge_id.push_back(factorId);
237 adjEdgesMap->emplace(key1, edge_id);
239 Key key2 = pose3Between->key2();
240 if (adjEdgesMap->find(key2) != adjEdgesMap->end()) {
241 adjEdgesMap->at(key2).push_back(factorId);
243 vector<size_t> edge_id;
244 edge_id.push_back(factorId);
245 adjEdgesMap->emplace(key2, edge_id);
248 cout <<
"Error in createSymbolicGraph" << endl;
258 double th = logRot.norm();
261 logRot = Rot3::Logmap(R1pert.
between(R2));
265 if (th > 1
e-5 && th == th) {
266 logRot = logRot / th;
272 double fdot = a*b*th*
exp(-b*th);
283 return computeOrientationsChordal(pose3Graph);
290 gttic(InitializePose3_computePoses);
291 return initialize::computePoses<Pose3>(initialRot, posegraph, singleIter);
296 const Values& givenGuess,
bool useGradient) {
297 gttic(InitializePose3_initialize);
307 orientations = computeOrientationsGradient(pose3Graph, givenGuess);
309 orientations = computeOrientationsChordal(pose3Graph);
Initialize Pose3 in a factor graph.
Matrix< RealScalar, Dynamic, Dynamic > M
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
void insert(Key j, const Value &val)
common code between lago.* (2D) and InitializePose3.* (3D)
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
std::map< Key, Rot3 > KeyRotMap
const VALUE & measured() const
return the measurement
NonlinearFactorGraph graph
static Values computePoses(const Values &initialRot, NonlinearFactorGraph *posegraph, bool singleIter=true)
void g(const string &key, int i)
GaussianFactorGraph buildLinearOrientationGraph(const vector< size_t > &spanningTreeIds, const vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap< Key > &tree)
Rot3 inverse() const
inverse of a rotation
const Symbol key1('v', 1)
std::map< Key, std::vector< size_t > > KeyVectorMap
void add(const GaussianFactor &factor)
Class compose(const Class &g) const
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
const sharedFactor at(size_t i) const
std::vector< float > Values
const Symbol key2('v', 2)
static constexpr Key kAnchorKey
Class between(const Class &g) const
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
std::uint64_t Key
Integer nonlinear key type.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation