Even more concise by templating on second argument. Made return type explicit in HasRange/HasBearing.
parent
64d315df19
commit
df1886c56c
|
|
@ -94,7 +94,7 @@ struct traits<BearingRange<A1, A2> >
|
||||||
internal::ManifoldTraits<BearingRange<A1, A2> > {};
|
internal::ManifoldTraits<BearingRange<A1, A2> > {};
|
||||||
|
|
||||||
// Helper class for to implement Range traits for classes with a bearing method
|
// Helper class for to implement Range traits for classes with a bearing method
|
||||||
template <class A1, typename A2, class T = double>
|
template <class A1, typename A2, class T>
|
||||||
struct HasBearing {
|
struct HasBearing {
|
||||||
typedef T result_type;
|
typedef T result_type;
|
||||||
T operator()(
|
T operator()(
|
||||||
|
|
@ -106,7 +106,7 @@ struct HasBearing {
|
||||||
};
|
};
|
||||||
|
|
||||||
// Helper class for to implement Range traits for classes with a range method
|
// Helper class for to implement Range traits for classes with a range method
|
||||||
template <class A1, typename A2, class T = double>
|
template <class A1, typename A2, class T>
|
||||||
struct HasRange {
|
struct HasRange {
|
||||||
typedef T result_type;
|
typedef T result_type;
|
||||||
T operator()(
|
T operator()(
|
||||||
|
|
|
||||||
|
|
@ -393,14 +393,8 @@ template <>
|
||||||
struct traits<const CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
|
struct traits<const CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
|
||||||
|
|
||||||
// range traits, used in RangeFactor
|
// range traits, used in RangeFactor
|
||||||
template <>
|
template <typename T>
|
||||||
struct Range<CalibratedCamera, Point3> : HasRange<CalibratedCamera, Point3> {};
|
struct Range<CalibratedCamera, T> : HasRange<CalibratedCamera, T, double> {};
|
||||||
|
|
||||||
template <>
|
|
||||||
struct Range<CalibratedCamera, Pose3> : HasRange<CalibratedCamera, Pose3> {};
|
|
||||||
|
|
||||||
template <>
|
|
||||||
struct Range<CalibratedCamera, CalibratedCamera> : HasRange<CalibratedCamera, CalibratedCamera> {};
|
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -314,20 +314,7 @@ struct traits<const PinholeCamera<Calibration> >
|
||||||
: public internal::Manifold<PinholeCamera<Calibration> > {};
|
: public internal::Manifold<PinholeCamera<Calibration> > {};
|
||||||
|
|
||||||
// range traits, used in RangeFactor
|
// range traits, used in RangeFactor
|
||||||
template <typename Calibration>
|
template <typename Calibration, typename T>
|
||||||
struct Range<PinholeCamera<Calibration>, Point3>
|
struct Range<PinholeCamera<Calibration>, T> : HasRange<PinholeCamera<Calibration>, T, double> {};
|
||||||
: HasRange<PinholeCamera<Calibration>, Point3> {};
|
|
||||||
|
|
||||||
template <typename Calibration>
|
|
||||||
struct Range<PinholeCamera<Calibration>, Pose3>
|
|
||||||
: HasRange<PinholeCamera<Calibration>, Pose3> {};
|
|
||||||
|
|
||||||
template <typename CalibrationA, typename CalibrationB>
|
|
||||||
struct Range<PinholeCamera<CalibrationA>, PinholeCamera<CalibrationB> >
|
|
||||||
: HasRange<PinholeCamera<CalibrationA>, PinholeCamera<CalibrationB> > {};
|
|
||||||
|
|
||||||
template <typename Calibration>
|
|
||||||
struct Range<PinholeCamera<Calibration>, CalibratedCamera>
|
|
||||||
: HasRange<PinholeCamera<Calibration>, CalibratedCamera> {};
|
|
||||||
|
|
||||||
} // \ gtsam
|
} // \ gtsam
|
||||||
|
|
|
||||||
|
|
@ -298,17 +298,11 @@ template <>
|
||||||
struct traits<const Pose2> : public internal::LieGroup<Pose2> {};
|
struct traits<const Pose2> : public internal::LieGroup<Pose2> {};
|
||||||
|
|
||||||
// bearing and range traits, used in RangeFactor
|
// bearing and range traits, used in RangeFactor
|
||||||
template <>
|
template <typename T>
|
||||||
struct Bearing<Pose2, Point2> : HasBearing<Pose2, Point2, Rot2> {};
|
struct Bearing<Pose2, T> : HasBearing<Pose2, T, Rot2> {};
|
||||||
|
|
||||||
template <>
|
template <typename T>
|
||||||
struct Bearing<Pose2, Pose2> : HasBearing<Pose2, Pose2, Rot2> {};
|
struct Range<Pose2, T> : HasRange<Pose2, T, double> {};
|
||||||
|
|
||||||
template <>
|
|
||||||
struct Range<Pose2, Point2> : HasRange<Pose2, Point2> {};
|
|
||||||
|
|
||||||
template <>
|
|
||||||
struct Range<Pose2, Pose2> : HasRange<Pose2, Pose2> {};
|
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -342,10 +342,7 @@ struct traits<const Pose3> : public internal::LieGroup<Pose3> {};
|
||||||
template <>
|
template <>
|
||||||
struct Bearing<Pose3, Point3> : HasBearing<Pose3, Point3, Unit3> {};
|
struct Bearing<Pose3, Point3> : HasBearing<Pose3, Point3, Unit3> {};
|
||||||
|
|
||||||
template <>
|
template <typename T>
|
||||||
struct Range<Pose3, Point3> : HasRange<Pose3, Point3> {};
|
struct Range<Pose3, T> : HasRange<Pose3, T, double> {};
|
||||||
|
|
||||||
template <>
|
|
||||||
struct Range<Pose3, Pose3> : HasRange<Pose3, Pose3> {};
|
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
||||||
|
|
@ -137,17 +137,7 @@ template <>
|
||||||
struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {};
|
struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {};
|
||||||
|
|
||||||
// range traits, used in RangeFactor
|
// range traits, used in RangeFactor
|
||||||
template <>
|
template <typename T>
|
||||||
struct Range<SimpleCamera, Point3> : HasRange<SimpleCamera, Point3> {};
|
struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
|
||||||
|
|
||||||
template <>
|
|
||||||
struct Range<SimpleCamera, Pose3> : HasRange<SimpleCamera, Pose3> {};
|
|
||||||
|
|
||||||
template <>
|
|
||||||
struct Range<SimpleCamera, SimpleCamera> : HasRange<SimpleCamera, SimpleCamera> {};
|
|
||||||
|
|
||||||
template <typename Calibration>
|
|
||||||
struct Range<SimpleCamera, PinholeCamera<Calibration> >
|
|
||||||
: HasRange<SimpleCamera, PinholeCamera<Calibration> > {};
|
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
||||||
|
|
@ -19,6 +19,7 @@
|
||||||
#include <gtsam/sam/RangeFactor.h>
|
#include <gtsam/sam/RangeFactor.h>
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
||||||
#include <gtsam/geometry/Pose2.h>
|
#include <gtsam/geometry/Pose2.h>
|
||||||
|
#include <gtsam/geometry/SimpleCamera.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/base/serializationTestHelpers.h>
|
#include <gtsam/base/serializationTestHelpers.h>
|
||||||
#include <gtsam/base/TestableAssertions.h>
|
#include <gtsam/base/TestableAssertions.h>
|
||||||
|
|
@ -347,6 +348,14 @@ TEST(RangeFactor, Point3) {
|
||||||
CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9));
|
CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
// Do tests with SimpleCamera
|
||||||
|
TEST( RangeFactor, Camera) {
|
||||||
|
RangeFactor<SimpleCamera,Point3> factor1(poseKey, pointKey, measurement, model);
|
||||||
|
RangeFactor<SimpleCamera,Pose3> factor2(poseKey, pointKey, measurement, model);
|
||||||
|
RangeFactor<SimpleCamera,SimpleCamera> factor3(poseKey, pointKey, measurement, model);
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// Do a test with non GTSAM types
|
// Do a test with non GTSAM types
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue