RIT VEXU Core API
Loading...
Searching...
No Matches
Transform2d Class Reference

#include <transform2d.h>

Public Member Functions

constexpr Transform2d ()
 
 Transform2d (const Translation2d &translation, const Rotation2d &rotation)
 
 Transform2d (const double &x, const double &y, const Rotation2d &rotation)
 
 Transform2d (const double &x, const double &y, const double &radians)
 
 Transform2d (const Translation2d &translation, const double &radians)
 
 Transform2d (const Eigen::Vector3d &transform_vector)
 
 Transform2d (const Pose2d &start, const Pose2d &end)
 
Translation2d translation () const
 
double x () const
 
double y () const
 
Rotation2d rotation () const
 
Transform2d inverse () const
 
Transform2d operator* (const double &scalar) const
 
Transform2d operator/ (const double &scalar) const
 
Transform2d operator- () const
 
bool operator== (const Transform2d &other) const
 

Friends

std::ostream & operator<< (std::ostream &os, const Transform2d &transform)
 

Detailed Description

Class representing a transformation of a pose2d, or a linear difference between the components of poses.

Assumes conventional cartesian coordinate system: Looking down at the coordinate plane, +X is right +Y is up +Theta is counterclockwise

Constructor & Destructor Documentation

◆ Transform2d() [1/7]

Transform2d::Transform2d ( )
constexpr

Default Constructor for Transform2d

◆ Transform2d() [2/7]

Transform2d::Transform2d ( const Translation2d & translation,
const Rotation2d & rotation )

Constructs a transform given translation and rotation components.

Parameters
translationthe translational component of the transform.
rotationthe rotational component of the transform.

◆ Transform2d() [3/7]

Transform2d::Transform2d ( const double & x,
const double & y,
const Rotation2d & rotation )

Constructs a transform given translation and rotation components.

Parameters
xthe x component of the transform.
ythe y component of the transform.
rotationthe rotational component of the transform.

◆ Transform2d() [4/7]

Transform2d::Transform2d ( const double & x,
const double & y,
const double & radians )

Constructs a transform given translation and rotation components.

Parameters
xthe x component of the transform.
ythe y component of the transform.
radiansthe rotational component of the transform in radians.

◆ Transform2d() [5/7]

Transform2d::Transform2d ( const Translation2d & translation,
const double & radians )

Constructs a transform given translation and rotation components.

Parameters
translationthe translational component of the transform.
radiansthe rotational component of the transform in radians.

◆ Transform2d() [6/7]

Transform2d::Transform2d ( const Eigen::Vector3d & transform_vector)

Constructs a transform given translation and rotation components given as a vector.

Parameters
transform_vectorvector of the form [x, y, theta]

◆ Transform2d() [7/7]

Transform2d::Transform2d ( const Pose2d & start,
const Pose2d & end )

Constructs a transform given translation and rotation components.

Parameters
translationthe translational component of the transform.
rotationthe rotational component of the transform.

Member Function Documentation

◆ inverse()

Transform2d Transform2d::inverse ( ) const

Inverts the transform.

Returns
the inverted transform.

◆ operator*()

Transform2d Transform2d::operator* ( const double & scalar) const

Multiplies this transform by a scalar.

Parameters
scalarthe scalar to multiply this transform by.

◆ operator-()

Transform2d Transform2d::operator- ( ) const

Inverts the transform.

Returns
the inverted transform.

◆ operator/()

Transform2d Transform2d::operator/ ( const double & scalar) const

Divides this transform by a scalar.

Parameters
scalarthe scalar to divide this transform by.

◆ operator==()

bool Transform2d::operator== ( const Transform2d & other) const

Compares this to another transform.

Parameters
otherthe other transform to compare to.
Returns
true if the components are within 1e-9 of each other.

◆ rotation()

Rotation2d Transform2d::rotation ( ) const

Returns the rotational component of the transform.

Returns
the rotational component of the transform.

◆ translation()

Translation2d Transform2d::translation ( ) const

Returns the translational component of the transform.

Returns
the translational component of the transform.

◆ x()

double Transform2d::x ( ) const

Returns the x component of the transform.

Returns
the x component of the transform.

◆ y()

double Transform2d::y ( ) const

Returns the y component of the transform.

Returns
the y component of the transform.

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream & os,
const Transform2d & transform )
friend

Sends a transform to an output stream. Ex. std::cout << transform;

prints "Transform2d[dx: (value), dy: (value), drad: (radians), ddeg: (degrees)]"

Sends a transform to an output stream. Ex. std::cout << transform;

prints "Transform2d[x: (value), y: (value), rad: (radians), deg: (degrees)]"


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