Main Content

geometricJacobian

Geometric Jacobian for robot configuration

Description

jacobian = geometricJacobian(robot,configuration,endeffectorname) computes the geometric Jacobian relative to the base for the specified end-effector name and configuration for the robot model.

example

jacobian = geometricJacobian(robot,configuration,framename) computes the geometric Jacobian for the frame specified by framename.

example

Examples

collapse all

Calculate the geometric Jacobian for a specific end effector and configuration of a robot.

Load a PUMA 560 robot from the Robotics System Toolbox™ loadrobot, specified as a rigidBodyTree object.

puma = loadrobot("puma560");

Calculate the geometric Jacobian of body "link7" on the Puma robot for a random configuration.

geoJacob = geometricJacobian(puma,randomConfiguration(puma),"link7")
geoJacob = 6×6

   -0.0000   -0.5752   -0.5752   -0.4266   -0.7683   -0.5213
    0.0000    0.8180    0.8180   -0.3000   -0.3776    0.8377
    1.0000   -0.0000   -0.0000    0.8533   -0.5168    0.1629
    0.1696    0.0823    0.3087   -0.0407    0.0198         0
   -0.5577    0.0578    0.2171   -0.0200    0.0210         0
    0.0000    0.5538    0.2224   -0.0274   -0.0448         0

Input Arguments

collapse all

Robot model, specified as a rigidBodyTree object.

Robot configuration, specified as a vector of joint positions or a structure with joint names and positions for all the bodies in the robot model. You can generate a configuration using homeConfiguration(robot), randomConfiguration(robot), or by specifying your own joint positions in a structure. To use the vector form of configuration, set the DataFormat property for robot to either "row" or "column".

End-effector name, specified as a string scalar or character vector. An end effector can be any body in the robot model.

Data Types: char | string

Frame name, specified as a string scalar or character vector. This frame can be any frame in the robot model.

Data Types: char | string

Output Arguments

collapse all

Geometric Jacobian of the end effector with the specified configuration, returned as a 6-by-n matrix, where n is the number of degrees of freedom of the robot. The Jacobian maps the joint-space velocity to the end-effector velocity, relative to the base coordinate frame. The end-effector velocity equals:

Equation for calculating linear velocities of the end effector using the Jacobian and joint velocities

ω is the angular velocity, υ is the linear velocity, and is the joint-space velocity.

More About

collapse all

References

[1] Featherstone, Roy. Rigid Body Dynamics Algorithms. Springer US, 2008. DOI.org (Crossref), doi:10.1007/978-1-4899-7560-7.

Extended Capabilities

expand all

Version History

Introduced in R2016b

expand all