RobWorkProject  23.9.11-
Public Types | Public Member Functions | List of all members
ParallelDevice Class Reference

This class defines the interface for Parallel devices. More...

#include <ParallelDevice.hpp>

Inherits JointDevice.

Public Types

typedef rw::core::Ptr< ParallelDevicePtr
 smart pointer type to this class
 
typedef std::vector< rw::models::ParallelLeg * > Legs
 type for a set of legs.
 
- Public Types inherited from JointDevice
typedef rw::core::Ptr< JointDevicePtr
 smart pointer type to this class
 
typedef rw::core::Ptr< const JointDeviceCPtr
 smart pointer type to this class
 
- Public Types inherited from Device
typedef rw::core::Ptr< DevicePtr
 smart pointer type to this class
 
typedef rw::core::Ptr< const DeviceCPtr
 const smart pointer type to this class
 
typedef std::pair< rw::math::Q, rw::math::QQBox
 Lower and upper corner of a box shaped configuration space.
 
- Public Types inherited from Stateless
typedef rw::core::Ptr< StatelessPtr
 Smart pointer type for Stateless.
 

Public Member Functions

 ParallelDevice (const Legs &legs, const std::string name, const rw::kinematics::State &state)
 Constructor. More...
 
 ParallelDevice (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, const std::vector< Legs > &junctions)
 Constructor for parallel device with multiple junctions. More...
 
 ~ParallelDevice ()
 Destructor.
 
virtual void setQ (const rw::math::Q &q, rw::kinematics::State &state) const
 Sets configuration vector \( \mathbf{q} \in \mathbb{R}^n \). More...
 
virtual void setQ (const rw::math::Q &q, const std::vector< bool > &enabled, rw::kinematics::State &state) const
 Set only some of the actuated joints. More...
 
rw::math::Jacobian baseJframe (const rw::core::Ptr< 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...
 
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...
 
virtual std::vector< rw::models::ParallelLeg * > getLegs () const
 The legs of the parallel device.
 
virtual std::vector< std::vector< rw::models::ParallelLeg * > > getJunctions () const
 Get the junctions of the device. More...
 
virtual std::vector< models::Joint * > getActiveJoints () const
 The active joints of the parallel device.
 
virtual std::vector< rw::models::Joint * > getAllJoints () const
 Get all joints (both active and passive). More...
 
std::size_t getFullDOF () const
 Get the total degrees of freedom for all (active and passive) joints in the device. More...
 
std::pair< rw::math::Q, rw::math::QgetAllBounds () const
 Get bounds for all joints (includes both active and passive joints). More...
 
rw::math::Q getFullQ (const rw::kinematics::State &state) const
 Get the full configuration vector of the device. This gives the complete state of the parallel device. More...
 
void setFullQ (const rw::math::Q &q, rw::kinematics::State &state) const
 Set the full configuration of the device. This sets the joint values directly, and there is no checks or guarantees that the device will be in a valid connected configuration afterwards. 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...
 
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::QgetBounds () 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::core::Ptr< rw::models::JacobianCalculatorbaseJCframes (const std::vector< rw::kinematics::Frame * > &frames, const rw::kinematics::State &state) const
 DeviceJacobian for a sequence of frames. More...
 
rw::kinematics::FramegetBase ()
 a method to return the frame of the base of the device. More...
 
const rw::kinematics::FramegetBase () const
 a method to return the frame of the base of the device. More...
 
virtual rw::kinematics::FramegetEnd ()
 a method to return the frame of the end of the device More...
 
virtual const rw::kinematics::FramegetEnd () const
 a method to return the frame of the end 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 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::JacobianCalculatorbaseJCend (const rw::kinematics::State &state) const
 DeviceJacobian for the end frame. More...
 
virtual rw::core::Ptr< rw::models::JacobianCalculatorbaseJCframe (rw::core::Ptr< const rw::kinematics::Frame > frame, const rw::kinematics::State &state) const
 DeviceJacobian for a particular frame. More...
 
const rw::core::PropertyMapgetPropertyMap () const
 Miscellaneous properties of the device. More...
 
rw::core::PropertyMapgetPropertyMap ()
 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.
 

Detailed Description

This class defines the interface for Parallel devices.

Constructor & Destructor Documentation

◆ ParallelDevice() [1/2]

ParallelDevice ( const Legs legs,
const std::string  name,
const rw::kinematics::State state 
)

Constructor.

Parameters
legs[in] the serial legs connecting the endplate to the base. The base of each serial Leg must be the same frame. Likewise, the endeffector (last frame) of each Leg must transform to the same transform as each of the other legs
name[in] name of device
state[in] the state for the assembly mode

◆ ParallelDevice() [2/2]

ParallelDevice ( 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,
const std::vector< Legs > &  junctions 
)

Constructor for parallel device with multiple junctions.

Parameters
name[in] name of the device.
base[in] the base frame.
end[in] the end frame.
joints[in] a list of joints. Each joint can be included in multiple legs.
state[in] the state used to construct a JointDevice.
junctions[in] a list of junctions. Each junction is given by a list of legs that must begin and end in the same frame.

Member Function Documentation

◆ baseJend()

rw::math::Jacobian baseJend ( const rw::kinematics::State state) const
virtual

Calculates the jacobian matrix of the end-effector described in the robot base frame \( ^{base}_{end}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \).

Parameters
state[in] State for which to calculate the Jacobian
Returns
the \( 6*ndof \) jacobian matrix: \( {^{base}_{end}}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \)

This method calculates the jacobian relating joint velocities ( \( \mathbf{\dot{q}} \)) to the end-effector velocity seen from base-frame ( \( \nu^{ase}_{end} \))

\[ \nu^{base}_{end} = {^{base}_{end}}\mathbf{J}_\mathbf{q}(\mathbf{q})\mathbf{\dot{q}} \]

The jacobian matrix

\[ {^{base}_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \]

is defined as:

\[ {^{base}_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) = \frac{\partial ^{base}\mathbf{x}_n}{\partial \mathbf{q}} \]

Where:

\[ {^{base}_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) = \left[ \begin{array}{cccc} {^{base}_1}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) & {^{base}_2}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) & \cdots & {^b_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \\ \end{array} \right] \]

where \( {^{base}_i}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \) is defined by

\[ {^{base}_i}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) = \begin{array}{cc} \left[ \begin{array}{c} {^{base}}\mathbf{z}_i \times {^{i}\mathbf{p}_n} \\ {^{base}}\mathbf{z}_i \\ \end{array} \right] & \textrm{revolute joint} \end{array} \]

