|
| std::string | name = "" |
| | **************** Model Information ****************
|
| |
|
int | n_q = 0 |
| | Number of configuration coordinates (degrees of freedom) in the model.
|
| |
|
int | base_link_idx = -1 |
| | Index of the base link in the models links vector.
|
| |
|
std::vector< int > | q_map = {} |
| | Map to indices of links in the models link vector that have a non-fixed joints.
|
| |
|
std::vector< int > | parent = {} |
| | Vector of parent link indices of the links which have a non-fixed joints.
|
| |
|
Eigen::Matrix< Scalar, 3, 1 > | gravity = {0, 0, -9.81} |
| | Gravitational acceleration vector experienced by model.
|
| |
|
Scalar | mass = 0 |
| | Total mass of the model.
|
| |
|
std::vector< Link< Scalar > > | links = {} |
| | Vector of links in the model.
|
| |
| Eigen::Matrix< Scalar, nq, nq > | mass_matrix = Eigen::Matrix<Scalar, nq, nq>::Zero() |
| | **************** Pre-allcoated variables for kinematics algorithms ****************
|
| |
|
Scalar | potential_energy = 0 |
| | Potential energy.
|
| |
|
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > | forward_kinematics = {} |
| | Vector of forward kinematics data.
|
| |
|
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > | forward_kinematics_com = {} |
| | Vector of forward kinematics com data.
|
| |
|
Eigen::Matrix< Scalar, 3, 1 > | center_of_mass = Eigen::Matrix<Scalar, 3, 1>::Zero() |
| | center of mass position
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 6 > > | Xup |
| | **************** Pre-allcoated variables for dynamics algorithms ****************
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 1 > > | S |
| | Motion subspace matrices for the joints.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 1 > > | v |
| | Spatial velocities of the robot links.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 1 > > | c |
| | Spatial acceleration bias terms for the robot links.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 6 > > | IA |
| | Articulated-body inertia matrices for the robot links.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 1 > > | pA |
| | Articulated-body forces for the robot links.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 1 > > | U |
| | Spatial force projections for the joints.
|
| |
|
std::vector< Scalar > | d = std::vector<Scalar>(nq, 0) |
| | Joint force inertia terms for the robot links.
|
| |
|
std::vector< Scalar > | u = std::vector<Scalar>(nq, 0) |
| | Joint force bias terms for the robot links.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 1 > > | a |
| | Spatial accelerations of the robot links.
|
| |
|
Eigen::Matrix< Scalar, 6, 1 > | vJ = Eigen::Matrix<Scalar, 6, 1>::Zero() |
| | Joint spatial velocities.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 1 > > | fvp |
| | Joint spatial forces.
|
| |
|
Eigen::Matrix< Scalar, nq, 1 > | C = Eigen::Matrix<Scalar, nq, 1>::Zero() |
| | Bias force vector.
|
| |
|
Eigen::Matrix< Scalar, 6, 1 > | fh = Eigen::Matrix<Scalar, 6, 1>::Zero() |
| | Force term for intermediately storing the result.
|
| |
| std::vector< Eigen::Matrix< Scalar, 6, 6 > > | IC |
| | Articulated-body inertias.
|
| |
|
Eigen::Matrix< Scalar, 6, 1 > | spatial_gravity = Eigen::Matrix<Scalar, 6, 1>::Zero() |
| | Gravity vector in spatial coordinates.
|
| |
|
Eigen::Matrix< Scalar, 6, nq > | J = Eigen::Matrix<Scalar, 6, nq>::Zero() |
| | Jacobian.
|
| |
|
Eigen::Matrix< Scalar, nq, 1 > | ddq = Eigen::Matrix<Scalar, nq, 1>::Zero() |
| | Joint acceleration.
|
| |
|
Eigen::Matrix< Scalar, nq, 1 > | tau = Eigen::Matrix<Scalar, nq, 1>::Zero() |
| | Joint torque/force.
|
| |
template<typename Scalar, int nq>
struct tinyrobotics::Model< Scalar, nq >
A tinyrobotics model.
A tinyrobotics model is a collection of links and joints that represents a robot.
- Template Parameters
-
| Scalar | The scalar type for the model. |
| nq | The number of configuration coordinates (number of degrees of freedom). |