gtsam/gtsam/geometry/Rot2.h

230 lines
6.0 KiB
C
Raw Normal View History

/* ----------------------------------------------------------------------------
2019-02-11 22:39:48 +08:00
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Rot2.h
* @brief 2D rotation
* @date Dec 9, 2009
* @author Frank Dellaert
*/
2011-06-14 00:55:31 +08:00
#pragma once
#include <gtsam/geometry/Point2.h>
#include <gtsam/base/Lie.h>
#include <boost/optional.hpp>
Feature/shonan averaging (#473) Shonan Rotation Averaging. 199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4). * prototyping weighted sampler * Moved WeightedSampler into its own header * Random now uses std header <random>. * Removed boost/random usage from linear and discrete directories * Made into class * Now using new WeightedSampler class * Inlined random direction generation * eradicated last vestiges of boost/random in gtsam_unstable * Added 3D example g2o file * Added Frobenius norm factors * Shonan averaging algorithm, using SOn class * Wrapping Frobenius and Shonan * Fixed issues with << * Use Builder parameters * Refactored Shonan interface * Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451 * ShonanAveragingParameters * New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij| * Fixed broken GetDimension for Lie groups with variable dimension. * Removed all but Shonan averaging factor and made everything work with new SOn * Just a single WormholeFactor, wrapped noise model * Use std <random> * comments/todos * added timing script * add script to process ShonanAveraging timing results * Now producing a CSV file * Parse csv file and make combined plot * Fixed range * change p value and set two flags on * input file path, all the csv files proceeses at the same time * add check convergence rate part * csv file have name according to input data name * correct one mistake in initialization * generate the convergence rate for each p value * add yticks for the bar plot * add noises to the measurements * test add noise * Basic structure for checkOptimalityAt * change optimizer method to cholesky * buildQ now working. Tests should be better but visually inspected. * multiple test with cholesky * back * computeLambda now works * make combined plots while make bar plot * Calculate minimum eigenvalue - the very expensive version * Exposed computeMinEigenValue * make plots and bar togenter * method change to jacobi * add time for check optimality, min_eigen_value, sub_bound * updated plot min_eigen value and subounds * Adding Spectra headers * David's min eigenvalue code inserted and made to compile. * Made it work * Made "run" method work. * add rim.g2o name * Fixed bug in shifting eigenvalues * roundSolution which replaces projectFrom * removed extra arguments * Added to wrapper * Add SOn to template lists * roundSolution delete the extra arguement p * only calculate p=5 and change to the correct way computing f_R * Fixed conflict and made Google-style name changes * prototype descent code and unit test for initializeWithDescent * add averaging cost/time part in processing data * initializewithDescent success in test * Formatting and find example rather than hardcode * Removed accidentally checked in cmake files * give value to xi by block * correct gradient descent * correct xi * } * Fix wrapper * Make Hat/Vee have alternating signs * MakeATangentVector helpder function * Fixed cmake files * changed sign * add line search * unit test for line search * test real data with line search * correct comment * Fix boost::uniform_real * add save .dat file * correct test case * add explanation * delete redundant cout * add name to .dat output file * correct checkR * add get poses_ in shonan * add Vector Point type for savig data * Remove cmake file which magically re-appeared?? * Switched to std random library. * Prepare Klaus test * Add klaus3.g2o data. * fix comment * Fix derivatives * Fixed broken GetDimension for Lie groups with variable dimension. * Fix SOn tests to report correct dimension * Added tests for Klaus3 data * Add runWithRandomKlaus test for shonan. * Finish runWithRandomKlaus unittest. * Correct datafile. * Correct the format. * Added measured and keys methods * Shonan works on Klaus data * Create dense versions for wrappers, for testing * Now store D, Q, and L * Remove another cmake file incorrectly checked in. * Found and fixed the bug in ComputeLambda ! * Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr. * Make FrobeniusFactor not use deprecated methods * FrobeniusWormholeFactor takes Rot3 as argument * Wrapped some more methods. * Wrapped more methods * Allow creating and populating BetweenFactorPose3s in python * New constructors for ShonanAveraging * add function of get measurements number * Remove option not to use noise model * wrap Use nrMeasurements * Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1) * Allow for Anchor index * Fix anchor bug * Change outside view to Rot3 rather than SO3 * Add Lift in SOn class * Make comet working * Small fixes * Delete extra function * Add SOn::Lift * Removed hardcoded flag * Moved Frobenius factor to gtsam from unstable * Added new tests and made an old regression pass again * Cleaned up formatting and some comments, added EXPORT directives * Throw exception if wrongly dimensioned values are given * static_cast and other throw * Fixed run-time dimension * Added gauge-constraining factor * LM parameters now passed in, added Gauge fixing * 2D test scaffold * Comments * Pre-allocated generators * Document API * Add optional weight * New prior weeights infrastructure * Made d a template parameter * Recursive Hat and RetractJacobian test * Added Spectra 0.9.0 to 3rdparty * Enabling 2D averaging * Templatized Wormhole factor * ignore xcode folder * Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4 * Simplifying constructors Moved file loading to tests (for now) All unit tests pass for d==3! * Templated some methods internally * Very generic parseToVector * refactored load2d * Very much improved FrobeniusWormholeFactor (Shonan) Jacobians * SO(2) averaging works ! * Templated parse methods * Switched to new Dataset paradigm * Moved Shonan to gtsam * Checked noise model is correctly gotten from file * Fixed covariance bug * Making Shonan wrapper work * Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm * Fixed wrong include * Simplified interface (removed irrelevant random inits) and fixed eigenvector test * Removed stray boost::none * Added citation as suggested by Jose * Made descent test deterministic * Fixed some comments, commented out flaky test Co-authored-by: Jing Wu <jingwu@gatech.edu> Co-authored-by: jingwuOUO <wujing2951@gmail.com> Co-authored-by: swang <swang736@gatech.edu> Co-authored-by: ss <ss> Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
#include <random>
namespace gtsam {
/**
* Rotation matrix
* NOTE: the angle theta is in radians unless explicitly stated
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Rot2 : public LieGroup<Rot2, 1> {
/** we store cos(theta) and sin(theta) */
double c_, s_;
2009-12-15 08:00:02 +08:00
/** normalize to make sure cos and sin form unit vector */
Rot2& normalize();
2012-01-10 02:52:39 +08:00
/** private constructor from cos/sin */
inline Rot2(double c, double s) : c_(c), s_(s) {}
public:
/// @name Constructors and named constructors
/// @{
/** default constructor, zero rotation */
Rot2() : c_(1.0), s_(0.0) {}
/** copy constructor */
Rot2(const Rot2& r) : Rot2(r.c_, r.s_) {}
/// Constructor from angle in radians == exponential map at identity
Rot2(double theta) : c_(cos(theta)), s_(sin(theta)) {}
/// Named constructor from angle in radians
static Rot2 fromAngle(double theta) {
return Rot2(theta);
}
/// Named constructor from angle in degrees
static Rot2 fromDegrees(double theta) {
static const double degree = M_PI / 180;
return fromAngle(theta * degree);
}
/// Named constructor from cos(theta),sin(theta) pair, will *not* normalize!
static Rot2 fromCosSin(double c, double s);
/**
* Named constructor with derivative
* Calculate relative bearing to a landmark in local coordinate frame
* @param d 2D location of landmark
* @param H optional reference for Jacobian
* @return 2D rotation \f$ \in SO(2) \f$
*/
static Rot2 relativeBearing(const Point2& d, OptionalJacobian<1,2> H =
boost::none);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
Feature/shonan averaging (#473) Shonan Rotation Averaging. 199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4). * prototyping weighted sampler * Moved WeightedSampler into its own header * Random now uses std header <random>. * Removed boost/random usage from linear and discrete directories * Made into class * Now using new WeightedSampler class * Inlined random direction generation * eradicated last vestiges of boost/random in gtsam_unstable * Added 3D example g2o file * Added Frobenius norm factors * Shonan averaging algorithm, using SOn class * Wrapping Frobenius and Shonan * Fixed issues with << * Use Builder parameters * Refactored Shonan interface * Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451 * ShonanAveragingParameters * New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij| * Fixed broken GetDimension for Lie groups with variable dimension. * Removed all but Shonan averaging factor and made everything work with new SOn * Just a single WormholeFactor, wrapped noise model * Use std <random> * comments/todos * added timing script * add script to process ShonanAveraging timing results * Now producing a CSV file * Parse csv file and make combined plot * Fixed range * change p value and set two flags on * input file path, all the csv files proceeses at the same time * add check convergence rate part * csv file have name according to input data name * correct one mistake in initialization * generate the convergence rate for each p value * add yticks for the bar plot * add noises to the measurements * test add noise * Basic structure for checkOptimalityAt * change optimizer method to cholesky * buildQ now working. Tests should be better but visually inspected. * multiple test with cholesky * back * computeLambda now works * make combined plots while make bar plot * Calculate minimum eigenvalue - the very expensive version * Exposed computeMinEigenValue * make plots and bar togenter * method change to jacobi * add time for check optimality, min_eigen_value, sub_bound * updated plot min_eigen value and subounds * Adding Spectra headers * David's min eigenvalue code inserted and made to compile. * Made it work * Made "run" method work. * add rim.g2o name * Fixed bug in shifting eigenvalues * roundSolution which replaces projectFrom * removed extra arguments * Added to wrapper * Add SOn to template lists * roundSolution delete the extra arguement p * only calculate p=5 and change to the correct way computing f_R * Fixed conflict and made Google-style name changes * prototype descent code and unit test for initializeWithDescent * add averaging cost/time part in processing data * initializewithDescent success in test * Formatting and find example rather than hardcode * Removed accidentally checked in cmake files * give value to xi by block * correct gradient descent * correct xi * } * Fix wrapper * Make Hat/Vee have alternating signs * MakeATangentVector helpder function * Fixed cmake files * changed sign * add line search * unit test for line search * test real data with line search * correct comment * Fix boost::uniform_real * add save .dat file * correct test case * add explanation * delete redundant cout * add name to .dat output file * correct checkR * add get poses_ in shonan * add Vector Point type for savig data * Remove cmake file which magically re-appeared?? * Switched to std random library. * Prepare Klaus test * Add klaus3.g2o data. * fix comment * Fix derivatives * Fixed broken GetDimension for Lie groups with variable dimension. * Fix SOn tests to report correct dimension * Added tests for Klaus3 data * Add runWithRandomKlaus test for shonan. * Finish runWithRandomKlaus unittest. * Correct datafile. * Correct the format. * Added measured and keys methods * Shonan works on Klaus data * Create dense versions for wrappers, for testing * Now store D, Q, and L * Remove another cmake file incorrectly checked in. * Found and fixed the bug in ComputeLambda ! * Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr. * Make FrobeniusFactor not use deprecated methods * FrobeniusWormholeFactor takes Rot3 as argument * Wrapped some more methods. * Wrapped more methods * Allow creating and populating BetweenFactorPose3s in python * New constructors for ShonanAveraging * add function of get measurements number * Remove option not to use noise model * wrap Use nrMeasurements * Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1) * Allow for Anchor index * Fix anchor bug * Change outside view to Rot3 rather than SO3 * Add Lift in SOn class * Make comet working * Small fixes * Delete extra function * Add SOn::Lift * Removed hardcoded flag * Moved Frobenius factor to gtsam from unstable * Added new tests and made an old regression pass again * Cleaned up formatting and some comments, added EXPORT directives * Throw exception if wrongly dimensioned values are given * static_cast and other throw * Fixed run-time dimension * Added gauge-constraining factor * LM parameters now passed in, added Gauge fixing * 2D test scaffold * Comments * Pre-allocated generators * Document API * Add optional weight * New prior weeights infrastructure * Made d a template parameter * Recursive Hat and RetractJacobian test * Added Spectra 0.9.0 to 3rdparty * Enabling 2D averaging * Templatized Wormhole factor * ignore xcode folder * Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4 * Simplifying constructors Moved file loading to tests (for now) All unit tests pass for d==3! * Templated some methods internally * Very generic parseToVector * refactored load2d * Very much improved FrobeniusWormholeFactor (Shonan) Jacobians * SO(2) averaging works ! * Templated parse methods * Switched to new Dataset paradigm * Moved Shonan to gtsam * Checked noise model is correctly gotten from file * Fixed covariance bug * Making Shonan wrapper work * Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm * Fixed wrong include * Simplified interface (removed irrelevant random inits) and fixed eigenvector test * Removed stray boost::none * Added citation as suggested by Jose * Made descent test deterministic * Fixed some comments, commented out flaky test Co-authored-by: Jing Wu <jingwu@gatech.edu> Co-authored-by: jingwuOUO <wujing2951@gmail.com> Co-authored-by: swang <swang736@gatech.edu> Co-authored-by: ss <ss> Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
/**
* Random, generates random angle \in [-p,pi]
* Example:
* std::mt19937 engine(42);
* Unit3 unit = Unit3::Random(engine);
*/
static Rot2 Random(std::mt19937 & rng);
/// @}
/// @name Testable
/// @{
/** print */
void print(const std::string& s = "theta") const;
/** equals with an tolerance */
bool equals(const Rot2& R, double tol = 1e-9) const;
/// @}
/// @name Group
/// @{
/** identity */
inline static Rot2 identity() { return Rot2(); }
/** The inverse rotation - negative angle */
Rot2 inverse() const { return Rot2(c_, -s_);}
/** Compose - make a new rotation by adding angles */
Rot2 operator*(const Rot2& R) const {
2013-06-06 07:40:05 +08:00
return fromCosSin(c_ * R.c_ - s_ * R.s_, s_ * R.c_ + c_ * R.s_);
}
/// @}
/// @name Lie Group
/// @{
/// Exponential map at identity - create a rotation from canonical coordinates
static Rot2 Expmap(const Vector1& v, ChartJacobian H = boost::none);
/// Log map at identity - return the canonical coordinates of this rotation
static Vector1 Logmap(const Rot2& r, ChartJacobian H = boost::none);
2014-12-24 04:37:28 +08:00
/** Calculate Adjoint map */
Matrix1 AdjointMap() const { return I_1x1; }
2014-04-30 04:18:52 +08:00
/// Left-trivialized derivative of the exponential map
2015-03-06 23:44:08 +08:00
static Matrix ExpmapDerivative(const Vector& /*v*/) {
return I_1x1;
2014-04-30 04:18:52 +08:00
}
/// Left-trivialized derivative inverse of the exponential map
2015-03-06 23:44:08 +08:00
static Matrix LogmapDerivative(const Vector& /*v*/) {
return I_1x1;
}
// Chart at origin simply uses exponential map and its inverse
struct ChartAtOrigin {
static Rot2 Retract(const Vector1& v, ChartJacobian H = boost::none) {
return Expmap(v, H);
}
static Vector1 Local(const Rot2& r, ChartJacobian H = boost::none) {
return Logmap(r, H);
}
};
using LieGroup<Rot2, 1>::inverse; // version with derivative
/// @}
/// @name Group Action on Point2
/// @{
/**
* rotate point from rotated coordinate frame to world \f$ p^w = R_c^w p^c \f$
*/
Point2 rotate(const Point2& p, OptionalJacobian<2, 1> H1 = boost::none,
OptionalJacobian<2, 2> H2 = boost::none) const;
/** syntactic sugar for rotate */
inline Point2 operator*(const Point2& p) const {
return rotate(p);
}
/**
* rotate point from world to rotated frame \f$ p^c = (R_c^w)^T p^w \f$
*/
Point2 unrotate(const Point2& p, OptionalJacobian<2, 1> H1 = boost::none,
OptionalJacobian<2, 2> H2 = boost::none) const;
/// @}
/// @name Standard Interface
/// @{
/// Creates a unit vector as a Point2
inline Point2 unit() const {
return Point2(c_, s_);
}
/** return angle (RADIANS) */
double theta() const {
return ::atan2(s_, c_);
}
/** return angle (DEGREES) */
double degrees() const {
const double degree = M_PI / 180;
return theta() / degree;
}
/** return cos */
inline double c() const {
return c_;
}
/** return sin */
inline double s() const {
return s_;
}
/** return 2*2 rotation matrix */
2014-11-30 21:32:52 +08:00
Matrix2 matrix() const;
/** return 2*2 transpose (inverse) rotation matrix */
Matrix2 transpose() const;
private:
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
2015-03-06 23:12:09 +08:00
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(c_);
ar & BOOST_SERIALIZATION_NVP(s_);
}
2014-10-22 00:02:33 +08:00
};
template<>
struct traits<Rot2> : public internal::LieGroup<Rot2> {};
template<>
struct traits<const Rot2> : public internal::LieGroup<Rot2> {};
} // gtsam