\[ {^{base}_i}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) = \begin{array}{cc} \left[ \begin{array}{c} {^{base}}\mathbf{z}_i \\ \mathbf{0} \\ \end{array} \right] & \textrm{prismatic joint} \\ \end{array} \]

By default the method forwards to baseJframe().

Reimplemented from JointDevice.

◆ baseJframe()

rw::math::Jacobian baseJframe ( const rw::core::Ptr< rw::kinematics::Frame frame,
const rw::kinematics::State state 
) const
virtual

Calculates the jacobian matrix of a frame f described in the robot base frame \( ^{base}_{frame}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \).

Parameters
frame[in] Frame for which to calculate the Jacobian
state[in] State for which to calculate the Jacobian
Returns
the \( 6*ndof \) jacobian matrix: \( {^{base}_{frame}}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \)

This method calculates the jacobian relating joint velocities ( \( \mathbf{\dot{q}} \)) to the frame f velocity seen from base-frame ( \( \nu^{base}_{frame} \))

\[ \nu^{base}_{frame} = {^{base}_{frame}}\mathbf{J}_\mathbf{q}(\mathbf{q})\mathbf{\dot{q}} \]

The jacobian matrix

\[ {^{base}_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \]

is defined as:

\[ {^{base}_n}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) = \frac{\partial ^{base}\mathbf{x}_n}{\partial \mathbf{q}} \]

By default the method forwards to baseJframes().

Reimplemented from Device.

◆ getAllBounds()

std::pair<rw::math::Q, rw::math::Q> getAllBounds ( ) const

Get bounds for all joints (includes both active and passive joints).

Returns
a pair with the lower and upper limits.

◆ getAllJoints()

virtual std::vector<rw::models::Joint*> getAllJoints ( ) const
virtual

Get all joints (both active and passive).

Returns
a vector of all the joints.

◆ getFullDOF()

std::size_t getFullDOF ( ) const

Get the total degrees of freedom for all (active and passive) joints in the device.

Returns
the total degrees of freedom.

◆ getFullQ()

rw::math::Q getFullQ ( const rw::kinematics::State state) const

Get the full configuration vector of the device. This gives the complete state of the parallel device.

Parameters
state[in] the state that contains the full configuration.
Returns
the configuration vector with the joint values for both active and passive joints.

◆ getJunctions()

virtual std::vector<std::vector<rw::models::ParallelLeg*> > getJunctions ( ) const
inlinevirtual

Get the junctions of the device.

Returns
a vector of junctions. Each junction is given by a two or more legs.

◆ setFullQ()

void setFullQ ( const rw::math::Q q,
rw::kinematics::State state 
) const

Set the full configuration of the device. This sets the joint values directly, and there is no checks or guarantees that the device will be in a valid connected configuration afterwards.

Parameters
q[in] the configuration vector to set.
state[in/out] the state to update with a new configuration.

◆ setQ() [1/2]

virtual void setQ ( const rw::math::Q q,
const std::vector< bool > &  enabled,
rw::kinematics::State state 
) const
virtual

Set only some of the actuated joints.

This version of setQ will only set a subset of the actuated joints. Based on the value of
q, the function will compute the values for the unactuated (passive) joints, and the remaining actuated joints.

This is mainly useful for parallel devices that have more controlled joints than strictly required to make the kinematics determined.

Parameters
q[in] the configuration of the actuated joints (the only considered elements are the ones where the corresponding elements of enabled is true).
enabled[in] vector of same size as q, specifying which values to solve for.
state[in/out] the state with all active and passive joint values. The input state is expected to contain a valid and consistent configuration of the device.

◆ setQ() [2/2]

virtual void setQ ( const rw::math::Q q,
rw::kinematics::State state 
) const
virtual

Sets configuration vector \( \mathbf{q} \in \mathbb{R}^n \).

Parameters
q[in] configuration vector \( \mathbf{q} \)
state[in] state into which to set \( \mathbf{q} \)
Precondition
q.size() == getDOF()

The configuration q is the configuration for the actuated joints of the parallel device. Based on the value of q the setQ() method automatically computes the values for the unactuated (passive) joints.

Reimplemented from JointDevice.


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