tinyrobotics
|
Contains functions for computing various kinematic quantities of a tinyrobotics model. More...
Go to the source code of this file.
Functions | |
template<typename Scalar , int nq, typename TargetLink > | |
const int | tinyrobotics::get_link_idx (const Model< Scalar, nq > &model, const TargetLink &target_link) |
Retrieves the index of the target link in the tinyrobotics model. | |
template<typename Scalar , int nq> | |
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > | tinyrobotics::forward_kinematics (Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q) |
Computes the transform to all the links in the tinyrobotics model. | |
template<typename Scalar , int nq, typename TargetLink > | |
Eigen::Transform< Scalar, 3, Eigen::Isometry > | tinyrobotics::forward_kinematics (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const TargetLink &target_link) |
Computes the transform to the target from the base link. | |
template<typename Scalar , int nq, typename TargetLink , typename SourceLink > | |
Eigen::Transform< Scalar, 3, Eigen::Isometry > | tinyrobotics::forward_kinematics (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const TargetLink &target_link, const SourceLink &source_link) |
Computes the homogeneous transform from a source to target link. | |
template<typename Scalar , int nq> | |
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > | tinyrobotics::forward_kinematics_com (Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q) |
Computes the transform to centre of mass of all the links in the tinyrobotics model. | |
template<typename Scalar , int nq, typename TargetLink , typename SourceLink = int> | |
Eigen::Transform< Scalar, 3, Eigen::Isometry > | tinyrobotics::forward_kinematics_com (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const TargetLink &target_link, const SourceLink &source_link=0) |
Computes the transform between source link {s} and target {t} centre of mass (CoM) {c}. | |
template<typename Scalar , int nq, typename TargetLink , typename SourceLink = int> | |
Eigen::Matrix< Scalar, 3, 1 > | tinyrobotics::translation (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const TargetLink &target_link, const SourceLink &source_link=0) |
Computes the translation of the target link from the source link in the source link frame. | |
template<typename Scalar , int nq, typename TargetLink , typename SourceLink = int> | |
Eigen::Matrix< Scalar, 3, 3 > | tinyrobotics::rotation (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const TargetLink &target_link, const SourceLink &source_link=0) |
Computes the rotation matrix between the target link and the source link in the source link frame. | |
template<typename Scalar , int nq, typename TargetLink > | |
Eigen::Matrix< Scalar, 6, nq > | tinyrobotics::geometric_jacobian (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const TargetLink &target_link) |
Computes the geometric jacobian of the target link from the base link in the base link frame. | |
template<typename Scalar , int nq, typename TargetLink > | |
Eigen::Matrix< Scalar, 6, nq > | tinyrobotics::geometric_jacobian_com (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const TargetLink &target_link) |
Computes the geometric jacobian relative to the base for the specified target link's center of mass. | |
template<typename Scalar , int nq, typename SourceLink = int> | |
Eigen::Matrix< Scalar, 3, 1 > | tinyrobotics::centre_of_mass (const Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const SourceLink &source_link=0) |
Computes the centre of mass expressed in source link frame. | |
Contains functions for computing various kinematic quantities of a tinyrobotics model.
Eigen::Matrix< Scalar, 3, 1 > tinyrobotics::centre_of_mass | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const SourceLink & | source_link = 0 |
||
) |
Computes the centre of mass expressed in source link frame.
model | tinyrobotics model. |
q | The configuration vector of the robot model. |
source_link | Source link, which can be an integer (index) or a string (name), from which the centre of mass is expressed. |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
SourceLink | Type of source_link parameter, which can be int or std::string. |
Eigen::Transform< Scalar, 3, Eigen::Isometry > tinyrobotics::forward_kinematics | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const TargetLink & | target_link | ||
) |
Computes the transform to the target from the base link.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
Eigen::Transform< Scalar, 3, Eigen::Isometry > tinyrobotics::forward_kinematics | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const TargetLink & | target_link, | ||
const SourceLink & | source_link | ||
) |
Computes the homogeneous transform from a source to target link.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
source_link | Source link, which can be an integer (index) or a string (name). |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
SourceLink | Type of source_link parameter, which can be int or std::string. |
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > tinyrobotics::forward_kinematics | ( | Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q | ||
) |
Computes the transform to all the links in the tinyrobotics model.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
Eigen::Transform< Scalar, 3, Eigen::Isometry > tinyrobotics::forward_kinematics_com | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const TargetLink & | target_link, | ||
const SourceLink & | source_link = 0 |
||
) |
Computes the transform between source link {s} and target {t} centre of mass (CoM) {c}.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
source_link | Source link, which can be an integer (index) or a string (name). |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
SourceLink | Type of source_link parameter, which can be int or std::string. |
std::vector< Eigen::Transform< Scalar, 3, Eigen::Isometry > > tinyrobotics::forward_kinematics_com | ( | Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q | ||
) |
Computes the transform to centre of mass of all the links in the tinyrobotics model.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
Eigen::Matrix< Scalar, 6, nq > tinyrobotics::geometric_jacobian | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const TargetLink & | target_link | ||
) |
Computes the geometric jacobian of the target link from the base link in the base link frame.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
Eigen::Matrix< Scalar, 6, nq > tinyrobotics::geometric_jacobian_com | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const TargetLink & | target_link | ||
) |
Computes the geometric jacobian relative to the base for the specified target link's center of mass.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
const int tinyrobotics::get_link_idx | ( | const Model< Scalar, nq > & | model, |
const TargetLink & | target_link | ||
) |
Retrieves the index of the target link in the tinyrobotics model.
model | tinyrobotics model. |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
std::invalid_argument | if the TargetLink type is not int or std::string. |
Eigen::Matrix< Scalar, 3, 3 > tinyrobotics::rotation | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const TargetLink & | target_link, | ||
const SourceLink & | source_link = 0 |
||
) |
Computes the rotation matrix between the target link and the source link in the source link frame.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
source_link | Source link, which can be an integer (index) or a string (name). |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
SourceLink | Type of source_link parameter, which can be int or std::string. |
Eigen::Matrix< Scalar, 3, 1 > tinyrobotics::translation | ( | const Model< Scalar, nq > & | model, |
const Eigen::Matrix< Scalar, nq, 1 > & | q, | ||
const TargetLink & | target_link, | ||
const SourceLink & | source_link = 0 |
||
) |
Computes the translation of the target link from the source link in the source link frame.
model | tinyrobotics model. |
q | Joint configuration of the robot. |
source_link | Source link, which can be an integer (index) or a string (name). |
target_link | Target link, which can be an integer (index) or a string (name). |
Scalar | type of the tinyrobotics model. |
nq | Number of configuration coordinates (degrees of freedom). |
TargetLink | Type of target_link parameter, which can be int or std::string. |
SourceLink | Type of source_link parameter, which can be int or std::string. |