RobWorkProject  23.9.11-
Public Types | Public Member Functions | List of all members
Device Class Referenceabstract

An abstract device class. More...

#include <Device.hpp>

Inherits Stateless.

Inherited by JointDevice, MobileDevice, and SE3Device.

Public Types

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

 Device (const std::string &name)
 
virtual ~Device ()
 Virtual destructor.
 
virtual void setQ (const rw::math::Q &q, rw::kinematics::State &state) const =0
 Sets configuration vector \( \mathbf{q} \in \mathbb{R}^n \). More...
 
virtual rw::math::Q getQ (const rw::kinematics::State &state) const =0
 Gets configuration vector \( \mathbf{q}\in \mathbb{R}^n \). More...
 
virtual QBox getBounds () const =0
 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...
 
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...
 
virtual rw::math::Q getVelocityLimits () const =0
 Returns the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\). More...
 
virtual void setVelocityLimits (const rw::math::Q &vellimits)=0
 Sets the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\). More...
 
virtual rw::math::Q getAccelerationLimits () const =0
 Returns the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\). More...
 
virtual void setAccelerationLimits (const rw::math::Q &acclimits)=0
 Sets the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\). More...
 
virtual size_t getDOF () const =0
 Returns number of active joints. 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...
 
virtual rw::kinematics::FramegetBase ()=0
 a method to return the frame of the base of the device. More...
 
virtual const rw::kinematics::FramegetBase () const =0
 a method to return the frame of the base of the device. More...
 
virtual rw::kinematics::FramegetEnd ()=0
 a method to return the frame of the end of the device More...
 
virtual const rw::kinematics::FramegetEnd () const =0
 a method to return the frame of the end 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 baseJend (const rw::kinematics::State &state) const =0
 Calculates the jacobian matrix of the end-effector described in the robot base frame \( ^{base}_{end}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \). 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::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...
 
virtual rw::core::Ptr< rw::models::JacobianCalculatorbaseJCframes (const std::vector< rw::kinematics::Frame * > &frames, const rw::kinematics::State &state) const =0
 DeviceJacobian for a sequence of frames.
 
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

An abstract device class.

The Device class is the basis for all other devices. It is assumed that all devices have a configuration which can be encoded by a rw::math::Q, that all have a base frame representing where in the work cell they are located and a primary end frame. Notice that some devices may have multiple end-frames.

Constructor & Destructor Documentation

◆ Device()

Device ( const std::string &  name)
inline

Constructs a device with a name

Parameters
name[in] name of the device

Member Function Documentation

◆ baseJCend()

virtual rw::core::Ptr<rw::models::JacobianCalculator> baseJCend ( const rw::kinematics::State state) const
virtual

DeviceJacobian for the end frame.

By default this method forwards to baseDJframe().

◆ baseJCframe()

virtual rw::core::Ptr<rw::models::JacobianCalculator> baseJCframe ( rw::core::Ptr< const rw::kinematics::Frame frame,
const rw::kinematics::State state 
) const
virtual

DeviceJacobian for a particular frame.

By default this method forwards to baseDJframes().

◆ baseJend()

virtual rw::math::Jacobian baseJend ( const rw::kinematics::State state) const
pure 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().

Implemented in SE3Device, ParallelDevice, MobileDevice, and JointDevice.

◆ baseJframe()

virtual rw::math::Jacobian baseJframe ( rw::core::Ptr< const 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 in ParallelDevice, and MobileDevice.

◆ baseJframes()

virtual rw::math::Jacobian baseJframes ( const std::vector< rw::kinematics::Frame * > &  frames,
const rw::kinematics::State state 
) const
inlinevirtual

The Jacobian for a sequence of frames.

A Jacobian is computed for each of the frames and the Jacobians are stacked on top of eachother.

Parameters
frames[in] the frames to calculate the frames from
state[in] the state to calculate in
Returns
the jacobian

Reimplemented in MobileDevice.

◆ baseTend()

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}} \).

Returns
the homogeneous transform \( \robabx{base}{end}{\mathbf{T}} \)

◆ baseTframe()

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}} \).

Returns
the homogeneous transform \( \robabx{b}{f}{\mathbf{T}} \)

◆ getAccelerationLimits()

virtual rw::math::Q getAccelerationLimits ( ) const
pure virtual

Returns the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\).

It is assumed that \( \ddot{\mathbf{q}}_{min}=-\ddot{\mathbf{q}}_{max}\)

Returns
the maximal acceleration

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ getBase() [1/2]

virtual const rw::kinematics::Frame* getBase ( ) const
pure virtual

a method to return the frame of the base of the device.

