Namespaces | Enumerations | Functions | Variables
rdl_mathutils.h File Reference
#include <assert.h>
#include <cmath>
#include "rdl_dynamics/rdl_eigenmath.h"
#include "rdl_dynamics/Quaternion.h"
Include dependency graph for rdl_mathutils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 RobotDynamics
 Namespace for all structures of the RobotDynamics library.
 
 RobotDynamics::Math
 Math types such as vectors and matrices and utility functions.
 

Enumerations

enum  RobotDynamics::Math::LinearSolver {
  RobotDynamics::Math::LinearSolverUnknown = 0, RobotDynamics::Math::LinearSolverPartialPivLU, RobotDynamics::Math::LinearSolverColPivHouseholderQR, RobotDynamics::Math::LinearSolverHouseholderQR,
  RobotDynamics::Math::LinearSolverLLT, RobotDynamics::Math::LinearSolverLast
}
 Available solver methods for the linear systems. More...
 

Functions

Vector3d RobotDynamics::Math::angular_acceleration_from_angle_rates (const Vector3d &zyx_angles, const Vector3d &zyx_angle_rates, const Vector3d &zyx_angle_rates_dot)
 
Vector3d RobotDynamics::Math::angular_velocity_from_angle_rates (const Vector3d &zyx_angles, const Vector3d &zyx_angle_rates)
 
Vector3d RobotDynamics::Math::global_angular_velocity_from_rates (const Vector3d &zyx_angles, const Vector3d &zyx_rates)
 
bool RobotDynamics::Math::linSolveGaussElimPivot (MatrixNd A, VectorNd b, VectorNd &x)
 Solves a linear system using gaussian elimination with pivoting. More...
 
MatrixNd RobotDynamics::Math::matrixFromPtr (unsigned int rows, unsigned int cols, double *ptr, bool row_major=true)
 
Matrix3d RobotDynamics::Math::parallel_axis (const Matrix3d &inertia, double mass, const Vector3d &com)
 Translates the inertia matrix to a new center. More...
 
Matrix3d RobotDynamics::Math::rotx (const double &xrot)
 
Matrix3d RobotDynamics::Math::rotxdot (const double &x, const double &xdot)
 
Matrix3d RobotDynamics::Math::roty (const double &yrot)
 
Matrix3d RobotDynamics::Math::rotydot (const double &y, const double &ydot)
 
Matrix3d RobotDynamics::Math::rotz (const double &zrot)
 
Matrix3d RobotDynamics::Math::rotzdot (const double &z, const double &zdot)
 
void RobotDynamics::Math::SparseFactorizeLTL (Model &model, Math::MatrixNd &H)
 
void RobotDynamics::Math::SparseMultiplyHx (Model &model, Math::MatrixNd &L)
 
void RobotDynamics::Math::SparseMultiplyLTx (Model &model, Math::MatrixNd &L)
 
void RobotDynamics::Math::SparseMultiplyLx (Model &model, Math::MatrixNd &L)
 
void RobotDynamics::Math::SparseSolveLTx (Model &model, Math::MatrixNd &L, Math::VectorNd &x)
 
void RobotDynamics::Math::SparseSolveLx (Model &model, Math::MatrixNd &L, Math::VectorNd &x)
 
VectorNd RobotDynamics::Math::vectorFromPtr (unsigned int n, double *ptr)
 
SpatialMatrix RobotDynamics::Math::Xrotx_mat (const double &xrot)
 Creates a rotational transformation around the X-axis. More...
 
SpatialMatrix RobotDynamics::Math::Xroty_mat (const double &yrot)
 Creates a rotational transformation around the Y-axis. More...
 
SpatialMatrix RobotDynamics::Math::Xrotz_mat (const double &zrot)
 Creates a rotational transformation around the Z-axis. More...
 
SpatialMatrix RobotDynamics::Math::Xtrans_mat (const Vector3d &displacement)
 Creates a transformation of a linear displacement. More...
 
SpatialMatrix RobotDynamics::Math::XtransRotZYXEuler (const Vector3d &displacement, const Vector3d &zyx_euler)
 Creates a spatial transformation for given parameters. More...
 

Variables

Matrix3d RobotDynamics::Math::Matrix3dIdentity
 
Matrix3d RobotDynamics::Math::Matrix3dZero
 
Quaternion RobotDynamics::Math::QuaternionIdentity
 
SpatialMatrix RobotDynamics::Math::SpatialMatrixIdentity
 
SpatialMatrix RobotDynamics::Math::SpatialMatrixZero
 
SpatialVector RobotDynamics::Math::SpatialVectorZero
 
Vector3d RobotDynamics::Math::Vector3dZero
 


rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:28