![]() |
RobWorkProject
23.9.11-
|
A tree structured device. More...
#include <TreeDevice.hpp>
Inherits JointDevice.
Public Types | |
| typedef rw::core::Ptr< TreeDevice > | Ptr |
| smart pointer type to this class | |
Public Types inherited from JointDevice | |
| typedef rw::core::Ptr< JointDevice > | Ptr |
| smart pointer type to this class | |
| typedef rw::core::Ptr< const JointDevice > | CPtr |
| smart pointer type to this class | |
Public Types inherited from Device | |
| typedef rw::core::Ptr< Device > | Ptr |
| smart pointer type to this class | |
| typedef rw::core::Ptr< const Device > | CPtr |
| const smart pointer type to this class | |
| typedef std::pair< rw::math::Q, rw::math::Q > | QBox |
| Lower and upper corner of a box shaped configuration space. | |
Public Types inherited from Stateless | |
| typedef rw::core::Ptr< Stateless > | Ptr |
| Smart pointer type for Stateless. | |
Public Member Functions | |
| TreeDevice (rw::core::Ptr< rw::kinematics::Frame > base, const std::vector< rw::kinematics::Frame * > &ends, const std::string &name, const rw::kinematics::State &state) | |
| Constructor. More... | |
| virtual | ~TreeDevice () |
| destructor | |
| rw::math::Jacobian | baseJends (const rw::kinematics::State &state) const |
| like Device::baseJend() but with a Jacobian calculated for all end effectors. | |
| const std::vector< rw::kinematics::Frame * > & | getEnds () const |
| The end-effectors of the tree device. | |
| virtual rw::kinematics::Frame * | getEnd () |
| a method to return the frame of the end of the device More... | |
| virtual const rw::kinematics::Frame * | getEnd () const |
| a method to return the frame of the end of the device More... | |
| const std::vector< rw::kinematics::Frame * > & | frames () const |
| Frames of the device. More... | |
Public Member Functions inherited from JointDevice | |
| JointDevice (const std::string &name, rw::core::Ptr< rw::kinematics::Frame > base, rw::core::Ptr< rw::kinematics::Frame > end, const std::vector< rw::models::Joint * > &joints, const rw::kinematics::State &state) | |
| Construct the device for a sequence of joints. More... | |
| virtual | ~JointDevice () |
| destructor | |
| const std::vector< rw::models::Joint * > & | getJoints () const |
| Get all joints of this device. More... | |
| void | setQ (const rw::math::Q &q, rw::kinematics::State &state) const |
| Sets configuration vector \( \mathbf{q} \in \mathbb{R}^n \). More... | |
| rw::math::Q | getQ (const rw::kinematics::State &state) const |
| Gets configuration vector \( \mathbf{q}\in \mathbb{R}^n \). More... | |
| size_t | getDOF () const |
| Returns number of active joints. More... | |
| std::pair< rw::math::Q, rw::math::Q > | getBounds () const |
| Returns the upper \( \mathbf{q}_{min} \in \mathbb{R}^n \) and lower \( \mathbf{q}_{max} \in \mathbb{R}^n \) bounds of the joint space. More... | |
| void | setBounds (const std::pair< rw::math::Q, rw::math::Q > &bounds) |
| Sets the upper \( \mathbf{q}_{min} \in \mathbb{R}^n \) and lower \( \mathbf{q}_{max} \in \mathbb{R}^n \) bounds of the joint space. More... | |
| rw::math::Q | getVelocityLimits () const |
| Returns the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\). More... | |
| void | setVelocityLimits (const rw::math::Q &vellimits) |
| Sets the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\). More... | |
| rw::math::Q | getAccelerationLimits () const |
| Returns the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\). More... | |
| void | setAccelerationLimits (const rw::math::Q &acclimits) |
| Sets the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\). More... | |
| rw::math::Jacobian | baseJend (const rw::kinematics::State &state) const |
| Calculates the jacobian matrix of the end-effector described in the robot base frame \( ^{base}_{end}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \). More... | |
| rw::core::Ptr< rw::models::JacobianCalculator > | baseJCframes (const std::vector< rw::kinematics::Frame * > &frames, const rw::kinematics::State &state) const |
| DeviceJacobian for a sequence of frames. More... | |
| rw::kinematics::Frame * | getBase () |
| a method to return the frame of the base of the device. More... | |
| const rw::kinematics::Frame * | getBase () const |
| a method to return the frame of the base of the device. More... | |
Public Member Functions inherited from Device | |
| Device (const std::string &name) | |
| virtual | ~Device () |
| Virtual destructor. | |
| virtual void | setBounds (const QBox &bounds)=0 |
| Sets the upper \( \mathbf{q}_{min} \in \mathbb{R}^n \) and lower \( \mathbf{q}_{max} \in \mathbb{R}^n \) bounds of the joint space. More... | |
| const std::string & | getName () const |
| Returns the name of the device. More... | |
| void | setName (const std::string &name) |
| Sets the name of the Device. More... | |
| rw::math::Transform3D< double > | baseTframe (rw::core::Ptr< const rw::kinematics::Frame > f, const rw::kinematics::State &state) const |
| Calculates the homogeneous transform from base to a frame f \( \robabx{b}{f}{\mathbf{T}} \). More... | |
| rw::math::Transform3D< double > | baseTend (const rw::kinematics::State &state) const |
| Calculates the homogeneous transform from base to the end frame \( \robabx{base}{end}{\mathbf{T}} \). More... | |
| rw::math::Transform3D< double > | worldTbase (const rw::kinematics::State &state) const |
| Calculates the homogeneous transform from world to base \( \robabx{w}{b}{\mathbf{T}} \). More... | |
| virtual rw::math::Jacobian | baseJframe (rw::core::Ptr< const rw::kinematics::Frame > frame, const rw::kinematics::State &state) const |
| Calculates the jacobian matrix of a frame f described in the robot base frame \( ^{base}_{frame}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \). More... | |
| virtual rw::math::Jacobian | baseJframes (const std::vector< rw::kinematics::Frame * > &frames, const rw::kinematics::State &state) const |
| The Jacobian for a sequence of frames. More... | |
| virtual rw::core::Ptr< rw::models::JacobianCalculator > | baseJCend (const rw::kinematics::State &state) const |
| DeviceJacobian for the end frame. More... | |
| virtual rw::core::Ptr< rw::models::JacobianCalculator > | baseJCframe (rw::core::Ptr< const rw::kinematics::Frame > frame, const rw::kinematics::State &state) const |
| DeviceJacobian for a particular frame. More... | |
| const rw::core::PropertyMap & | getPropertyMap () const |
| Miscellaneous properties of the device. More... | |
| rw::core::PropertyMap & | getPropertyMap () |
| Miscellaneous properties of the device. More... | |
Public Member Functions inherited from Stateless | |
| virtual | ~Stateless () |
| destructor | |
| virtual void | registerIn (State &state) |
| initialize this stateless data to a specific state More... | |
| virtual void | registerIn (StateStructure::Ptr state) |
| register this stateless object in a statestructure. | |
| virtual void | unregister () |
| unregisters all state data of this stateless object | |
| StateStructure::Ptr | getStateStructure () |
| Get the state structure. More... | |
| const StateStructure::Ptr | getStateStructure () const |
| Get the state structure. More... | |
| bool | isRegistered () |
| Check if object has registered its state. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from Stateless | |
| Stateless () | |
| constructor | |
| template<class T > | |
| void | add (StatelessData< T > &data) |
| implementations of sensor should add all their stateless data on initialization | |
| void | add (StateData *data) |
| Add data. More... | |
| void | add (rw::core::Ptr< StateData > data) |
| implementations of sensor should add all their state data on initialization | |
Protected Attributes inherited from Stateless | |
| bool | _registered |
| True if object has registered its state. | |
| std::vector< rw::core::Ptr< StateData > > | _datas |
| Data. | |
| StateStructure::Ptr | _stateStruct |
| The state structure. | |
A tree structured device.
This device type defines devices that are tree-structured, with multiple end effectors. Typical for dexterous hands, and multi-armed robots.
| TreeDevice | ( | rw::core::Ptr< rw::kinematics::Frame > | base, |
| const std::vector< rw::kinematics::Frame * > & | ends, | ||
| const std::string & | name, | ||
| const rw::kinematics::State & | state | ||
| ) |
Constructor.
| base | [in] the base frame of the robot |
| ends | [in] the set of end-effectors of the robot |
| name | [in] name of device |
| state | [in] the initial state of everything |
|
inline |
Frames of the device.
This method is being used when displaying the kinematic structure of devices in RobWorkStudio. The method really isn't of much use for everyday programming.
|
inlinevirtual |
a method to return the frame of the end of the device
Reimplemented from JointDevice.
|
inlinevirtual |
a method to return the frame of the end of the device
Reimplemented from JointDevice.