Returns
the base frame

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ getBase() [2/2]

virtual rw::kinematics::Frame* getBase ( )
pure virtual

a method to return the frame of the base of the device.

Returns
the base frame

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ getBounds()

virtual QBox getBounds ( ) const
pure virtual

Returns the upper \( \mathbf{q}_{min} \in \mathbb{R}^n \) and lower \( \mathbf{q}_{max} \in \mathbb{R}^n \) bounds of the joint space.

Returns
std::pair containing \( (\mathbf{q}_{min}, \mathbf{q}_{max}) \)

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ getDOF()

virtual size_t getDOF ( ) const
pure virtual

Returns number of active joints.

Returns
number of active joints \( n \)

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ getEnd() [1/2]

virtual const rw::kinematics::Frame* getEnd ( ) const
pure virtual

a method to return the frame of the end of the device

Returns
the end frame

Implemented in TreeDevice, SE3Device, MobileDevice, and JointDevice.

◆ getEnd() [2/2]

virtual rw::kinematics::Frame* getEnd ( )
pure virtual

a method to return the frame of the end of the device

Returns
the end frame

Implemented in TreeDevice, SE3Device, MobileDevice, and JointDevice.

◆ getName()

const std::string& getName ( ) const
inline

Returns the name of the device.

Returns
name of the device

◆ getPropertyMap() [1/2]

rw::core::PropertyMap& getPropertyMap ( )
inline

Miscellaneous properties of the device.

The property map of the device is provided to let the user store various settings for the device. The settings are typically loaded from setup files.

The low-level manipulations of the property map can be cumbersome. To ease these manipulations, the PropertyAccessor utility class has been provided. Instances of this class are provided for a number of common settings, however it is undecided if these properties are a public part of RobWork.

Returns
The property map of the device.

◆ getPropertyMap() [2/2]

const rw::core::PropertyMap& getPropertyMap ( ) const
inline

Miscellaneous properties of the device.

The property map of the device is provided to let the user store various settings for the device. The settings are typically loaded from setup files.

The low-level manipulations of the property map can be cumbersome. To ease these manipulations, the PropertyAccessor utility class has been provided. Instances of this class are provided for a number of common settings, however it is undecided if these properties are a public part of RobWork.

Returns
The property map of the device.

◆ getQ()

virtual rw::math::Q getQ ( const rw::kinematics::State state) const
pure virtual

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

Parameters
state[in] state from which which to get \( \mathbf{q} \)
Returns
configuration vector \( \mathbf{q} \)

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ getVelocityLimits()

virtual rw::math::Q getVelocityLimits ( ) const
pure virtual

Returns the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\).

It is assumed that \( \dot{\mathbf{q}}_{min}=-\dot{\mathbf{q}}_{max}\)

Returns
the maximal velocity

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ setAccelerationLimits()

virtual void setAccelerationLimits ( const rw::math::Q acclimits)
pure virtual

Sets the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\).

It is assumed that \( \ddot{\mathbf{q}}_{min}=-\ddot{\mathbf{q}}_{max}\)

Parameters
acclimits[in] the maximal acceleration

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ setBounds()

virtual void setBounds ( const QBox bounds)
pure virtual

Sets the upper \( \mathbf{q}_{min} \in \mathbb{R}^n \) and lower \( \mathbf{q}_{max} \in \mathbb{R}^n \) bounds of the joint space.

Parameters
bounds[in] std::pair containing \( (\mathbf{q}_{min}, \mathbf{q}_{max}) \)

Implemented in SE3Device.

◆ setName()

void setName ( const std::string &  name)
inline

Sets the name of the Device.

Parameters
name[in] the new name of the frame

◆ setQ()

virtual void setQ ( const rw::math::Q q,
rw::kinematics::State state 
) const
pure 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()

Implemented in SE3Device, ParallelDevice, MobileDevice, JointDevice, CompositeJointDevice, and CompositeDevice.

◆ setVelocityLimits()

virtual void setVelocityLimits ( const rw::math::Q vellimits)
pure virtual

Sets the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\).

It is assumed that \( \dot{\mathbf{q}}_{min}=-\dot{\mathbf{q}}_{max}\)

Parameters
vellimits[in] Q with the maximal velocity

Implemented in SE3Device, MobileDevice, and JointDevice.

◆ worldTbase()

rw::math::Transform3D<double> worldTbase ( const rw::kinematics::State state) const

Calculates the homogeneous transform from world to base \( \robabx{w}{b}{\mathbf{T}} \).

Returns
the homogeneous transform \( \robabx{w}{b}{\mathbf{T}} \)

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