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

A device constructed from a sequence of devices. More...

#include <CompositeDevice.hpp>

Inherits JointDevice.

Public Member Functions

 CompositeDevice (rw::core::Ptr< rw::kinematics::Frame > base, const std::vector< rw::core::Ptr< rw::models::Device >> &devices, rw::core::Ptr< rw::kinematics::Frame > end, const std::string &name, const rw::kinematics::State &state)
 Constructor. More...
 
 CompositeDevice (rw::core::Ptr< rw::kinematics::Frame > base, const std::vector< rw::core::Ptr< rw::models::Device >> &devices, const std::vector< rw::kinematics::Frame * > &ends, const std::string &name, const rw::kinematics::State &state)
 Constructor. More...
 
virtual ~CompositeDevice ()
 destructor
 
void setQ (const rw::math::Q &q, rw::kinematics::State &state) const
 Sets configuration vector \( \mathbf{q} \in \mathbb{R}^n \). More...
 
rw::math::Jacobian baseJends (const rw::kinematics::State &state) const
 like Device::baseJend() but with a Jacobian calculated for all end-effectors (see getEnds()).
 
const std::vector< rw::kinematics::Frame * > & getEnds () const
 The end-effectors of the composite 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::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::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::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 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...
 
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

- 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.
 
- 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

A device constructed from a sequence of devices.

The configuration of a composite device is equal to the concatenation of the configurations of the sequence of devices.

The devices that make up the CompositeDevice may not share joints, but the implementation does not check if this is actually the case.

A composite device implements its operations of Device by querying each Joint in the straight-forward way of JointDevice. The notable exception is Device::setQ() which is implemented by forwarding the Device::setQ() calls to the sequence of devices. This means that CompositeDevice works also for example for devices of type ParallelDevice that have an overwritten implementation of Device::setQ().

The devices from which the composite device is constructed must all be of type JointDevice. An exception is thrown by the constructor if one of the devices is not of this subtype.

The computation of Jacobians of CompositeDevice is not correct in general, but is correct only for devices for which the standard technique of JointDevice is correct. We cannot in general in RobWork do any better currently. The implementation does not check if the requirements for the computation of Jacobians are indeed satisfied.

CompositeDevice is related to TreeDevice in the sense that CompositeDevice has also multiple end-effectors (one end-effector for each device). CompositeDevice differs from TreeDevice by not requiring that the child-to-parent paths of the end-effectors connect to a common base.

Constructor & Destructor Documentation

◆ CompositeDevice() [1/2]

CompositeDevice ( rw::core::Ptr< rw::kinematics::Frame base,
const std::vector< rw::core::Ptr< rw::models::Device >> &  devices,
rw::core::Ptr< rw::kinematics::Frame end,
const std::string &  name,
const rw::kinematics::State state 
)

Constructor.

Parameters
base[in] the base of the device
devices[in] the sequence of subdevices
end[in] the end (or tool) of the device
name[in] the name of the device
state[in] the kinematic structure assumed for Jacobian computations

◆ CompositeDevice() [2/2]

CompositeDevice ( rw::core::Ptr< rw::kinematics::Frame base,
const std::vector< rw::core::Ptr< rw::models::Device >> &  devices,
const std::vector< rw::kinematics::Frame * > &  ends,
const std::string &  name,
const rw::kinematics::State state 
)

Constructor.

Parameters
base[in] the base of the device
devices[in] the sequence of subdevices
ends[in] the end frames (or tools) of the device
name[in] the name of the device
state[in] the kinematic structure assumed for Jacobian computations

Member Function Documentation

◆ getEnds()

const std::vector<rw::kinematics::Frame*>& getEnds ( ) const
inline

The end-effectors of the composite device.

The end-effectors of the composite device are the end-effectors of the devices from which the composite device was constructed.

This sequence of end-effectors may or may not include the default end-effector returned by getEnd().

◆ setQ()

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 method is implemented via forwarding to the Device::setQ() methods of the subdevices.

Implements Device.


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