RobWorkProject
24.12.4-
|
Prismatic joints. More...
#include <PrismaticJoint.hpp>
Inherits Joint.
Public Types | |
typedef rw::core::Ptr< PrismaticJoint > | Ptr |
smart pointer type to this class | |
Public Types inherited from Joint | |
typedef rw::core::Ptr< Joint > | Ptr |
smart pointer type to this class | |
Public Types inherited from Frame | |
typedef rw::core::Ptr< Frame > | Ptr |
Smart pointer type for a Frame object. | |
typedef rw::core::Ptr< const Frame > | CPtr |
Smart pointer type for a constant Frame object. | |
typedef rw::common::ConcatVectorIterator< Frame > | iterator |
Forward iterator for frames. | |
typedef rw::common::ConstConcatVectorIterator< Frame > | const_iterator |
Forward iterator for const frames. | |
typedef rw::core::iter_pair< iterator > | iterator_pair |
Pair of iterators. | |
typedef rw::core::iter_pair< const_iterator > | const_iterator_pair |
Pair of const iterators. | |
Public Member Functions | |
PrismaticJoint (const std::string &name, const rw::math::Transform3D<> &transform) | |
Constructs PrismaticJoint. More... | |
virtual | ~PrismaticJoint () |
destructor | |
void | multiplyJointTransform (const rw::math::Transform3D<> &parent, const rw::math::Q &q, rw::math::Transform3D<> &result) const |
Post-multiply the transform of the joint to the parent transform. More... | |
rw::math::Transform3D | getJointTransform (double q) const |
The transform of the joint relative to its parent. More... | |
rw::math::Transform3D | getTransform (double q) const |
The transform of the joint relative to its parent. More... | |
rw::math::Transform3D | getFixedTransform () const |
get the fixed transform from parent to this joint More... | |
void | setFixedTransform (const rw::math::Transform3D<> &t3d) |
change the transform from parent to joint base. More... | |
rw::math::Transform3D | getJointTransform (const rw::kinematics::State &state) const |
get the isolated joint transformation which is purely dependent on q. More... | |
void | getJacobian (size_t row, size_t col, const rw::math::Transform3D<> &joint, const rw::math::Transform3D<> &tcp, const rw::kinematics::State &state, rw::math::Jacobian &jacobian) const |
Finds the Jacobian of the joints and adds it in jacobian. More... | |
virtual void | setJointMapping (rw::math::Function1Diff<>::Ptr function) |
set the function to be used in transforming from the state q to the actual q needed. More... | |
virtual void | removeJointMapping () |
removes mapping of joint values More... | |
Public Member Functions inherited from Joint | |
virtual | ~Joint () |
Virtual destructor. | |
void | setBounds (const std::pair< const rw::math::Q, const rw::math::Q > &bounds) |
Sets joint bounds. More... | |
void | setBounds (const rw::math::Q &lower, const rw::math::Q &upper) |
Sets joint bounds. More... | |
const std::pair< rw::math::Q, rw::math::Q > & | getBounds () const |
Gets joint bounds. More... | |
void | setMaxVelocity (const rw::math::Q &maxVelocity) |
Sets max velocity of joint. More... | |
const rw::math::Q & | getMaxVelocity () const |
Gets max velocity of joint. More... | |
void | setMaxAcceleration (const rw::math::Q &maxAcceleration) |
Sets max acceleration of joint. More... | |
const rw::math::Q & | getMaxAcceleration () const |
Gets max acceleration of joint. More... | |
void | setActive (bool isActive) |
set the active state of the joint More... | |
bool | isActive () const |
a joint is active if its motorized/controlled in some fasion. passive or non-active joints are typically used in parrallel robots. More... | |
Public Member Functions inherited from Frame | |
virtual | ~Frame () |
Destructor for the frame. | |
void | multiplyTransform (const rw::math::Transform3D<> &parent, const rw::kinematics::State &state, rw::math::Transform3D<> &result) const |
Post-multiply the transform of the frame to the parent transform. More... | |
rw::math::Transform3D | getTransform (const rw::kinematics::State &state) const |
The transform of the frame relative to its parent. More... | |
const rw::core::PropertyMap & | getPropertyMap () const |
Miscellaneous properties of the frame. More... | |
rw::core::PropertyMap & | getPropertyMap () |
Miscellaneous properties of the frame. More... | |
int | getDOF () const |
The number of degrees of freedom (dof) of the frame. More... | |
const rw::kinematics::Frame * | getParent () const |
The parent of the frame or NULL if the frame is a DAF. | |
rw::kinematics::Frame * | getParent () |
The parent of the frame or NULL if the frame is a DAF. | |
rw::kinematics::Frame * | getParent (const rw::kinematics::State &state) |
Returns the parent of the frame. More... | |
const rw::kinematics::Frame * | getParent (const rw::kinematics::State &state) const |
Returns the parent of the frame. More... | |
const rw::kinematics::Frame * | getDafParent (const rw::kinematics::State &state) const |
The dynamically attached parent or NULL if the frame is not a DAF. | |
rw::kinematics::Frame * | getDafParent (const rw::kinematics::State &state) |
The dynamically attached parent or NULL if the frame is not a DAF. More... | |
const_iterator_pair | getChildren () const |
Iterator pair for the fixed children of the frame. | |
iterator_pair | getChildren () |
Iterator pair for the fixed children of the frame. More... | |
const_iterator_pair | getChildren (const rw::kinematics::State &state) const |
Iterator pair for all children of the frame. | |
iterator_pair | getChildren (const rw::kinematics::State &state) |
Iterator pair for all children of the frame. | |
std::vector< Frame::Ptr > | getChildrenList (const rw::kinematics::State &state) |
get a list of all frame children More... | |
const_iterator_pair | getDafChildren (const rw::kinematics::State &state) const |
Iterator pair for the dynamically attached children of the frame. | |
iterator_pair | getDafChildren (const rw::kinematics::State &state) |
Iterator pair for the dynamically attached children of the frame. More... | |
void | attachTo (const Ptr &parent, rw::kinematics::State &state) |
Move a frame within the tree. More... | |
bool | isDAF () |
Test if this frame is a Dynamically Attachable Frame. More... | |
rw::math::Transform3D | wTf (const rw::kinematics::State &state) const |
Get the transform relative to world. More... | |
rw::math::Transform3D | fTf (const CPtr &to, const rw::kinematics::State &state) const |
Get the transform of other frame relative to this frame. More... | |
bool | operator== (const Frame &rhs) |
Compares the Frame to see if they are the same Checks the statedata, parent frame and chld frame. More... | |
bool | operator!= (const Frame &rhs) |
Check if not equal. More... | |
Public Member Functions inherited from StateData | |
virtual | ~StateData () |
destructor | |
int | getID () const |
An integer ID for the StateData. More... | |
const std::string & | getName () const |
The name of the state data. More... | |
int | size () const |
The number of doubles allocated by this StateData in each State object. More... | |
const double * | getData (const rw::kinematics::State &state) const |
An array of length size() containing the values for the state data. More... | |
double * | getData (rw::kinematics::State &state) |
An array of length size() containing the values for the state data. More... | |
void | setData (rw::kinematics::State &state, const double *vals) const |
Assign for state data the size() of values of the array vals. More... | |
void | setData (rw::kinematics::State &state, const std::vector< double > &vals) const |
Assign for state data the size() of values of the array vals. More... | |
void | setData (rw::kinematics::State &state, const double &val) const |
Assign for state data the size() of values of the array vals. More... | |
bool | hasCache () const |
Check is state data includes a cache. More... | |
rw::core::Ptr< rw::kinematics::StateCache > | getCache (const rw::kinematics::State &state) const |
Get the cache. More... | |
rw::core::Ptr< rw::kinematics::StateCache > | getCache (rw::kinematics::State &state) |
Get the cache. . More... | |
rw::core::Ptr< rw::kinematics::StateCache > | getDefaultCache () |
Get default cache. More... | |
void | setCache (rw::core::Ptr< rw::kinematics::StateCache > cache, rw::kinematics::State &state) |
Set the cache values. More... | |
class rw::kinematics::StateStructure * | getStateStructure () |
Get the state structure. More... | |
bool | operator== (const StateData &rhs) |
Compares the state data to see if they are the same Checks the ID, name and which statetrucure they belong to. More... | |
bool | operator!= (const StateData &rhs) |
Check if not equal. More... | |
StateData (int size, const std::string &name) | |
A state with size number of doubles in the State vector. More... | |
StateData (int size, const std::string &name, rw::core::Ptr< rw::kinematics::StateCache > cache) | |
A state with size number of doubles in the State vector. More... | |
Protected Member Functions | |
void | doMultiplyTransform (const rw::math::Transform3D<> &parent, const rw::kinematics::State &state, rw::math::Transform3D<> &result) const |
Subclass implementation of the getTransform() method. More... | |
rw::math::Transform3D | doGetTransform (const rw::kinematics::State &state) const |
Protected Member Functions inherited from Joint | |
Joint (const std::string &name, size_t dof) | |
Default constructor for the joint interface. More... | |
Joint (const std::string &name, size_t dof, size_t stateSize) | |
constructor - with the possiblity of adding additional states than the dofs. More... | |
Protected Member Functions inherited from Frame | |
Frame (int dof, const std::string &name) | |
A frame with dof number of degrees of freedom. More... | |
Prismatic joints.
PrismaticJoint implements a prismatic joint for the displacement in the direction of the z-axis of an arbitrary displacement transform.
PrismaticJoint | ( | const std::string & | name, |
const rw::math::Transform3D<> & | transform | ||
) |
Constructs PrismaticJoint.
name | [in] Name of the joints |
transform | [in] Static transform of the joint |
|
protectedvirtual |
brief Subclass implementation of the multiplyTransform() method
Implements Frame.
|
protectedvirtual |
Subclass implementation of the getTransform() method.
Implements Frame.
|
virtual |
get the fixed transform from parent to this joint
Notice that this does not include the actual rotation of the joint (its state) only its fixed transform.
Implements Joint.
|
virtual |
Finds the Jacobian of the joints and adds it in jacobian.
Calculates the Jacobian contribution to the device Jacobian when controlling a frame tcp and given a current joint pose joint.
The values are stored from row row to row+5 and column col to col+(joint.getDOF()-1).
row | [in] Row where values should be stored |
col | [in] Column where values should be stored |
joint | [in] Transform of the joint |
tcp | [in] Transformation of the point to control |
state | |
jacobian | [in] Jacobian to which to add the results. |
Implements Joint.
|
virtual |
get the isolated joint transformation which is purely dependent on q.
state | [in] the state from which to extract q |
Implements Joint.
rw::math::Transform3D getJointTransform | ( | double | q | ) | const |
The transform of the joint relative to its parent.
The transform is calculated for the joint values of state.
This method is equivalent to Frame::multiplyTransform except that is operates directly on a joint vector instead of a State.
q | [in] Joint values for the joint |
rw::math::Transform3D getTransform | ( | double | q | ) | const |
The transform of the joint relative to its parent.
The transform is calculated for the joint values of state.
This method is equivalent to Frame::multiplyTransform except that is operates directly on a joint vector instead of a State.
q | [in] Joint values for the joint |
void multiplyJointTransform | ( | const rw::math::Transform3D<> & | parent, |
const rw::math::Q & | q, | ||
rw::math::Transform3D<> & | result | ||
) | const |
Post-multiply the transform of the joint to the parent transform.
The transform is calculated for the joint values of q.
This method is equivalent to Frame::multiplyTransform except that is operates directly on a joint vector instead of a State.
parent | [in] The world transform of the parent frame. |
q | [in] Joint values for the joint |
result | [in] The transform of the frame in the world frame. |
|
virtual |
removes mapping of joint values
Implements Joint.
|
virtual |
change the transform from parent to joint base.
t3d | [in] the new transform. |
Implements Joint.
|
virtual |
set the function to be used in transforming from the state q to the actual q needed.
This function can be used e.g. by a calibration.
function | [in] function with first order derivative. |
Implements Joint.