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

The device for a serial chain. More...

#include <SerialDevice.hpp>

Inherits JointDevice.

Public Types

typedef rw::core::Ptr< SerialDevicePtr
 smart pointer type to this class
 
typedef rw::core::Ptr< const SerialDeviceCPtr
 smart pointer type to this const class
 
- 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

 SerialDevice (rw::core::Ptr< rw::kinematics::Frame > first, rw::core::Ptr< rw::kinematics::Frame > last, const std::string &name, const rw::kinematics::State &state)
 Constructor. More...
 
virtual ~SerialDevice ()
 destructor
 
const std::vector< rw::kinematics::Frame * > & frames () const
 Frames of the device. More...
 
 SerialDevice (const std::vector< rw::kinematics::Frame * > &serialChain, const std::string &name, const rw::kinematics::State &state)
 Creates object. 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

- 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

The device for a serial chain.

SerialChain is like JointDevice except that SerialChain has the additional guarantee that the joints lie on a single parent to child path of the kinematic tree.

Constructor & Destructor Documentation

◆ SerialDevice() [1/2]

SerialDevice ( rw::core::Ptr< rw::kinematics::Frame first,
rw::core::Ptr< rw::kinematics::Frame last,
const std::string &  name,
const rw::kinematics::State state 
)

Constructor.

Parameters
first[in] the base frame of the robot
last[in] the end-effector of the robot
name[in] name of device
state[in] the connectedness of the frames

◆ SerialDevice() [2/2]

SerialDevice ( const std::vector< rw::kinematics::Frame * > &  serialChain,
const std::string &  name,
const rw::kinematics::State state 
)

Creates object.

Parameters
serialChain[in] a vector of connected frames. The first frame in serialChain is the base of the device and the last frame of serialChain is the end of the device. The joints of the device are the active joints of serialChain.
name[in] name of device
state[in] the initial state of everything

Member Function Documentation

◆ frames()

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

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.

Returns
list of raw Frame pointers.

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