Public Types | Public Member Functions | Private Attributes | Friends | List of all members
gtsam::Line3 Class Reference

#include <Line3.h>

Public Types

enum  { dimension = 4 }
 

Public Member Functions

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={}, OptionalJacobian< 4, 4 > Dq={}) const
 
Point3 point (double distance=0) const
 
void print (const std::string &s="") const
 
Unit3 project (OptionalJacobian< 2, 4 > Dline={}) const
 
Rot3 R () const
 
Line3 retract (const Vector4 &v, OptionalJacobian< 4, 4 > Dp={}, OptionalJacobian< 4, 4 > Dv={}) const
 

Private Attributes

double a_
 
double b_
 
Rot3 R_
 

Friends

Line3 transformTo (const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
 

Detailed Description

A 3D line (R,a,b) : (Rot3,Scalar,Scalar)

Definition at line 44 of file Line3.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
dimension 

Definition at line 50 of file Line3.h.

Constructor & Destructor Documentation

◆ Line3() [1/2]

gtsam::Line3::Line3 ( )
inline

Default constructor is the Z axis

Definition at line 53 of file Line3.h.

◆ Line3() [2/2]

gtsam::Line3::Line3 ( const Rot3 R,
const double  a,
const double  b 
)
inline

Constructor for general line from (R, a, b)

Definition at line 57 of file Line3.h.

Member Function Documentation

◆ a()

double gtsam::Line3::a ( ) const
inline

Return the x-coordinate of the intersection of the line with the xy plane.

Definition at line 130 of file Line3.h.

◆ b()

double gtsam::Line3::b ( ) const
inline

Return the y-coordinate of the intersection of the line with the xy plane.

Definition at line 137 of file Line3.h.

◆ equals()

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.

◆ localCoordinates()

Vector4 gtsam::Line3::localCoordinates ( const Line3 q,
OptionalJacobian< 4, 4 >  Dp = {},
OptionalJacobian< 4, 4 >  Dq = {} 
) const

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
qLine3 on manifold
DpOptionalJacobian of localCoordinates with respect to this line
DqOptionalJacobian of localCoordinates with respect to this line
Returns
v: difference in the tangent space

Definition at line 27 of file Line3.cpp.

◆ point()

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.

◆ print()

void gtsam::Line3::print ( const std::string &  s = "") const

Print R, a, b

Parameters
soptional starting string

Definition at line 49 of file Line3.cpp.

◆ project()

Unit3 gtsam::Line3::project ( OptionalJacobian< 2, 4 >  Dline = {}) const

Projecting a line to the image plane. Assumes this line is in camera frame.

Parameters
DlineOptionalJacobian of projected line with respect to this line
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.

◆ R()

Rot3 gtsam::Line3::R ( ) const
inline

Return the rotation of the line.

Definition at line 123 of file Line3.h.

◆ retract()

Line3 gtsam::Line3::retract ( const Vector4 &  v,
OptionalJacobian< 4, 4 >  Dp = {},
OptionalJacobian< 4, 4 >  Dv = {} 
) const

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
vincrement in tangent space
Dpincrement of retraction with respect to this line
DvJacobian 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.

Friends And Related Function Documentation

◆ transformTo

Line3 transformTo ( const Pose3 wTc,
const Line3 wL,
OptionalJacobian< 4, 6 >  Dpose,
OptionalJacobian< 4, 4 >  Dline 
)
friend

Transform a line from world to camera frame

Parameters
wTc- Pose3 of camera in world frame
wL- Line3 in world frame
Dpose- OptionalJacobian of transformed line with respect to p
Dline- OptionalJacobian of transformed line with respect to l
Returns
Transformed line in camera frame

Definition at line 94 of file Line3.cpp.

Member Data Documentation

◆ a_

double gtsam::Line3::a_
private

Definition at line 47 of file Line3.h.

◆ b_

double gtsam::Line3::b_
private

Definition at line 47 of file Line3.h.

◆ R_

Rot3 gtsam::Line3::R_
private

Definition at line 46 of file Line3.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:22