#include <Line3.h>
|
double | a () const |
|
double | b () const |
|
bool | equals (const Line3 &l2, double tol=10e-9) const |
|
| Line3 () |
|
| Line3 (const Rot3 &R, const double a, const double b) |
|
Vector4 | localCoordinates (const Line3 &q, OptionalJacobian< 4, 4 > Dp=boost::none, OptionalJacobian< 4, 4 > Dq=boost::none) const |
|
Point3 | point (double distance=0) const |
|
void | print (const std::string &s="") const |
|
Unit3 | project (OptionalJacobian< 2, 4 > Dline=boost::none) const |
|
Rot3 | R () const |
|
Line3 | retract (const Vector4 &v, OptionalJacobian< 4, 4 > Dp=boost::none, OptionalJacobian< 4, 4 > Dv=boost::none) const |
|
Definition at line 29 of file Line3.h.
Default constructor is the Z axis
Definition at line 38 of file Line3.h.
gtsam::Line3::Line3 |
( |
const Rot3 & |
R, |
|
|
const double |
a, |
|
|
const double |
b |
|
) |
| |
|
inline |
Constructor for general line from (R, a, b)
Definition at line 42 of file Line3.h.
double gtsam::Line3::a |
( |
| ) |
const |
|
inline |
Return the x-coordinate of the intersection of the line with the xy plane.
Definition at line 115 of file Line3.h.
double gtsam::Line3::b |
( |
| ) |
const |
|
inline |
Return the y-coordinate of the intersection of the line with the xy plane.
Definition at line 122 of file Line3.h.
bool gtsam::Line3::equals |
( |
const Line3 & |
l2, |
|
|
double |
tol = 10e-9 |
|
) |
| const |
Check if two lines are equal
- Parameters
-
l2 | - line to be compared |
tol | : optional tolerance |
- Returns
- boolean - true if lines are equal
Definition at line 55 of file Line3.cpp.
The localCoordinates method is the inverse of retract and finds the difference between two lines in the tangent space. It computes v = q - p where q is an input line, p is this line and v is their difference in the tangent space.
- Parameters
-
- Returns
- v: difference in the tangent space
Definition at line 27 of file Line3.cpp.
Point3 gtsam::Line3::point |
( |
double |
distance = 0 | ) |
const |
Returns point on the line that is at a certain distance starting from the point where the rotated XY axis intersects the line.
- Parameters
-
distance | (can be positive or negative) - positive is the positive direction of the rotated z axis that forms the line. The default value of zero returns the point where the rotated XY axis intersects the line. |
- Returns
- Point on the line
Definition at line 86 of file Line3.cpp.
void gtsam::Line3::print |
( |
const std::string & |
s = "" | ) |
const |
Print R, a, b
- Parameters
-
s | optional starting string |
Definition at line 49 of file Line3.cpp.
Projecting a line to the image plane. Assumes this line is in camera frame.
- Parameters
-
- Returns
- Unit3 - projected line in image plane, in homogenous coordinates. We use Unit3 since it is a manifold with the right dimension.
Definition at line 61 of file Line3.cpp.
Rot3 gtsam::Line3::R |
( |
| ) |
const |
|
inline |
Return the rotation of the line.
Definition at line 108 of file Line3.h.
The retract method maps from the tangent space back to the manifold. The method q = p + v, where p is this line, v is an increment along the tangent space and q is the resulting line. The tangent space for the rotation of a line is only two dimensional - rotation about x and y
- Parameters
-
v | increment in tangent space |
Dp | increment of retraction with respect to this line |
Dv | Jacobian of retraction with respect to the increment |
- Returns
- q: resulting line after adding the increment and mapping to the manifold
Definition at line 5 of file Line3.cpp.
Transform a line from world to camera frame
- Parameters
-
- Returns
- Transformed line in camera frame
Definition at line 94 of file Line3.cpp.
The documentation for this class was generated from the following files: