| 
    wbc
    
   | 
 
Classes | |
| class | Contact | 
| Describes a rigid contact between a robot link and the environment. This can be either a point or surface contact.  More... | |
| class | JointCommand | 
| class | JointLimits | 
| class | JointState | 
| The JointState class describes either the state or the command for a set of joints, i.e., its actual or target position, velocity, acceleration and effort.  More... | |
| class | Limits | 
| class | Pose | 
| class | RigidBodyState | 
| class | SpatialAcceleration | 
| class | Twist | 
| class | Wrench | 
Enumerations | |
| enum | CommandMode {  UNSET = -1 , POSITION = 0 , VELOCITY = 1 , ACCELERATION = 2 , EFFORT = 3 }  | 
Functions | |
| SpatialAcceleration | operator* (const Pose &transform, const SpatialAcceleration &acc_in) | 
| Twist | operator* (const Pose &transform, const Twist &twist_in) | 
| types::Twist | operator- (const types::Pose &a, const types::Pose &b) | 
| Wrench | operator* (const Pose &transform, const Wrench &wrench_in) | 
| SpatialAcceleration wbc::types::operator* | ( | const Pose & | transform, | 
| const SpatialAcceleration & | acc_in ) | 
Transform of a spatial acceleration from a coordinate frame A to another coordinate frame B. The mapping is performed using the adjoint \( Adj(X) \in R^{6 \times 6} \) of the given input transform \(X = (R,p) \in SE(3)\) as follows:
\[ \left(\begin{array}{cc} \dot{\omega} \\ \dot{v} \end{array}\right)_B = \left(\begin{array}{cc} R & 0 \\ \left[p\right]R & R \end{array}\right) \left(\begin{array}{cc} \dot{\omega} \\ \dot{v} \end{array}\right)_A \]
 with 
   
\[ \left[p\right] = \left(\begin{array}{ccc}0 & -p_z & p_y \\ p_z & 0 &-p_x \\ -p_y & p_x & 0\end{array}\right) \]
 and 
 \( \dot{\omega} \in R^3\) - Angular acceleration 
 \( \dot{v} \in R^3\) - Linear acceleration 
 \( R \in SO(3)\) - Rotation matrix 
 \( p \in R^3\) - Translation vector 
 *According to: Lynch, K.M. and Park, F.C. 2017. Modern Robotics: Mechanics, Planning, and Control. page 100. Cambridge University Press, USA 
| transform | Input transform as position and orientation of frame A expressed in frame B (not vice versa!) | 
| acc_in | Input spatial acceleration, expressed in coordinate frame A | 
Transform of a twist \( V = (\omega,v)^T \) from a coordinate frame A to another coordinate frame B. The mapping is performed using the adjoint \( Adj(X) \in R^{6 \times 6} \) of the given input transform \(X = (R,p) \in SE(3)\) as follows*:
\[ \left(\begin{array}{cc} \omega \\ v \end{array}\right)_B = \left(\begin{array}{cc} R & 0 \\ \left[p\right]R & R \end{array}\right) \left(\begin{array}{cc} \omega \\ v \end{array}\right)_A \]
 with 
   
\[ \left[p\right] = \left(\begin{array}{ccc}0 & -p_z & p_y \\ p_z & 0 &-p_x \\ -p_y & p_x & 0\end{array}\right) \]
 and 
 \( \omega \in R^3\) - Angular velocity 
 \( v \in R^3\) - Linear velocity 
 \( R \in SO(3)\) - Rotation matrix 
 \( p \in R^3\) - Translation vector 
 *According to: Lynch, K.M. and Park, F.C. 2017. Modern Robotics: Mechanics, Planning, and Control. page 100. Cambridge University Press, USA 
| transform | Input transform as position and orientation of frame A expressed in frame B (not vice versa!) | 
| twist_in | Input twist, expressed in coordinate frame A | 
Transform of a wrench \( F = (m,f)^T \) from a coordinate frame A to another coordinate frame B. The mapping is performed using the co-adjoint \( Adj(X)^{-T} \in R^{6 \times 6} \) of the given input transform \(X = (R,p) \in SE(3)\) as follows*:
\[ \left(\begin{array}{cc} m \\ f \end{array}\right)_B = \left(\begin{array}{cc} R & \left[p\right]R \\ 0 & R \end{array}\right) \left(\begin{array}{cc} m \\ f \end{array}\right)_A \]
 with 
   
\[ \left[p\right] = \left(\begin{array}{ccc}0 & -p_z & p_y \\ p_z & 0 &-p_x \\ -p_y & p_x & 0\end{array}\right) \]
 and 
 \( m \in R^3\) - Torque/moment 
 \( f \in R^3\) - Linear force 
 \( R \in SO(3)\) - Rotation matrix 
 \( p \in R^3\) - Translation vector 
 *According to: Lynch, K.M. and Park, F.C. 2017. Modern Robotics: Mechanics, Planning, and Control. page 110. Cambridge University Press, USA 
| transform | Input transform as position and orientation of frame A expressed in frame B (not vice versa!) | 
| wrench_in | Input twist, expressed in coordinate frame A | 
| types::Twist wbc::types::operator- | ( | const types::Pose & | a, | 
| const types::Pose & | b ) |