Line3.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
3  * Atlanta, Georgia 30332-0415
4  * All Rights Reserved
5  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
6  * See LICENSE for the license information
7  * -------------------------------------------------------------------------- */
8 
15 // \callgraph
16 
17 #pragma once
18 
19 #include <gtsam/geometry/Rot3.h>
20 #include <gtsam/geometry/Pose3.h>
21 
22 namespace gtsam {
23 
29 class Line3 {
30  private:
31  Rot3 R_; // Rotation of line about x and y in world frame
32  double a_, b_; // Intersection of line with the world x-y plane rotated by R_
33  // Also the closest point on line to origin
34  public:
35  enum { dimension = 4 };
36 
38  Line3() :
39  a_(0), b_(0) {}
40 
42  Line3(const Rot3 &R, const double a, const double b) :
43  R_(R), a_(a), b_(b) {}
44 
56  Line3 retract(const Vector4 &v,
57  OptionalJacobian<4, 4> Dp = boost::none,
58  OptionalJacobian<4, 4> Dv = boost::none) const;
59 
69  Vector4 localCoordinates(const Line3 &q,
70  OptionalJacobian<4, 4> Dp = boost::none,
71  OptionalJacobian<4, 4> Dq = boost::none) const;
72 
77  void print(const std::string &s = "") const;
78 
85  bool equals(const Line3 &l2, double tol = 10e-9) const;
86 
93  Unit3 project(OptionalJacobian<2, 4> Dline = boost::none) const;
94 
103  Point3 point(double distance = 0) const;
104 
108  inline Rot3 R() const {
109  return R_;
110  }
111 
115  inline double a() const {
116  return a_;
117  }
118 
122  inline double b() const {
123  return b_;
124  }
125 
134  friend Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
136  OptionalJacobian<4, 4> Dline);
137 };
138 
147 Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
148  OptionalJacobian<4, 6> Dpose = boost::none,
149  OptionalJacobian<4, 4> Dline = boost::none);
150 
151 template<>
152 struct traits<Line3> : public internal::Manifold<Line3> {};
153 
154 template<>
155 struct traits<const Line3> : public internal::Manifold<Line3> {};
156 }
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
friend Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
ArrayXcf v
Definition: Cwise_arg.cpp:1
gtsam::Key l2
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Vector4 localCoordinates(const Line3 &q, OptionalJacobian< 4, 4 > Dp=boost::none, OptionalJacobian< 4, 4 > Dq=boost::none) const
Definition: Line3.cpp:27
double a_
Definition: Line3.h:32
Line3 retract(const Vector4 &v, OptionalJacobian< 4, 4 > Dp=boost::none, OptionalJacobian< 4, 4 > Dv=boost::none) const
Definition: Line3.cpp:5
void print(const std::string &s="") const
Definition: Line3.cpp:49
Unit3 project(OptionalJacobian< 2, 4 > Dline=boost::none) const
Definition: Line3.cpp:61
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
EIGEN_DEVICE_FUNC const Scalar & q
double b() const
Definition: Line3.h:122
traits
Definition: chartTesting.h:28
Line3(const Rot3 &R, const double a, const double b)
Definition: Line3.h:42
bool equals(const Line3 &l2, double tol=10e-9) const
Definition: Line3.cpp:55
double b_
Definition: Line3.h:32
Rot3 R_
Definition: Line3.h:31
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
Point3 point(double distance=0) const
Definition: Line3.cpp:86
double a() const
Definition: Line3.h:115
3D Pose
Rot3 R() const
Definition: Line3.h:108
3D rotation represented as a rotation matrix or quaternion


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:31