![]() |
RobWorkProject
25.2.11-
|
An abstract device class. More...
#include <Device.hpp>
Inherits Stateless.
Inherited by JointDevice, MobileDevice, and SE3Device.
Public Types | |
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. | |
![]() | |
typedef rw::core::Ptr< Stateless > | Ptr |
Smart pointer type to a Stateless. | |
typedef rw::core::Ptr< const Stateless > | CPtr |
Smart pointer type to a constant 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::Frame * | getBase ()=0 |
a method to return the frame of the base of the device. More... | |
virtual const rw::kinematics::Frame * | getBase () const =0 |
a method to return the frame of the base of the device. More... | |
virtual rw::kinematics::Frame * | getEnd ()=0 |
a method to return the frame of the end of the device More... | |
virtual const rw::kinematics::Frame * | getEnd () 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 (const 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... | |
virtual rw::core::Ptr< rw::models::JacobianCalculator > | baseJCframes (const std::vector< rw::kinematics::Frame * > &frames, const rw::kinematics::State &state) const =0 |
DeviceJacobian for a sequence of frames. | |
const rw::core::PropertyMap & | getPropertyMap () const |
Miscellaneous properties of the device. More... | |
rw::core::PropertyMap & | getPropertyMap () |
Miscellaneous properties of the device. More... | |
![]() | |
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 | |
![]() | |
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 | |
![]() | |
bool | _registered |
True if object has registered its state. | |
std::vector< rw::core::Ptr< StateData > > | _datas |
Data. | |
StateStructure::Ptr | _stateStruct |
The state structure. | |
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.
|
inline |
Constructs a device with a name
name | [in] name of the device |
|
virtual |
DeviceJacobian for the end frame.
By default this method forwards to baseDJframe().
|
virtual |
DeviceJacobian for a particular frame.
By default this method forwards to baseDJframes().
|
pure virtual |
Calculates the jacobian matrix of the end-effector described in the robot base frame \( ^{base}_{end}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \).
state | [in] State for which to calculate the Jacobian |
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.
|
virtual |
Calculates the jacobian matrix of a frame f described in the robot base frame \( ^{base}_{frame}\mathbf{J}_{\mathbf{q}}(\mathbf{q}) \).
frame | [in] Frame for which to calculate the Jacobian |
state | [in] State for which to calculate the Jacobian |
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.
|
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.
frames | [in] the frames to calculate the frames from |
state | [in] the state to calculate in |
Reimplemented in MobileDevice.
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}} \).
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}} \).
|
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}\)
Implemented in SE3Device, MobileDevice, and JointDevice.
|
pure virtual |
a method to return the frame of the base of the device.
Implemented in SE3Device, MobileDevice, and JointDevice.
|
pure virtual |
a method to return the frame of the base of the device.
Implemented in SE3Device, MobileDevice, and JointDevice.
|
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.
Implemented in SE3Device, MobileDevice, and JointDevice.
|
pure virtual |
Returns number of active joints.
Implemented in SE3Device, MobileDevice, and JointDevice.
|
pure virtual |
a method to return the frame of the end of the device
Implemented in TreeDevice, SE3Device, MobileDevice, and JointDevice.
|
pure virtual |
a method to return the frame of the end of the device
Implemented in TreeDevice, SE3Device, MobileDevice, and JointDevice.
|
inline |
Returns the name of the device.
|
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.
|
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.
|
pure virtual |
Gets configuration vector \( \mathbf{q}\in \mathbb{R}^n \).
state | [in] state from which which to get \( \mathbf{q} \) |
Implemented in SE3Device, MobileDevice, and JointDevice.
|
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}\)
Implemented in SE3Device, MobileDevice, and JointDevice.
|
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}\)
acclimits | [in] the maximal acceleration |
Implemented in SE3Device, MobileDevice, and JointDevice.
|
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.
bounds | [in] std::pair containing \( (\mathbf{q}_{min}, \mathbf{q}_{max}) \) |
Implemented in SE3Device.
|
inline |
Sets the name of the Device.
name | [in] the new name of the frame |
|
pure virtual |
Sets configuration vector \( \mathbf{q} \in \mathbb{R}^n \).
q | [in] configuration vector \( \mathbf{q} \) |
state | [in] state into which to set \( \mathbf{q} \) |
Implemented in SE3Device, ParallelDevice, MobileDevice, JointDevice, CompositeJointDevice, and CompositeDevice.
|
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}\)
vellimits | [in] Q with the maximal velocity |
Implemented in SE3Device, MobileDevice, and JointDevice.
rw::math::Transform3D<double> worldTbase | ( | const rw::kinematics::State & | state | ) | const |
Calculates the homogeneous transform from world to base \( \robabx{w}{b}{\mathbf{T}} \).