Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
fcl::ScrewMotion< S > Class Template Reference

#include <bv_motion_bound_visitor.h>

Public Member Functions

computeMotionBound (const BVMotionBoundVisitor< S > &mb_visitor) const
 Compute the motion bound for a bounding volume along a given direction n, which is defined in the visitor. More...
 
computeMotionBound (const TriangleMotionBoundVisitor< S > &mb_visitor) const
 Compute the motion bound for a triangle along a given direction n, which is defined in the visitor. More...
 
getAngularVelocity () const
 
const Vector3< S > & getAxis () const
 
const Vector3< S > & getAxisOrigin () const
 
void getCurrentTransform (Transform3< S > &tf_) const
 Get the rotation and translation in current step. More...
 
getLinearVelocity () const
 
void getTaylorModel (TMatrix3< S > &tm, TVector3< S > &tv) const
 
bool integrate (S dt) const
 Integrate the motion from 0 to dt We compute the current transformation from zero point instead of from last integrate time, for precision. More...
 
 ScrewMotion ()
 Default transformations are all identities. More...
 
 ScrewMotion (const Matrix3< S > &R1, const Vector3< S > &T1, const Matrix3< S > &R2, const Vector3< S > &T2)
 Construct motion from the initial rotation/translation and goal rotation/translation. More...
 
 ScrewMotion (const Transform3< S > &tf1_, const Transform3< S > &tf2_)
 Construct motion from the initial transform and goal transform. More...
 

Protected Member Functions

Quaternion< S > absoluteRotation (S dt) const
 
void computeScrewParameter ()
 
Quaternion< S > deltaRotation (S dt) const
 

Protected Attributes

angular_vel
 angular velocity More...
 
Vector3< S > axis
 screw axis More...
 
linear_vel
 linear velocity along the axis More...
 
Vector3< S > p
 A point on the axis. More...
 
Transform3< S > tf
 The transformation at current time t. More...
 
Transform3< S > tf1
 The transformation at time 0. More...
 
Transform3< S > tf2
 The transformation at time 1. More...
 

Detailed Description

template<typename S>
class fcl::ScrewMotion< S >

Definition at line 51 of file bv_motion_bound_visitor.h.

Constructor & Destructor Documentation

◆ ScrewMotion() [1/3]

template<typename S >
fcl::ScrewMotion< S >::ScrewMotion

Default transformations are all identities.

Definition at line 52 of file screw_motion-inl.h.

◆ ScrewMotion() [2/3]

template<typename S >
fcl::ScrewMotion< S >::ScrewMotion ( const Matrix3< S > &  R1,
const Vector3< S > &  T1,
const Matrix3< S > &  R2,
const Vector3< S > &  T2 
)

Construct motion from the initial rotation/translation and goal rotation/translation.

Definition at line 66 of file screw_motion-inl.h.

◆ ScrewMotion() [3/3]

template<typename S >
fcl::ScrewMotion< S >::ScrewMotion ( const Transform3< S > &  tf1_,
const Transform3< S > &  tf2_ 
)

Construct motion from the initial transform and goal transform.

Definition at line 86 of file screw_motion-inl.h.

Member Function Documentation

◆ absoluteRotation()

template<typename S >
Quaternion< S > fcl::ScrewMotion< S >::absoluteRotation ( dt) const
protected

Definition at line 196 of file screw_motion-inl.h.

◆ computeMotionBound() [1/2]

template<typename S >
S fcl::ScrewMotion< S >::computeMotionBound ( const BVMotionBoundVisitor< S > &  mb_visitor) const

Compute the motion bound for a bounding volume along a given direction n, which is defined in the visitor.

Definition at line 109 of file screw_motion-inl.h.

◆ computeMotionBound() [2/2]

template<typename S >
S fcl::ScrewMotion< S >::computeMotionBound ( const TriangleMotionBoundVisitor< S > &  mb_visitor) const

Compute the motion bound for a triangle along a given direction n, which is defined in the visitor.

Definition at line 117 of file screw_motion-inl.h.

◆ computeScrewParameter()

template<typename S >
void fcl::ScrewMotion< S >::computeScrewParameter
protected

Definition at line 159 of file screw_motion-inl.h.

◆ deltaRotation()

template<typename S >
Quaternion< S > fcl::ScrewMotion< S >::deltaRotation ( dt) const
protected

Definition at line 189 of file screw_motion-inl.h.

◆ getAngularVelocity()

template<typename S >
S fcl::ScrewMotion< S >::getAngularVelocity

Definition at line 212 of file screw_motion-inl.h.

◆ getAxis()

template<typename S >
const Vector3< S > & fcl::ScrewMotion< S >::getAxis

Definition at line 219 of file screw_motion-inl.h.

◆ getAxisOrigin()

template<typename S >
const Vector3< S > & fcl::ScrewMotion< S >::getAxisOrigin

Definition at line 226 of file screw_motion-inl.h.

◆ getCurrentTransform()

template<typename S >
void fcl::ScrewMotion< S >::getCurrentTransform ( Transform3< S > &  tf_) const

Get the rotation and translation in current step.

Definition at line 125 of file screw_motion-inl.h.

◆ getLinearVelocity()

template<typename S >
S fcl::ScrewMotion< S >::getLinearVelocity

Definition at line 205 of file screw_motion-inl.h.

◆ getTaylorModel()

template<typename S >
void fcl::ScrewMotion< S >::getTaylorModel ( TMatrix3< S > &  tm,
TVector3< S > &  tv 
) const

Definition at line 132 of file screw_motion-inl.h.

◆ integrate()

template<typename S >
bool fcl::ScrewMotion< S >::integrate ( dt) const

Integrate the motion from 0 to dt We compute the current transformation from zero point instead of from last integrate time, for precision.

Definition at line 95 of file screw_motion-inl.h.

Member Data Documentation

◆ angular_vel

template<typename S >
S fcl::ScrewMotion< S >::angular_vel
protected

angular velocity

Definition at line 107 of file screw_motion.h.

◆ axis

template<typename S >
Vector3<S> fcl::ScrewMotion< S >::axis
protected

screw axis

Definition at line 98 of file screw_motion.h.

◆ linear_vel

template<typename S >
S fcl::ScrewMotion< S >::linear_vel
protected

linear velocity along the axis

Definition at line 104 of file screw_motion.h.

◆ p

template<typename S >
Vector3<S> fcl::ScrewMotion< S >::p
protected

A point on the axis.

Definition at line 101 of file screw_motion.h.

◆ tf

template<typename S >
Transform3<S> fcl::ScrewMotion< S >::tf
mutableprotected

The transformation at current time t.

Definition at line 95 of file screw_motion.h.

◆ tf1

template<typename S >
Transform3<S> fcl::ScrewMotion< S >::tf1
protected

The transformation at time 0.

Definition at line 89 of file screw_motion.h.

◆ tf2

template<typename S >
Transform3<S> fcl::ScrewMotion< S >::tf2
protected

The transformation at time 1.

Definition at line 92 of file screw_motion.h.


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


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:50