#include <Point3.hpp>
Public Member Functions | |
void | absoluteValue () |
Set each element to the absolute value. More... | |
void | clampMax (const double max) |
clamp any values that are greater than make to max More... | |
void | clampMin (const double min) |
clamp any values that are less than min to min More... | |
void | clampMinMax (const double min, const double max) |
clamp any values greater than max to max, and any value less than min to min More... | |
Vector3d | cross (const Vector3d &v) |
Cross product between a point and vector. More... | |
EIGEN_STRONG_INLINE double * | data () |
double | distance (const Point3d &point) const |
double | distanceL1 (const Point3d &point) const |
L1 norm of two points. More... | |
double | distanceLinf (const Point3d &point) const |
double | distanceSquared (const Point3d &point) const |
Square of the distance between two ponts, . More... | |
EIGEN_STRONG_INLINE bool | epsilonEquals (const Point3d &point, const double epsilon) const |
bool | operator!= (const Point3d &rhs) |
template<typename T > | |
void | operator*= (const T scale) |
void | operator+= (const Vector3d &v) |
void | operator-= (const Vector3d &v) |
template<typename T > | |
void | operator/= (const T scale) |
Point3d & | operator= (const Point3d &other) |
bool | operator== (const Point3d &rhs) |
Point3d (const double x, const double y, const double z) | |
Point3d (const Point3d &point) | |
Point3d (const Vector3d &vector) | |
EIGEN_STRONG_INLINE | Point3d () |
EIGEN_STRONG_INLINE void | set (const std::vector< double > &vector) |
EIGEN_STRONG_INLINE void | set (const Point3d &point) |
void | set (const Math::Vector3d &v) |
void | set (const double x, const double y, const double z) |
EIGEN_STRONG_INLINE void | setToZero () |
void | transform (const Math::SpatialTransform &X) |
Performs in place point transform. Given a point, , this performs . More... | |
Point3d | transform_copy (const Math::SpatialTransform &X) |
EIGEN_STRONG_INLINE Math::Vector3d | vec () const |
EIGEN_STRONG_INLINE double & | x () |
EIGEN_STRONG_INLINE double | x () const |
EIGEN_STRONG_INLINE double & | y () |
EIGEN_STRONG_INLINE double | y () const |
EIGEN_STRONG_INLINE double & | z () |
EIGEN_STRONG_INLINE double | z () const |
virtual | ~Point3d () |
Protected Attributes | |
double | point [3] |
Definition at line 28 of file Point3.hpp.
|
inline |
Definition at line 31 of file Point3.hpp.
|
inline |
Definition at line 38 of file Point3.hpp.
|
inlineexplicit |
Definition at line 43 of file Point3.hpp.
|
inline |
Definition at line 47 of file Point3.hpp.
|
inlinevirtual |
Definition at line 51 of file Point3.hpp.
|
inline |
Set each element to the absolute value.
Definition at line 167 of file Point3.hpp.
|
inline |
clamp any values that are greater than make to max
max |
Definition at line 135 of file Point3.hpp.
|
inline |
clamp any values that are less than min to min
min |
Definition at line 113 of file Point3.hpp.
|
inline |
clamp any values greater than max to max, and any value less than min to min
min | |
max |
Definition at line 158 of file Point3.hpp.
Cross product between a point and vector.
v |
Definition at line 213 of file Point3.hpp.
|
inline |
Definition at line 264 of file Point3.hpp.
|
inline |
brief Distance between two points,
point |
Definition at line 193 of file Point3.hpp.
|
inline |
|
inline |
|
inline |
Square of the distance between two ponts, .
point |
Definition at line 179 of file Point3.hpp.
|
inline |
Compares if two points are within epsilon of each other
point | |
epsilon |
Definition at line 104 of file Point3.hpp.
|
inline |
Definition at line 308 of file Point3.hpp.
|
inline |
Definition at line 281 of file Point3.hpp.
|
inline |
Definition at line 313 of file Point3.hpp.
|
inline |
Definition at line 320 of file Point3.hpp.
|
inline |
Definition at line 290 of file Point3.hpp.
Definition at line 274 of file Point3.hpp.
|
inline |
Definition at line 298 of file Point3.hpp.
|
inline |
Definition at line 71 of file Point3.hpp.
|
inline |
Definition at line 76 of file Point3.hpp.
|
inline |
Definition at line 81 of file Point3.hpp.
|
inline |
Definition at line 86 of file Point3.hpp.
|
inline |
Definition at line 93 of file Point3.hpp.
|
inlinevirtual |
Performs in place point transform. Given a point, , this performs .
X |
Implements RobotDynamics::Math::TransformableGeometricObject.
Definition at line 59 of file Point3.hpp.
|
inline |
Definition at line 64 of file Point3.hpp.
|
inline |
Definition at line 269 of file Point3.hpp.
|
inline |
Definition at line 234 of file Point3.hpp.
|
inline |
Definition at line 239 of file Point3.hpp.
|
inline |
Definition at line 244 of file Point3.hpp.
|
inline |
Definition at line 249 of file Point3.hpp.
|
inline |
Definition at line 254 of file Point3.hpp.
|
inline |
Definition at line 259 of file Point3.hpp.
|
protected |
Definition at line 328 of file Point3.hpp.