Go to the documentation of this file.
32 :
std::runtime_error(
"Stereo Cheirality Exception"),
64 inline constexpr
static auto dimension = 6;
87 void print(
const std::string&
s =
"")
const {
88 leftCamPose_.
print(
s +
".camera.");
89 K_->print(
s +
".calibration.");
103 inline size_t dim()
const {
108 static inline size_t Dim() {
133 return K_->baseline();
144 {}, OptionalJacobian<3, 3> H2 = {})
const;
153 Point3 backproject2(
const StereoPoint2&
z,
154 OptionalJacobian<3, 6> H1 = {},
155 OptionalJacobian<3, 3> H2 = {})
const;
168 OptionalJacobian<3, 3> H2 = {}, OptionalJacobian<3, 0> H3 =
180 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
181 friend class boost::serialization::access;
182 template<
class Archive>
183 void serialize(Archive & ar,
const unsigned int ) {
184 ar & BOOST_SERIALIZATION_NVP(leftCamPose_);
185 ar & BOOST_SERIALIZATION_NVP(K_);
const Cal3_S2Stereo & calibration() const
Return shared pointer to calibration.
Vector defaultErrorWhenTriangulatingBehindCamera() const
for Nonlinear Triangulation
const Pose3 & pose() const
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Cal3_S2Stereo::shared_ptr K_
StereoPoint2Vector MeasurementVector
StereoCheiralityException()
double baseline() const
baseline
std::vector< StereoPoint2 > StereoPoint2Vector
def retract(a, np.ndarray xi)
StereoCheiralityException(Key j)
Both ManifoldTraits and Testable.
static Point3 backproject(const Pose3 &pose, const Point2 &point, const double &depth)
bool equals(const StereoCamera &camera, double tol=1e-9) const
equals
Point2_ project2(const Expression< CAMERA > &camera_, const Expression< POINT > &p_)
void print(const std::string &s="") const
print with optional string
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
void print(const std::string &s="") const
print
Key nearbyVariable() const
static size_t Dim()
Dimensionality of the tangent space.
std::shared_ptr< Cal3_S2Stereo > shared_ptr
The most common 5DOF 3D->2D calibration + Stereo baseline.
StereoCamera()
Default constructor allocates a calibration!
A 2D stereo point (uL,uR,v)
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
StereoCamera retract(const Vector &v) const
Updates a with tangent space delta.
Vector6 localCoordinates(const StereoCamera &t2) const
Local coordinates of manifold neighborhood around current value.
The most common 5DOF 3D->2D calibration, stereo version.
size_t dim() const
Dimensionality of the tangent space.
Array< int, Dynamic, 1 > v
The matrix class, also used for vectors and row-vectors.
static const CalibratedCamera camera(kDefaultPose)
std::uint64_t Key
Integer nonlinear key type.
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:14:03