modern_robotics
Functions
Chapter 5: Velocity Kinematics and Statics

Functions

const arma::mat mr::JacobianBody (const std::vector< arma::vec6 > &Blist, const arma::vec &thetalist)
 Computes the body Jacobian for an open chain robot. More...
 
const arma::mat mr::JacobianSpace (const std::vector< arma::vec6 > &Slist, const arma::vec &thetalist)
 Computes the space Jacobian for an open chain robot. More...
 

Detailed Description

Function Documentation

◆ JacobianBody()

const arma::mat mr::JacobianBody ( const std::vector< arma::vec6 > &  Blist,
const arma::vec &  thetalist 
)

Computes the body Jacobian for an open chain robot.

Parameters
BlistThe joint screw axes in the end-effector frame when the manipulator is at the home position, in the format of a matrix with axes as the columns
thetalistA list of joint coordinates
Returns
The body Jacobian corresponding to the inputs (6xn real numbers)

◆ JacobianSpace()

const arma::mat mr::JacobianSpace ( const std::vector< arma::vec6 > &  Slist,
const arma::vec &  thetalist 
)

Computes the space Jacobian for an open chain robot.

Parameters
SlistThe joint screw axes in the space frame when the manipulator is at the home position, in the format of a matrix with axes as the columns
thetalistA list of joint coordinates
Returns
The space Jacobian corresponding to the inputs (6xn real numbers)