(in branch) added DerivedValue base class to geometry objects
parent
6dde91f636
commit
0eaf241340
|
|
@ -18,6 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -27,7 +28,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Cal3Bundler {
|
||||
class Cal3Bundler : public DerivedValue<Cal3Bundler> {
|
||||
|
||||
private:
|
||||
double f_, k1_, k2_ ;
|
||||
|
|
|
|||
|
|
@ -18,6 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -27,7 +28,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Cal3DS2 {
|
||||
class Cal3DS2 : public DerivedValue<Cal3DS2> {
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
|||
|
|
@ -21,6 +21,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -30,7 +31,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Cal3_S2 {
|
||||
class Cal3_S2 : public DerivedValue<Cal3_S2> {
|
||||
private:
|
||||
double fx_, fy_, s_, u0_, v0_;
|
||||
|
||||
|
|
|
|||
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Cal3_S2Stereo: public Cal3_S2 {
|
||||
class Cal3_S2Stereo: public DerivedValue<Cal3_S2Stereo>, public Cal3_S2 {
|
||||
private:
|
||||
double b_;
|
||||
|
||||
|
|
|
|||
|
|
@ -18,6 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
|
||||
|
|
@ -35,7 +36,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class CalibratedCamera {
|
||||
class CalibratedCamera : public DerivedValue<CalibratedCamera> {
|
||||
private:
|
||||
Pose3 pose_; // 6DOF pose
|
||||
|
||||
|
|
|
|||
|
|
@ -8,6 +8,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/optional.hpp>
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
|
||||
|
|
@ -23,7 +25,7 @@ namespace gtsam {
|
|||
* \nosubgrouping
|
||||
*/
|
||||
template <typename Calibration>
|
||||
class CalibratedCameraT {
|
||||
class CalibratedCameraT : public DerivedValue<CalibratedCameraT<Calibration> > {
|
||||
private:
|
||||
Pose3 pose_; // 6DOF pose
|
||||
Calibration k_;
|
||||
|
|
|
|||
|
|
@ -18,6 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/CalibratedCamera.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
#include <gtsam/geometry/Cal3Bundler.h>
|
||||
|
|
@ -31,7 +32,7 @@ namespace gtsam {
|
|||
* \nosubgrouping
|
||||
*/
|
||||
template <typename Camera, typename Calibration>
|
||||
class GeneralCameraT {
|
||||
class GeneralCameraT : public DerivedValue<GeneralCameraT<Camera, Calibration> > {
|
||||
|
||||
private:
|
||||
Camera calibrated_; // Calibrated camera
|
||||
|
|
|
|||
|
|
@ -18,6 +18,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/base/Matrix.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
|
||||
|
|
@ -30,7 +32,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Point2 {
|
||||
class Point2 : DerivedValue<Point2> {
|
||||
public:
|
||||
/// dimension of the variable - used to autodetect sizes
|
||||
static const size_t dimension = 2;
|
||||
|
|
|
|||
|
|
@ -24,6 +24,7 @@
|
|||
#include <boost/serialization/nvp.hpp>
|
||||
|
||||
#include <gtsam/base/Matrix.h>
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -33,7 +34,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Point3 {
|
||||
class Point3 : public DerivedValue<Point3> {
|
||||
public:
|
||||
/// dimension of the variable - used to autodetect sizes
|
||||
static const size_t dimension = 3;
|
||||
|
|
|
|||
|
|
@ -22,6 +22,7 @@
|
|||
|
||||
#include <boost/optional.hpp>
|
||||
#include <gtsam/base/Matrix.h>
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/geometry/Rot2.h>
|
||||
|
||||
|
|
@ -32,7 +33,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Pose2 {
|
||||
class Pose2 : public DerivedValue<Pose2> {
|
||||
|
||||
public:
|
||||
static const size_t dimension = 3;
|
||||
|
|
|
|||
|
|
@ -22,6 +22,7 @@
|
|||
#define POSE3_DEFAULT_COORDINATES_MODE Pose3::FIRST_ORDER
|
||||
#endif
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/geometry/Rot3.h>
|
||||
|
||||
|
|
@ -34,7 +35,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Pose3 {
|
||||
class Pose3 : public DerivedValue<Pose3> {
|
||||
public:
|
||||
static const size_t dimension = 6;
|
||||
|
||||
|
|
|
|||
|
|
@ -19,6 +19,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/optional.hpp>
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -29,7 +31,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class Rot2 {
|
||||
class Rot2 : public DerivedValue<Rot2> {
|
||||
|
||||
public:
|
||||
/** get the dimension by the type */
|
||||
|
|
|
|||
|
|
@ -18,6 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/CalibratedCamera.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
|
||||
|
|
@ -29,7 +30,7 @@ namespace gtsam {
|
|||
* to produce measurements in pixels.
|
||||
* Not a sublass as a SimpleCamera *is not* a CalibratedCamera.
|
||||
*/
|
||||
class SimpleCamera {
|
||||
class SimpleCamera : public DerivedValue<SimpleCamera> {
|
||||
private:
|
||||
CalibratedCamera calibrated_; // Calibrated camera
|
||||
Cal3_S2 K_; // Calibration
|
||||
|
|
|
|||
|
|
@ -18,6 +18,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/tuple/tuple.hpp>
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Cal3_S2Stereo.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/StereoPoint2.h>
|
||||
|
|
|
|||
|
|
@ -18,6 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/DerivedValue.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -27,7 +28,7 @@ namespace gtsam {
|
|||
* @ingroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class StereoPoint2 {
|
||||
class StereoPoint2 : public DerivedValue<StereoPoint2> {
|
||||
public:
|
||||
static const size_t dimension = 3;
|
||||
private:
|
||||
|
|
|
|||
Loading…
Reference in New Issue