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 ¶
- Variables
- type Joint
- type Pace
- type Pose
- type Robot
- func (r *Robot) Arc(was *Pose, total float64, target Pose, axis geom.Vector, theta geom.Angle, ...) (<-chan Pace, error)
- func (r *Robot) Closest(ref *Pose, cjs [][]geom.Angle) (int, error)
- func (r *Robot) Forward(j []geom.Angle) (geom.Matrix, geom.Vector)
- func (r *Robot) Inverse(m geom.Matrix, v geom.Vector) [][]geom.Angle
- func (r *Robot) J(i int) geom.Angle
- func (r *Robot) Joined(was *Pose, total float64, target Pose, quitter <-chan struct{}) (<-chan Pace, error)
- func (r *Robot) Linear(was *Pose, total float64, target Pose, quitter <-chan struct{}) (<-chan Pace, error)
- func (r *Robot) MV() (geom.Matrix, geom.Vector)
- func (r *Robot) Near(w *Pose, total float64, a, b, c Pose, rA, rB float64, quitter <-chan struct{}) (<-chan Pace, error)
- func (r *Robot) Pose() Pose
- func (r *Robot) SetJ(i int, a geom.Angle) error
Constants ¶
This section is empty.
Variables ¶
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 Pace ¶
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 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 ¶
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 ¶
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 ¶
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 ¶
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) 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 ¶
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.