Common expressions for solving geometry/slam/sfm problems. More...
#include <gtsam/nonlinear/expressions.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/geometry/Line3.h>
#include <gtsam/geometry/OrientedPlane3.h>
#include <gtsam/geometry/PinholeCamera.h>
Go to the source code of this file.
Namespaces | |
gtsam | |
traits | |
gtsam::internal | |
Typedefs | |
typedef Expression< Cal3_S2 > | gtsam::Cal3_S2_ |
typedef Expression< Cal3Bundler > | gtsam::Cal3Bundler_ |
typedef Expression< Line3 > | gtsam::Line3_ |
typedef Expression< OrientedPlane3 > | gtsam::OrientedPlane3_ |
typedef Expression< Point2 > | gtsam::Point2_ |
typedef Expression< Point3 > | gtsam::Point3_ |
typedef Expression< Pose2 > | gtsam::Pose2_ |
typedef Expression< Pose3 > | gtsam::Pose3_ |
typedef Expression< Rot2 > | gtsam::Rot2_ |
typedef Expression< Rot3 > | gtsam::Rot3_ |
typedef Expression< Unit3 > | gtsam::Unit3_ |
Functions | |
Point3_ | gtsam::cross (const Point3_ &a, const Point3_ &b) |
Double_ | gtsam::distance (const OrientedPlane3_ &p) |
Double_ | gtsam::dot (const Point3_ &a, const Point3_ &b) |
template<class CALIBRATION > | |
Pose3_ | gtsam::getPose (const Expression< PinholeCamera< CALIBRATION > > &cam) |
template<typename T > | |
gtsam::Expression< typename gtsam::traits< T >::TangentVector > | gtsam::logmap (const gtsam::Expression< T > &x1, const gtsam::Expression< T > &x2) |
logmap More... | |
Unit3_ | gtsam::normal (const OrientedPlane3_ &p) |
Point3_ | gtsam::normalize (const Point3_ &a) |
Point3_ | gtsam::point3 (const Unit3_ &v) |
Point2_ | gtsam::project (const Point3_ &p_cam) |
Expression version of PinholeBase::Project. More... | |
Point2_ | gtsam::project (const Unit3_ &p_cam) |
template<class CAMERA , class POINT > | |
Point2_ | gtsam::project2 (const Expression< CAMERA > &camera_, const Expression< POINT > &p_) |
template<class CALIBRATION , class POINT > | |
Point2_ | gtsam::project3 (const Pose3_ &x, const Expression< POINT > &p, const Expression< CALIBRATION > &K) |
template<class CAMERA , class POINT > | |
Point2 | gtsam::internal::project4 (const CAMERA &camera, const POINT &p, OptionalJacobian< 2, CAMERA::dimension > Dcam, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint) |
template<class CALIBRATION , class POINT > | |
Point2 | gtsam::internal::project6 (const Pose3 &x, const POINT &p, const CALIBRATION &K, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, CALIBRATION::dimension > Dcal) |
Double_ | gtsam::range (const Point2_ &p, const Point2_ &q) |
Point3_ | gtsam::rotate (const Rot3_ &x, const Point3_ &p) |
Unit3_ | gtsam::rotate (const Rot3_ &x, const Unit3_ &p) |
Rot3 | gtsam::internal::rotation (const Pose3 &pose, OptionalJacobian< 3, 6 > H) |
Rot3_ | gtsam::rotation (const Pose3_ &pose) |
Point3_ | gtsam::transformFrom (const Pose3_ &x, const Point3_ &p) |
Pose3_ | gtsam::transformPoseTo (const Pose3_ &p, const Pose3_ &q) |
Point2_ | gtsam::transformTo (const Pose2_ &x, const Point2_ &p) |
Line3_ | gtsam::transformTo (const Pose3_ &wTc, const Line3_ &wL) |
Point3_ | gtsam::transformTo (const Pose3_ &x, const Point3_ &p) |
Point3 | gtsam::internal::translation (const Pose3 &pose, OptionalJacobian< 3, 6 > H) |
Point3_ | gtsam::translation (const Pose3_ &pose) |
template<class CALIBRATION > | |
Point2_ | gtsam::uncalibrate (const Expression< CALIBRATION > &K, const Point2_ &xy_hat) |
Point3_ | gtsam::unrotate (const Rot3_ &x, const Point3_ &p) |
Unit3_ | gtsam::unrotate (const Rot3_ &x, const Unit3_ &p) |
Common expressions for solving geometry/slam/sfm problems.
Definition in file slam/expressions.h.