sixaxis

package module
v0.5.0 Latest Latest
Warning

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

Go to latest
Published: Jun 1, 2021 License: BSD-3-Clause Imports: 4 Imported by: 0

README

sixaxis is a package for solving the pose of a 6 axis robot

Overview

This package solves the forward and inverse kinematics of a 6 axis robot.

License info

The sixaxis package is distributed with the same BSD 3-clause license as that used by golang itself.

Reporting bugs

Use the github sixaxis bug tracker.

Documentation

Overview

Package sixaxis does forward and inverse kinematics for a six axis robot defined as a sequence of radial joints.

The radial joints are arranged in the following global coordinates with the robot in its "all angles zero" pose (all joints point arm segment up in positive Z direction).

J0 = rotate around Z axis an arm segment of length d0
J1 = rotate around X axis an arm segment of length d1
J2 = rotate around X axis an arm segment of length d2
J3 = rotate around Z axis an arm segment of length d3
J4 = rotate around X axis an arm segment of length d4
J5 = rotate around Z axis an arm segment of length d5 = 0

Index

Constants

This section is empty.

Variables

View Source
var (
	ErrBadJoint   = errors.New("invalid joint")
	ErrLimit      = errors.New("paramter outside joint range")
	ErrNoSolution = errors.New("no inverse kinimatics solution")
)

Err* are the errors exported by this package.

Functions

This section is empty.

Types

type Joint

type Joint struct {
	Min, Max geom.Angle
	Rot      func(a geom.Angle) geom.Matrix
	Offset   float64
}

Joint holds a robot joint configuration.

type Pace

type Pace struct {
	Frac float64
	J    []geom.Angle
}

Pace represents a fraction completed of a linear path between two poses in terms of a number [0,1] and a collection of joint angles for the robot.

type Pose

type Pose struct {
	M geom.Matrix
	V geom.Vector
	J []geom.Angle
}

Pose holds the current pose of the robot in both cartesian and joint coordinates.

type Robot

type Robot struct {

	// Precision holds the dtheta precision of the robot. It
	// defaults to geom.Zeroish fraction of a full rotation.
	Precision geom.Angle
	// contains filtered or unexported fields
}

Robot holds the combined geometric state of a robot.

func NewRobot

func NewRobot(js ...Joint) (*Robot, error)

NewRobot specifies the joints for a robot. Its default pose is all joint parameters are zero.

func (*Robot) Arc

func (r *Robot) Arc(was *Pose, total float64, target Pose, axis geom.Vector, theta geom.Angle, quitter <-chan struct{}) (<-chan Pace, error)

Arc returns a channel over which a set of paces map out a linearly interpolatable set of joint poses that map out an arc that join was to target. The plane of said arc is perpendicular to axis, and the angle of the arc is theta.

func (*Robot) Closest

func (r *Robot) Closest(ref *Pose, cjs [][]geom.Angle) (int, error)

Closest picks the closest pose to the ref (or if ref is nil the current) pose from a list of equivalent joint positions. This function currently treats all joints with equal weight.

func (*Robot) Forward

func (r *Robot) Forward(j []geom.Angle) (geom.Matrix, geom.Vector)

Forward evaluates the forward kinematics for a set of joint angles and returns the basis and vector of the face-plate. It does not alter the working pose of the robot.

func (*Robot) Inverse

func (r *Robot) Inverse(m geom.Matrix, v geom.Vector) [][]geom.Angle

Inverse computes the potential set of inverse kinematics for a target RV pose. It is the responsibility of the client to pick which of the solutions to use. If no angle selections are returned there are no solutions.

func (*Robot) J

func (r *Robot) J(i int) geom.Angle

J returns the joint parameter for the specified joint.

func (*Robot) Joined

func (r *Robot) Joined(was *Pose, total float64, target Pose, quitter <-chan struct{}) (<-chan Pace, error)

Joined translates a destination pose into a Pace over a channel.

func (*Robot) Linear

func (r *Robot) Linear(was *Pose, total float64, target Pose, quitter <-chan struct{}) (<-chan Pace, error)

Linear returns a channel over which a backgrounded function forwards a sequence of joint angle poses to move linearly between the initial robot pose and the target pose. The function terminates and closes the channel to signal early exit if the quitter channel is closed. Total is the range over which we report fractional progress at each pose.

func (*Robot) MV

func (r *Robot) MV() (geom.Matrix, geom.Vector)

MV returns the orientation and offset of the J5 face-plate of robot. This is equal to the last forward kinematics solution for the robot's pose.

func (*Robot) Near

func (r *Robot) Near(w *Pose, total float64, a, b, c Pose, rA, rB float64, quitter <-chan struct{}) (<-chan Pace, error)

Near determines a multi-segment path based on three consecutive target poses (a,b,c) and two nearness thresholds parameterizing how much to cut off the corners (rA, rB). The start location, w, need not be any of these poses. The result of the generated paces is to adopt a pose near to b (at z), with b's M value.

The path goes, w (curve to) x (line to) y (curve to) z. Where xy follows the middle segment of ab. If w is on (ab) then the (curve to) x is interpreted as linear.

In all cases, the final location, z, is such that stitching together calls to Near will yield continuous motion. That is, z is computed purely based on a,b,c and not w.

For each rounded corner, we do not use an arc, but a parameterized sum of the nearby vectors. The parameterization has w and z at the 50% parameterization.

func (*Robot) Pose

func (r *Robot) Pose() Pose

Pose returns the current pose of the robot.

func (*Robot) SetJ

func (r *Robot) SetJ(i int, a geom.Angle) error

SetJ forces the joint of the robot to a joint parameter value. An error is returned if the joint cannot adopt that paramter because of a range limit.

Jump to

Keyboard shortcuts

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