dh_jacobian Interface

public interface dh_jacobian

Contents


Module Procedures

private function dh_build_jacobian(alpha, a, theta, d, jtypes) result(rst)

Builds the Jacobian matrix for a linkage given the Denavit-Hartenberg parameters. The first entry in each array must be from the first link nearest ground. The Jacobian matrix relates the joint velocities to the end-effector velocity by .

Arguments

Type IntentOptional Attributes Name
real(kind=real64), intent(in), dimension(:) :: alpha

The link twist angles, in radians. This angle is the required rotation of the z(i-1) axis about the link's x-axis to become parallel with the link's z-axis.

real(kind=real64), intent(in), dimension(size(alpha)) :: a

The link lengths as measured along the link's x-axis.

real(kind=real64), intent(in), dimension(size(alpha)) :: theta

The joint angles, in radians. This angle is the required rotation of the z(i-1) axis about the z(i-1) axis to become parallel with the link's x-axis.

real(kind=real64), intent(in), dimension(size(alpha)) :: d

The joint offsets distance measured as the distance between the x(i-1) axis and the link's x-axis along the z(i-1) axis.

integer(kind=int32), intent(in), dimension(size(alpha)) :: jtypes

The types of each joint. Must be either REVOLUTE_JOINT or PRISMATIC_JOINT. The code defaults to REVOLUTE_JOINT.

Return Value real(kind=real64), allocatable, dimension(:,:)

The resulting 6-by-N Jacobian matrix where N is the number of joint variables (i.e. the length of the input arrays).