Little things
parent
81b3b896be
commit
5ed2abd292
|
@ -249,12 +249,12 @@ public:
|
||||||
/// Return canonical coordinate
|
/// Return canonical coordinate
|
||||||
Vector localCoordinates(const CalibratedCamera& T2) const;
|
Vector localCoordinates(const CalibratedCamera& T2) const;
|
||||||
|
|
||||||
/// Lie group dimensionality
|
/// @deprecated
|
||||||
inline size_t dim() const {
|
inline size_t dim() const {
|
||||||
return 6;
|
return 6;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Lie group dimensionality
|
/// @deprecated
|
||||||
inline static size_t Dim() {
|
inline static size_t Dim() {
|
||||||
return 6;
|
return 6;
|
||||||
}
|
}
|
||||||
|
|
|
@ -22,7 +22,6 @@
|
||||||
#include <gtsam/geometry/CalibratedCamera.h>
|
#include <gtsam/geometry/CalibratedCamera.h>
|
||||||
#include <gtsam/geometry/Point2.h>
|
#include <gtsam/geometry/Point2.h>
|
||||||
#include <boost/make_shared.hpp>
|
#include <boost/make_shared.hpp>
|
||||||
#include <cmath>
|
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
@ -34,7 +33,9 @@ namespace gtsam {
|
||||||
template<typename Calibration>
|
template<typename Calibration>
|
||||||
class GTSAM_EXPORT PinholeBaseK: public PinholeBase {
|
class GTSAM_EXPORT PinholeBaseK: public PinholeBase {
|
||||||
|
|
||||||
public:
|
GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration)
|
||||||
|
|
||||||
|
public :
|
||||||
|
|
||||||
/// @name Standard Constructors
|
/// @name Standard Constructors
|
||||||
/// @{
|
/// @{
|
||||||
|
@ -92,10 +93,8 @@ public:
|
||||||
Dpose || Dpoint ? &Dpi_pn : 0);
|
Dpose || Dpoint ? &Dpi_pn : 0);
|
||||||
|
|
||||||
// If needed, apply chain rule
|
// If needed, apply chain rule
|
||||||
if (Dpose)
|
if (Dpose) *Dpose = Dpi_pn * (*Dpose);
|
||||||
*Dpose = Dpi_pn * *Dpose;
|
if (Dpoint) *Dpoint = Dpi_pn * (*Dpoint);
|
||||||
if (Dpoint)
|
|
||||||
*Dpoint = Dpi_pn * *Dpoint;
|
|
||||||
|
|
||||||
return pi;
|
return pi;
|
||||||
}
|
}
|
||||||
|
@ -246,10 +245,12 @@ public:
|
||||||
/// @name Advanced Constructors
|
/// @name Advanced Constructors
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
|
/// Init from 6D vector
|
||||||
explicit PinholePose(const Vector &v) :
|
explicit PinholePose(const Vector &v) :
|
||||||
Base(v), K_(new Calibration()) {
|
Base(v), K_(new Calibration()) {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// Init from Vector and calibration
|
||||||
PinholePose(const Vector &v, const Vector &K) :
|
PinholePose(const Vector &v, const Vector &K) :
|
||||||
Base(v), K_(new Calibration(K)) {
|
Base(v), K_(new Calibration(K)) {
|
||||||
}
|
}
|
||||||
|
@ -286,25 +287,23 @@ public:
|
||||||
/// @name Manifold
|
/// @name Manifold
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
/// Manifold 6
|
/// @deprecated
|
||||||
size_t dim() const {
|
size_t dim() const {
|
||||||
return 6;
|
return 6;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Manifold 6
|
/// @deprecated
|
||||||
static size_t Dim() {
|
static size_t Dim() {
|
||||||
return 6;
|
return 6;
|
||||||
}
|
}
|
||||||
|
|
||||||
typedef Eigen::Matrix<double, 6, 1> VectorK6;
|
|
||||||
|
|
||||||
/// move a cameras according to d
|
/// move a cameras according to d
|
||||||
PinholePose retract(const Vector6& d) const {
|
PinholePose retract(const Vector6& d) const {
|
||||||
return PinholePose(Base::pose().retract(d), K_);
|
return PinholePose(Base::pose().retract(d), K_);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// return canonical coordinate
|
/// return canonical coordinate
|
||||||
VectorK6 localCoordinates(const PinholePose& p) const {
|
Vector6 localCoordinates(const PinholePose& p) const {
|
||||||
return Base::pose().localCoordinates(p.Base::pose());
|
return Base::pose().localCoordinates(p.Base::pose());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue