RobWorkProject
23.9.11-
|
Provides a differential controlled mobile device. More...
#include <MobileDevice.hpp>
Inherits Device.
Public Member Functions | |
MobileDevice (rw::kinematics::MovableFrame *base, RevoluteJoint *wheel1, RevoluteJoint *wheel2, rw::kinematics::State &state, const std::string &name) | |
Constructs a mobile device. More... | |
virtual | ~MobileDevice () |
Destructor. | |
void | setDevicePose (const rw::math::Transform3D<> &transform, rw::kinematics::State &state) |
Sets the position and orientation of the base. More... | |
virtual void | setQ (const rw::math::Q &q, rw::kinematics::State &state) const |
Sets configuration vector \( \mathbf{q} \in \mathbb{R}^n \). More... | |
virtual rw::math::Q | getQ (const rw::kinematics::State &state) const |
Gets configuration vector \( \mathbf{q}\in \mathbb{R}^n \). More... | |
virtual std::pair< rw::math::Q, rw::math::Q > | getBounds () 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... | |
virtual 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... | |
virtual rw::math::Q | getVelocityLimits () const |
Returns the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\). More... | |
virtual void | setVelocityLimits (const rw::math::Q &vellimits) |
Sets the maximal velocity of the joints \(\mathbf{\dot{q}}_{max}\in \mathbb{R}^n\). More... | |
virtual rw::math::Q | getAccelerationLimits () const |
Returns the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\). More... | |
virtual void | setAccelerationLimits (const rw::math::Q &acclimits) |
Sets the maximal acceleration of the joints \(\mathbf{\ddot{q}}_{max}\in \mathbb{R}^n\). More... | |
virtual size_t | getDOF () const |
Returns number of active joints. More... | |
virtual rw::kinematics::Frame * | getBase () |
a method to return the frame of the base of the device. More... | |
virtual const rw::kinematics::Frame * | getBase () const |
a method to return the frame of the base of the device. More... | |
virtual rw::kinematics::Frame * | getEnd () |
a method to return the frame of the end of the device More... | |
virtual const rw::kinematics::Frame * | getEnd () const |
a method to return the frame of the end of the device More... | |
virtual 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 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... | |
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 > | baseJCframes (const std::vector< rw::kinematics::Frame * > &frames, const rw::kinematics::State &state) const |
DeviceJacobian for a sequence of frames. 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::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... | |
const rw::core::PropertyMap & | getPropertyMap () const |
Miscellaneous properties of the device. More... | |
rw::core::PropertyMap & | getPropertyMap () |
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 Device | |
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. | |
Public Types inherited from Stateless | |
typedef rw::core::Ptr< Stateless > | Ptr |
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. | |
Provides a differential controlled mobile device.
The MobileDevice class provides a differential controlled mobile device with non-holonomic constraints. The \( x\) direction is defined as straight forward and \( z\) vertically up. The wheels are assumed to be positioned summetrically around the base and have \( 0\) \( x\) component.
When using setQ it takes 2 parameters, which corresponds to the distances travelled by the wheels. Based on this input and the current pose of the device it calcualtes a new pose as.
MobileDevice | ( | rw::kinematics::MovableFrame * | base, |
RevoluteJoint * | wheel1, | ||
RevoluteJoint * | wheel2, | ||
rw::kinematics::State & | state, | ||
const std::string & | name | ||
) |
Constructs a mobile device.
base | [in] the base of the device |
wheel1 | [in] the left wheel |
wheel2 | [in] the right wheel |
state | [in] the state of the device |
name | [in] name of device |
|
virtual |
|
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().
Implements Device.
|
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(). Not implemented.
Reimplemented from Device.
|
virtual |
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 from Device.
|
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}\)
Implements Device.
|
virtual |
|
virtual |
|
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.
Implements Device.
|
virtual |
|
virtual |
|
virtual |
|
virtual |
Gets configuration vector \( \mathbf{q}\in \mathbb{R}^n \).
state | [in] state from which which to get \( \mathbf{q} \) |
Implements Device.
|
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}\)
Implements Device.
|
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 |
Implements Device.
|
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}) \) |
void setDevicePose | ( | const rw::math::Transform3D<> & | transform, |
rw::kinematics::State & | state | ||
) |
Sets the position and orientation of the base.
This operation moves the base of the robot, without considering the non-holonomic constraints of the device
transform | [in] new base transform |
state | [in] state to write change to |
|
virtual |
|
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 |
Implements Device.