From ce7e357ea7ea4ecb0329a71de7bb5d856221b50a Mon Sep 17 00:00:00 2001 From: lcarlone Date: Thu, 26 Aug 2021 15:56:34 -0400 Subject: [PATCH] adding basic function, get ready for testing --- gtsam/geometry/SpericalCamera.cpp | 102 ++++++ gtsam/geometry/SpericalCamera.h | 173 +++++++++ gtsam/geometry/tests/testSphericalCamera.cpp | 354 +++++++++++++++++++ 3 files changed, 629 insertions(+) create mode 100644 gtsam/geometry/SpericalCamera.cpp create mode 100644 gtsam/geometry/SpericalCamera.h create mode 100644 gtsam/geometry/tests/testSphericalCamera.cpp diff --git a/gtsam/geometry/SpericalCamera.cpp b/gtsam/geometry/SpericalCamera.cpp new file mode 100644 index 000000000..9d412310c --- /dev/null +++ b/gtsam/geometry/SpericalCamera.cpp @@ -0,0 +1,102 @@ +/* ---------------------------------------------------------------------------- + + * 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 SphericalCamera.h + * @brief Calibrated camera with spherical projection + * @date Aug 26, 2021 + * @author Luca Carlone + */ + +#include + +using namespace std; + +namespace gtsam { + +/* ************************************************************************* */ +Matrix26 SphericalCamera::Dpose(const Point2& pn, double d) { +// // optimized version of derivatives, see CalibratedCamera.nb +// const double u = pn.x(), v = pn.y(); +// double uv = u * v, uu = u * u, vv = v * v; +// Matrix26 Dpn_pose; +// Dpn_pose << uv, -1 - uu, v, -d, 0, d * u, 1 + vv, -uv, -u, 0, -d, d * v; +// return Dpn_pose; +} + +/* ************************************************************************* */ +Matrix23 SphericalCamera::Dpoint(const Point2& pn, double d, const Matrix3& Rt) { +// // optimized version of derivatives, see CalibratedCamera.nb +// const double u = pn.x(), v = pn.y(); +// Matrix23 Dpn_point; +// Dpn_point << // +// Rt(0, 0) - u * Rt(2, 0), Rt(0, 1) - u * Rt(2, 1), Rt(0, 2) - u * Rt(2, 2), // +// /**/Rt(1, 0) - v * Rt(2, 0), Rt(1, 1) - v * Rt(2, 1), Rt(1, 2) - v * Rt(2, 2); +// Dpn_point *= d; +// return Dpn_point; +} + +/* ************************************************************************* */ +bool SphericalCamera::equals(const SphericalCamera &camera, double tol) const { + return pose_.equals(camera.pose(), tol); +} + +/* ************************************************************************* */ +void SphericalCamera::print(const string& s) const { + pose_.print(s + ".pose"); +} + +/* ************************************************************************* */ +pair SphericalCamera::projectSafe(const Point3& pw) const { + const Point3 pc = pose().transformTo(pw); + Unit3::FromPoint3(pc); + return make_pair(pn, pc.norm() > 1e-8); +} + +/* ************************************************************************* */ +Unit3 SphericalCamera::project2(const Point3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 3> Dpoint) const { + + Matrix3 Dtf_pose, Dtf_point; // calculated by transformTo if needed + const Point3 pc = pose().transformTo(pw, Dpoint ? &Dtf_pose : 0, Dpoint ? &Dtf_point : 0); + +#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION + if (pc.norm() <= 1e-8) + throw CheiralityException(); +#endif + Matrix Dunit; // calculated by FromPoint3 if needed + Unit3 pn = Unit3::FromPoint3(Point3(pc), Dpoint ? &Dunit : 0); + + if (Dpose) + *Dpose = Dunit * Dtf_pose; //2x3 * 3x6 = 2x6 + if (Dpoint) + *Dpoint = Dunit * Dtf_point; //2x3 * 3x3 = 2x3 + return pn; +} + +/* ************************************************************************* */ +Unit3 SphericalCamera::project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 2> Dpoint) const { + return project2(Point3(pw), Dpose, Dpoint); +} +/* ************************************************************************* */ +Point3 SphericalCamera::BackprojectFromCamera(const Unit3& pu, const double depth) { + return depth * pu; +} + +/* ************************************************************************* */ +Unit3 SphericalCamera::project(const Point3& point, + OptionalJacobian<2, 6> Dcamera, OptionalJacobian<2, 3> Dpoint) const { + return project2(point, Dcamera, Dpoint); +} + +/* ************************************************************************* */ +} diff --git a/gtsam/geometry/SpericalCamera.h b/gtsam/geometry/SpericalCamera.h new file mode 100644 index 000000000..e3ae10c23 --- /dev/null +++ b/gtsam/geometry/SpericalCamera.h @@ -0,0 +1,173 @@ +/* ---------------------------------------------------------------------------- + + * 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 SphericalCamera.h + * @brief Calibrated camera with spherical projection + * @date Aug 26, 2021 + * @author Luca Carlone + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +/** + * A spherical camera class that has a Pose3 and measures bearing vectors + * @addtogroup geometry + * \nosubgrouping + */ +class GTSAM_EXPORT SphericalCamera { + +public: + + enum { + dimension = 6 + }; + + typedef Point2 Measurement; + typedef Point2Vector MeasurementVector; + +private: + + Pose3 pose_; ///< 3D pose of camera + +protected: + + /// @name Derivatives + /// @{ + +// /** +// * Calculate Jacobian with respect to pose +// * @param pn projection in normalized coordinates +// * @param d disparity (inverse depth) +// */ +// static Matrix26 Dpose(const Point2& pn, double d); +// +// /** +// * Calculate Jacobian with respect to point +// * @param pn projection in normalized coordinates +// * @param d disparity (inverse depth) +// * @param Rt transposed rotation matrix +// */ +// static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt); +// +// /// @} + +public: + + /// @} + /// @name Standard Constructors + /// @{ + + /// Default constructor + SphericalCamera() {} + + /// Constructor with pose + explicit SphericalCamera(const Pose3& pose) : pose_(pose) {} + + /// @} + /// @name Advanced Constructors + /// @{ + explicit SphericalCamera(const Vector& v) : pose_(Pose3::Expmap(v)) {} + + /// Default destructor + virtual ~SphericalCamera() = default; + + /// @} + /// @name Testable + /// @{ + + /// assert equality up to a tolerance + bool equals(const SphericalCamera &camera, double tol = 1e-9) const; + + /// print + virtual void print(const std::string& s = "SphericalCamera") const; + + /// @} + /// @name Standard Interface + /// @{ + + /// return pose, constant version + const Pose3& pose() const { + return pose_; + } + + /// get rotation + const Rot3& rotation() const { + return pose_.rotation(); + } + + /// get translation + const Point3& translation() const { + return pose_.translation(); + } + +// /// return pose, with derivative +// const Pose3& getPose(OptionalJacobian<6, 6> H) const; + + /// @} + /// @name Transformations and measurement functions + /// @{ + + /// Project a point into the image and check depth + std::pair projectSafe(const Point3& pw) const; + + /** Project point into the image + * (note: there is no CheiralityException for a spherical camera) + * @param point 3D point in world coordinates + * @return the intrinsic coordinates of the projected point + */ + Unit3 project2(const Point3& point, OptionalJacobian<2, 6> Dpose = + boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const; + + /** Project point at infinity into the image + * (note: there is no CheiralityException for a spherical camera) + * @param point 3D point in world coordinates + * @return the intrinsic coordinates of the projected point + */ + Unit3 project2(const Unit3& point, + OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 2> Dpoint = boost::none) const; + + /// backproject a 2-dimensional point to a 3-dimensional point at given depth + static Point3 BackprojectFromCamera(const Point2& p, const double depth, + OptionalJacobian<3, 2> Dpoint = boost::none, + OptionalJacobian<3, 1> Ddepth = boost::none); + + /** Project point into the image + * (note: there is no CheiralityException for a spherical camera) + * @param point 3D point in world coordinates + * @return the intrinsic coordinates of the projected point + */ + Unit3 project(const Point3& point, OptionalJacobian<2, 6> Dpose = + boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const; + /// @} + +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int /*version*/) { + ar & BOOST_SERIALIZATION_NVP(pose_); + } +}; +// end of class PinholeBase diff --git a/gtsam/geometry/tests/testSphericalCamera.cpp b/gtsam/geometry/tests/testSphericalCamera.cpp new file mode 100644 index 000000000..0679a4609 --- /dev/null +++ b/gtsam/geometry/tests/testSphericalCamera.cpp @@ -0,0 +1,354 @@ +/* ---------------------------------------------------------------------------- + + * 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 testPinholeCamera.cpp + * @author Frank Dellaert + * @brief test PinholeCamera class + */ + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +using namespace std::placeholders; +using namespace std; +using namespace gtsam; + +typedef PinholeCamera Camera; + +static const Cal3_S2 K(625, 625, 0, 0, 0); + +static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5)); +static const Camera camera(pose, K); + +static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5)); +static const Camera camera1(pose1, K); + +static const Point3 point1(-0.08,-0.08, 0.0); +static const Point3 point2(-0.08, 0.08, 0.0); +static const Point3 point3( 0.08, 0.08, 0.0); +static const Point3 point4( 0.08,-0.08, 0.0); + +static const Unit3 point1_inf(-0.16,-0.16, -1.0); +static const Unit3 point2_inf(-0.16, 0.16, -1.0); +static const Unit3 point3_inf( 0.16, 0.16, -1.0); +static const Unit3 point4_inf( 0.16,-0.16, -1.0); + +/* ************************************************************************* */ +TEST( PinholeCamera, constructor) +{ + EXPECT(assert_equal( K, camera.calibration())); + EXPECT(assert_equal( pose, camera.pose())); +} + +//****************************************************************************** +TEST(PinholeCamera, Create) { + + Matrix actualH1, actualH2; + EXPECT(assert_equal(camera, Camera::Create(pose,K, actualH1, actualH2))); + + // Check derivative + std::function f = // + std::bind(Camera::Create, std::placeholders::_1, std::placeholders::_2, + boost::none, boost::none); + Matrix numericalH1 = numericalDerivative21(f,pose,K); + EXPECT(assert_equal(numericalH1, actualH1, 1e-9)); + Matrix numericalH2 = numericalDerivative22(f,pose,K); + EXPECT(assert_equal(numericalH2, actualH2, 1e-8)); +} + +//****************************************************************************** +TEST(PinholeCamera, Pose) { + + Matrix actualH; + EXPECT(assert_equal(pose, camera.getPose(actualH))); + + // Check derivative + std::function f = // + std::bind(&Camera::getPose, std::placeholders::_1, boost::none); + Matrix numericalH = numericalDerivative11(f,camera); + EXPECT(assert_equal(numericalH, actualH, 1e-9)); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, level2) +{ + // Create a level camera, looking in Y-direction + Pose2 pose2(0.4,0.3,M_PI/2.0); + Camera camera = Camera::Level(K, pose2, 0.1); + + // expected + Point3 x(1,0,0),y(0,0,-1),z(0,1,0); + Rot3 wRc(x,y,z); + Pose3 expected(wRc,Point3(0.4,0.3,0.1)); + EXPECT(assert_equal( camera.pose(), expected)); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, lookat) +{ + // Create a level camera, looking in Y-direction + Point3 C(10,0,0); + Camera camera = Camera::Lookat(C, Point3(0,0,0), Point3(0,0,1)); + + // expected + Point3 xc(0,1,0),yc(0,0,-1),zc(-1,0,0); + Pose3 expected(Rot3(xc,yc,zc),C); + EXPECT(assert_equal(camera.pose(), expected)); + + Point3 C2(30,0,10); + Camera camera2 = Camera::Lookat(C2, Point3(0,0,0), Point3(0,0,1)); + + Matrix R = camera2.pose().rotation().matrix(); + Matrix I = trans(R)*R; + EXPECT(assert_equal(I, I_3x3)); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, project) +{ + EXPECT(assert_equal( camera.project(point1), Point2(-100, 100) )); + EXPECT(assert_equal( camera.project(point2), Point2(-100, -100) )); + EXPECT(assert_equal( camera.project(point3), Point2( 100, -100) )); + EXPECT(assert_equal( camera.project(point4), Point2( 100, 100) )); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, backproject) +{ + EXPECT(assert_equal( camera.backproject(Point2(-100, 100), 0.5), point1)); + EXPECT(assert_equal( camera.backproject(Point2(-100, -100), 0.5), point2)); + EXPECT(assert_equal( camera.backproject(Point2( 100, -100), 0.5), point3)); + EXPECT(assert_equal( camera.backproject(Point2( 100, 100), 0.5), point4)); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, backprojectInfinity) +{ + EXPECT(assert_equal( camera.backprojectPointAtInfinity(Point2(-100, 100)), point1_inf)); + EXPECT(assert_equal( camera.backprojectPointAtInfinity(Point2(-100, -100)), point2_inf)); + EXPECT(assert_equal( camera.backprojectPointAtInfinity(Point2( 100, -100)), point3_inf)); + EXPECT(assert_equal( camera.backprojectPointAtInfinity(Point2( 100, 100)), point4_inf)); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, backproject2) +{ + Point3 origin(0,0,0); + Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.); // a camera1 looking down + Camera camera(Pose3(rot, origin), K); + + Point3 actual = camera.backproject(Point2(0,0), 1.); + Point3 expected(0., 1., 0.); + pair x = camera.projectSafe(expected); + + EXPECT(assert_equal(expected, actual)); + EXPECT(assert_equal(Point2(0,0), x.first)); + EXPECT(x.second); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, backprojectInfinity2) +{ + Point3 origin(0,0,0); + Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.); // a camera1 looking down + Camera camera(Pose3(rot, origin), K); + + Unit3 actual = camera.backprojectPointAtInfinity(Point2(0,0)); + Unit3 expected(0., 1., 0.); + Point2 x = camera.project(expected); + + EXPECT(assert_equal(expected, actual)); + EXPECT(assert_equal(Point2(0,0), x)); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, backprojectInfinity3) +{ + Point3 origin(0,0,0); + Rot3 rot(1., 0., 0., 0., 1., 0., 0., 0., 1.); // identity + Camera camera(Pose3(rot, origin), K); + + Unit3 actual = camera.backprojectPointAtInfinity(Point2(0,0)); + Unit3 expected(0., 0., 1.); + Point2 x = camera.project(expected); + + EXPECT(assert_equal(expected, actual)); + EXPECT(assert_equal(Point2(0,0), x)); +} + +/* ************************************************************************* */ +static Point2 project3(const Pose3& pose, const Point3& point, const Cal3_S2& cal) { + return Camera(pose,cal).project(point); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, Dproject) +{ + Matrix Dpose, Dpoint, Dcal; + Point2 result = camera.project(point1, Dpose, Dpoint, Dcal); + Matrix numerical_pose = numericalDerivative31(project3, pose, point1, K); + Matrix Hexpected2 = numericalDerivative32(project3, pose, point1, K); + Matrix numerical_cal = numericalDerivative33(project3, pose, point1, K); + EXPECT(assert_equal(Point2(-100, 100), result)); + EXPECT(assert_equal(numerical_pose, Dpose, 1e-7)); + EXPECT(assert_equal(Hexpected2, Dpoint, 1e-7)); + EXPECT(assert_equal(numerical_cal, Dcal, 1e-7)); +} + +/* ************************************************************************* */ +static Point2 projectInfinity3(const Pose3& pose, const Unit3& point3D, const Cal3_S2& cal) { + return Camera(pose,cal).project(point3D); +} + +TEST( PinholeCamera, Dproject_Infinity) +{ + Matrix Dpose, Dpoint, Dcal; + Unit3 point3D(point1.x(), point1.y(), -10.0); // a point in front of the camera1 + + // test Projection + Point2 actual = camera.project(point3D, Dpose, Dpoint, Dcal); + Point2 expected(-5.0, 5.0); + EXPECT(assert_equal(actual, expected, 1e-7)); + + // test Jacobians + Matrix numerical_pose = numericalDerivative31(projectInfinity3, pose, point3D, K); + Matrix Hexpected2 = numericalDerivative32(projectInfinity3, pose, point3D, K); + Matrix numerical_point2x2 = Hexpected2.block(0,0,2,2); // only the direction to the point matters + Matrix numerical_cal = numericalDerivative33(projectInfinity3, pose, point3D, K); + EXPECT(assert_equal(numerical_pose, Dpose, 1e-7)); + EXPECT(assert_equal(numerical_point2x2, Dpoint, 1e-7)); + EXPECT(assert_equal(numerical_cal, Dcal, 1e-7)); +} + +/* ************************************************************************* */ +static Point2 project4(const Camera& camera, const Point3& point) { + return camera.project2(point); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, Dproject2) +{ + Matrix Dcamera, Dpoint; + Point2 result = camera.project2(point1, Dcamera, Dpoint); + Matrix Hexpected1 = numericalDerivative21(project4, camera, point1); + Matrix Hexpected2 = numericalDerivative22(project4, camera, point1); + EXPECT(assert_equal(result, Point2(-100, 100) )); + EXPECT(assert_equal(Hexpected1, Dcamera, 1e-7)); + EXPECT(assert_equal(Hexpected2, Dpoint, 1e-7)); +} + +/* ************************************************************************* */ +// Add a test with more arbitrary rotation +TEST( PinholeCamera, Dproject3) +{ + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Camera camera(pose1); + Matrix Dpose, Dpoint; + camera.project2(point1, Dpose, Dpoint); + Matrix numerical_pose = numericalDerivative21(project4, camera, point1); + Matrix numerical_point = numericalDerivative22(project4, camera, point1); + CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); +} + +/* ************************************************************************* */ +static double range0(const Camera& camera, const Point3& point) { + return camera.range(point); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, range0) { + Matrix D1; Matrix D2; + double result = camera.range(point1, D1, D2); + Matrix Hexpected1 = numericalDerivative21(range0, camera, point1); + Matrix Hexpected2 = numericalDerivative22(range0, camera, point1); + EXPECT_DOUBLES_EQUAL(distance3(point1, camera.pose().translation()), result, + 1e-9); + EXPECT(assert_equal(Hexpected1, D1, 1e-7)); + EXPECT(assert_equal(Hexpected2, D2, 1e-7)); +} + +/* ************************************************************************* */ +static double range1(const Camera& camera, const Pose3& pose) { + return camera.range(pose); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, range1) { + Matrix D1; Matrix D2; + double result = camera.range(pose1, D1, D2); + Matrix Hexpected1 = numericalDerivative21(range1, camera, pose1); + Matrix Hexpected2 = numericalDerivative22(range1, camera, pose1); + EXPECT_DOUBLES_EQUAL(1, result, 1e-9); + EXPECT(assert_equal(Hexpected1, D1, 1e-7)); + EXPECT(assert_equal(Hexpected2, D2, 1e-7)); +} + +/* ************************************************************************* */ +typedef PinholeCamera Camera2; +static const Cal3Bundler K2(625, 1e-3, 1e-3); +static const Camera2 camera2(pose1, K2); +static double range2(const Camera& camera, const Camera2& camera2) { + return camera.range(camera2); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, range2) { + Matrix D1; Matrix D2; + double result = camera.range(camera2, D1, D2); + Matrix Hexpected1 = numericalDerivative21(range2, camera, camera2); + Matrix Hexpected2 = numericalDerivative22(range2, camera, camera2); + EXPECT_DOUBLES_EQUAL(1, result, 1e-9); + EXPECT(assert_equal(Hexpected1, D1, 1e-7)); + EXPECT(assert_equal(Hexpected2, D2, 1e-7)); +} + +/* ************************************************************************* */ +static const CalibratedCamera camera3(pose1); +static double range3(const Camera& camera, const CalibratedCamera& camera3) { + return camera.range(camera3); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, range3) { + Matrix D1; Matrix D2; + double result = camera.range(camera3, D1, D2); + Matrix Hexpected1 = numericalDerivative21(range3, camera, camera3); + Matrix Hexpected2 = numericalDerivative22(range3, camera, camera3); + EXPECT_DOUBLES_EQUAL(1, result, 1e-9); + EXPECT(assert_equal(Hexpected1, D1, 1e-7)); + EXPECT(assert_equal(Hexpected2, D2, 1e-7)); +} + +/* ************************************************************************* */ +TEST( PinholeCamera, Cal3Bundler) { + Cal3Bundler calibration; + Pose3 wTc; + PinholeCamera camera(wTc, calibration); + Point2 p(50, 100); + camera.backproject(p, 10); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ + +