kinematics

package module
v1.0.2 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Sep 21, 2021 License: MIT Imports: 5 Imported by: 1

README

Kinematics

Build Status Coverage Status godocs.io

This repo contains the code for the Golang kinematics library, which implements forward and inverse kinematics for robotic arms. We provide default parameters for the AR2 / AR3 robotic arm from Annin Robotics, but other parameters can be used for other arms.

Package documentation can be found at pkg.go.dev or godoc.io

Documentation

Overview

Package kinematics calculates forward and inverse kinematics for robotic arm systems.

Forward kinematics takes joint angles and returns the end effector Pose. Inverse kinematics takes a Pose and returns joint angles that move the end effector to that Pose.

ForwardKinematics (joint angles	-> Pose)
InverseKinematics (Pose	-> joint angles)

Each function also requires a Denavit-Hartenberg Parameter set for the arm of interest. This package provides defaults for the following arm systems:

AR2/AR3

Index

Examples

Constants

This section is empty.

Variables

View Source
var MaxInverseKinematicIteration int = 50

MaxInverseKinematicIteration is the max number of times InverseKinematics should try new seeds before failing. 50 is used here because it is approximately the number of iterations that will take 1 second to compute.

Functions

This section is empty.

Types

type DhParameters

type DhParameters struct {
	ThetaOffsets [6]float64
	AlphaValues  [6]float64
	AValues      [6]float64
	DValues      [6]float64
}

DhParameters stand for "Denavit-Hartenberg Parameters". These parameters define a robotic arm for input into forward or reverse kinematics.

var AR3DhParameters DhParameters = DhParameters{
	ThetaOffsets: [...]float64{0, 0, -math.Pi / 2, 0, 0, math.Pi},
	AlphaValues:  [...]float64{-(math.Pi / 2), 0, math.Pi / 2, -(math.Pi / 2), math.Pi / 2, 0},
	AValues:      [...]float64{64.2, 305, 0, 0, 0, 0},
	DValues:      [...]float64{169.77, 0, 0, -222.63, 0, -36.25},
}

Denavit-Hartenberg Parameters of AR3 provided by AR2 Version 2.0 software executable files from https://www.anninrobotics.com/downloads Those parameters are the same between the AR2 and AR3.

type JointAngles added in v1.0.1

type JointAngles struct {
	J1 float64
	J2 float64
	J3 float64
	J4 float64
	J5 float64
	J6 float64
}

JointAngles represents angles of the joints in radians.

func InverseKinematics

func InverseKinematics(desiredEndEffector Pose, dhParameters DhParameters,
	thetasInit JointAngles) (JointAngles, error)

InverseKinematics calculates joint angles to achieve an end effector Pose given the desired Pose coordinates, the robotic DH parameters and a starting set of joint angles

Example
package main

import (
	"fmt"
	"github.com/koeng101/kinematics"
)

func main() {
	// Establish the original joint angles
	thetasInit := kinematics.JointAngles{0, 0, 0, 0, 0, 0}

	// Establish coordinates to go to
	coordinates := kinematics.Pose{Position: kinematics.Position{X: -100, Y: 250, Z: 250}, Rotation: kinematics.Quaternion{W: 0.41903052745255764, X: 0.4007833787652043, Y: -0.021233218878182854, Z: 0.9086418268616911}}

	// Run kinematics procedure
	angles, _ := kinematics.InverseKinematics(coordinates, kinematics.AR3DhParameters, thetasInit)

	// Math works slightly differently on arm and x86 machines when calculating
	// inverse kinematics. We check 5 decimals deep, since it appears numbers can
	// have slight variations between arm and x86 at 6 decimals.
	fmt.Printf("%5f, %5f, %5f, %5f, %5f, %5f\n", angles.J1, angles.J2, angles.J3, angles.J4, angles.J5, angles.J6)
}
Output:

1.846274, 0.341672, -2.313720, -1.776501, 2.221810, 1.231879

type Pose added in v1.0.1

type Pose struct {
	Position Position
	Rotation Quaternion
}

Pose represents a position and rotation, where Position is the translational component, and Rot is the quaternion representing the rotation.

func ForwardKinematics

func ForwardKinematics(thetas JointAngles, dhParameters DhParameters) Pose

ForwardKinematics calculates the end effector Pose coordinates given joint angles and robotic arm parameters.

Example
package main

import (
	"fmt"
	"github.com/koeng101/kinematics"
)

func main() {
	angles := kinematics.JointAngles{J1: 10, J2: 1, J3: 1, J4: 0, J5: 0, J6: 0}
	coordinates := kinematics.ForwardKinematics(angles, kinematics.AR3DhParameters)

	fmt.Println(coordinates)
	// Output {{-101.74590611879692 -65.96805988175777 -322.27756822304093} {0.06040824945687102 -0.20421099379003957 0.2771553334491873 0.9369277637862541}}
}
Output:

type Position added in v1.0.1

type Position struct {
	X float64
	Y float64
	Z float64
}

Position represents a position in 3D cartesian space.

type Quaternion added in v1.0.1

type Quaternion struct {
	W float64
	X float64
	Y float64
	Z float64
}

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL