tinyrobotics
Loading...
Searching...
No Matches
kinematics.hpp File Reference

Contains functions for computing various kinematic quantities of a tinyrobotics model. More...

#include <Eigen/Core>
#include <Eigen/Geometry>
#include "math.hpp"
#include "model.hpp"

Go to the source code of this file.

Functions

template<typename Scalar , int nq, typename TargetLink >
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 between target and the base link. The transform converts points in target frame to the base link frame.
 
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 transform between target and the source link. The transform converts points in target frame to the source link frame.
 
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 between center of mass of each link and the source link.
 
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 and target center of mass. The transform converts points in the target links center of mass frame into the source link frame.
 
template<typename Scalar , int nq, typename TargetLink >
Eigen::Matrix< Scalar, 6, nq > tinyrobotics::jacobian (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 SourceLink = int>
Eigen::Matrix< Scalar, 3, 1 > tinyrobotics::center_of_mass (Model< Scalar, nq > &model, const Eigen::Matrix< Scalar, nq, 1 > &q, const SourceLink &source_link=0)
 Computes the center of mass expressed in source link frame.
 

Detailed Description

Contains functions for computing various kinematic quantities of a tinyrobotics model.

Function Documentation

◆ center_of_mass()

template<typename Scalar , int nq, typename SourceLink = int>
Eigen::Matrix< Scalar, 3, 1 > tinyrobotics::center_of_mass ( Model< Scalar, nq > &  model,
const Eigen::Matrix< Scalar, nq, 1 > &  q,
const SourceLink &  source_link = 0 
)

Computes the center of mass expressed in source link frame.

Parameters
modeltinyrobotics model.
qThe configuration vector of the robot model.
source_linkSource link, which can be an integer (index) or a string (name), from which the center of mass is expressed.
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
SourceLinkType of source_link parameter, which can be int or std::string.
Returns
The center of mass position expressed in source link frame.

◆ forward_kinematics() [1/3]

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 between target and the base link. The transform converts points in target frame to the base link frame.

Parameters
modeltinyrobotics model.
qJoint configuration of the robot.
target_linkTarget link, which can be an integer (index) or a string (name).
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
TargetLinkType of target_link parameter, which can be int or std::string.
Returns
Homogeneous transform between the target and the base link.

◆ forward_kinematics() [2/3]

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 transform between target and the source link. The transform converts points in target frame to the source link frame.

Parameters
modeltinyrobotics model.
qJoint configuration of the robot.
target_linkTarget link, which can be an integer (index) or a string (name).
source_linkSource link, which can be an integer (index) or a string (name).
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
TargetLinkType of target_link parameter, which can be int or std::string.
SourceLinkType of source_link parameter, which can be int or std::string.
Returns
Homogeneous transform between the target and the source link.

◆ forward_kinematics() [3/3]

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.

Parameters
modeltinyrobotics model.
qJoint configuration of the robot.
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
Returns
Stores the transform to all the links in model.forward_kinematics.

◆ forward_kinematics_com() [1/2]

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 and target center of mass. The transform converts points in the target links center of mass frame into the source link frame.

Parameters
modeltinyrobotics model.
qJoint configuration of the robot.
target_linkTarget link, which can be an integer (index) or a string (name).
source_linkSource link, which can be an integer (index) or a string (name).
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
TargetLinkType of target_link parameter, which can be int or std::string.
SourceLinkType of source_link parameter, which can be int or std::string.
Returns
Homogeneous transform from source link to target link center of mass.

◆ forward_kinematics_com() [2/2]

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 between center of mass of each link and the source link.

Parameters
modeltinyrobotics model.
qJoint configuration of the robot.
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
Returns
Vector of homogeneous transforms between the center of mass of each link and the source link.

◆ get_link_idx()

template<typename Scalar , int nq, typename TargetLink >
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.

Parameters
modeltinyrobotics model.
target_linkTarget link, which can be an integer (index) or a string (name).
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
TargetLinkType of target_link parameter, which can be int or std::string.
Returns
Index of the target link in the model.
Exceptions
std::invalid_argumentif the TargetLink type is not int or std::string.

◆ jacobian()

template<typename Scalar , int nq, typename TargetLink >
Eigen::Matrix< Scalar, 6, nq > tinyrobotics::jacobian ( 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.

Parameters
modeltinyrobotics model.
qJoint configuration of the robot.
target_linkTarget link, which can be an integer (index) or a string (name).
Template Parameters
Scalartype of the tinyrobotics model.
nqNumber of configuration coordinates (degrees of freedom).
TargetLinkType of target_link parameter, which can be int or std::string.
Returns
The geometric jacobian of the target link from the base link, in the base link frame.