Documentation
¶
Overview ¶
Package ar3 is a Golang library implementing serial commands for the AR3 robotic arm.
Basics ¶
The AR3 robotic arm is a low cost + open source 6 axis robotic arm designed and created by Chris Annin of Annin Robotics. Annin Robotics provides software for operating the robotic arm, but this software is designed for windows and is not useful for devices for like raspberry pis.
This Golang library takes over for the local robotic control software by implementing the functions needed to communicate with the arduino on the AR3 or AR2 robot.
We do not yet support encoders in the AR3, nor any other commands. All other rountines can be reproduced in code and not directly on the robot.
Testing ¶
Testing can be done with the AR3simulate struct, which satisfies all of the interfaces of AR3. For real connection to a robot, use connect to the robot using `Connect` instead of `ConnectMock`.
Compatibility ¶
The code here is only designed to function on linux machines directly connected to the AR3 robotic arm. It uses a couple of serial port configuration variables specific to linux systems. We use as few packages as possible, with the only non-standard package being golang.org/x/sys/unix, which carries unix file variables that help us open the serial port.
Example (Basic) ¶
This example shows basic connection to the robot.
package main import ( "fmt" "github.com/koeng101/ar3" ) func main() { arm := ar3.ConnectMock() // arm := ar3.Connect("/dev/ttyUSB0") // Move the arm. First 5 are rational defaults, following 6 numbers are joint stepper counts, and the final is the track length. _ = arm.MoveSteppers(25, 15, 10, 20, 5, 500, 500, 500, 500, 500, 500, 0) fmt.Println("Moved arm!") }
Output: Moved arm!
Index ¶
- Variables
- type AR3exec
- func (ar3 *AR3exec) Calibrate(speed int, j1, j2, j3, j4, j5, j6, tr bool) error
- func (ar3 *AR3exec) CurrentJointRadians() [7]float64
- func (ar3 *AR3exec) CurrentPose() kinematics.Pose
- func (ar3 *AR3exec) CurrentStepperPosition() [7]int
- func (ar3 *AR3exec) Echo() error
- func (ar3 *AR3exec) GetDirections() [7]bool
- func (ar3 *AR3exec) Move(speed, accdur, accspd, dccdur, dccspd int, pose kinematics.Pose) error
- func (ar3 *AR3exec) MoveJointRadians(speed, accdur, accspd, dccdur, dccspd int, j1, j2, j3, j4, j5, j6, tr float64) error
- func (ar3 *AR3exec) MoveSteppers(speed, accdur, accspd, dccdur, dccspd, j1, j2, j3, j4, j5, j6, tr int) error
- func (ar3 *AR3exec) SetDirections(jointDirs [7]bool)
- type AR3simulate
- func (ar3 *AR3simulate) Calibrate(speed int, j1, j2, j3, j4, j5, j6, tr bool) error
- func (ar3 *AR3simulate) CurrentJointRadians() [7]float64
- func (ar3 *AR3simulate) CurrentPose() kinematics.Pose
- func (ar3 *AR3simulate) CurrentStepperPosition() [7]int
- func (ar3 *AR3simulate) Echo() error
- func (ar3 *AR3simulate) GetDirections() [7]bool
- func (ar3 *AR3simulate) Move(speed, accdur, accspd, dccdur, dccspd int, pose kinematics.Pose) error
- func (ar3 *AR3simulate) MoveJointRadians(speed, accdur, accspd, dccdur, dccspd int, j1, j2, j3, j4, j5, j6, tr float64) error
- func (ar3 *AR3simulate) MoveSteppers(speed, accdur, accspd, dccdur, dccspd, j1, j2, j3, j4, j5, j6, tr int) error
- func (ar3 *AR3simulate) SetDirections(jointDirs [7]bool)
- type Arm
Examples ¶
Constants ¶
This section is empty.
Variables ¶
var AR3DhParameters kinematics.DhParameters = kinematics.DhParameters{ ThetaOffsets: [...]float64{0, -math.Pi / 2, 0, 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.
Functions ¶
This section is empty.
Types ¶
type AR3exec ¶
type AR3exec struct {
// contains filtered or unexported fields
}
AR3exec struct represents an AR3 robotic arm connected to a serial port.
func Connect ¶
func Connect(serialConnectionStr string, jointDirs [7]bool, limitSwitchSteps [7]int) (*AR3exec, error)
Connect connects to the AR3 over serial.
jointDirs is a boolean array describing which direction (positive or negative) a positive step number should move each joint.
limitSwitchSteps is an array of integers representing the number of steps the limit switch is offset from zero. Each value should be directional, i.e. the value should be the directional number of steps to move the joint from the limit switch to the 0 position. If you do not know this number, set limitSwitchSteps all to 0 and immediately calibrate.
func (*AR3exec) Calibrate ¶
Calibrate moves each of the AR3's stepper motors to their respective limit switch. A good default speed for this action is 50 (line 4659 on ARCS). Set the j1 -> j6 booleans "true" if that joint should be homed. Set the j1calibdir -> j6calibdir booleans "true" if the calibration direction should be in the negative axis direction.
func (*AR3exec) CurrentJointRadians ¶
CurrentJointRadians returns the current joint angles from the zero joint value This is different than CurrentStepperPositions which returns values from the limit switch zeroed positions, as these values are offset by the limitSwitchSteps array.
func (*AR3exec) CurrentPose ¶
func (ar3 *AR3exec) CurrentPose() kinematics.Pose
CurrentPose returns the current Pose of the robot, using forward kinematics on the DH parameters and current joint angles.
func (*AR3exec) CurrentStepperPosition ¶
CurrentStepperPosition returns the current position of the AR3 arm as stepper motor steps from the zeroed value for each axis.
func (*AR3exec) Echo ¶
Echo tests an echo command on the AR3. Useful for testing connectivity to the AR3.
func (*AR3exec) GetDirections ¶
GetDirections gets the directions of the AR3 arm.
func (*AR3exec) Move ¶
func (ar3 *AR3exec) Move(speed, accdur, accspd, dccdur, dccspd int, pose kinematics.Pose) error
Move to a new end effector Pose using inverse kinematics to solve for the joint angles.
func (*AR3exec) MoveJointRadians ¶
func (ar3 *AR3exec) MoveJointRadians(speed, accdur, accspd, dccdur, dccspd int, j1, j2, j3, j4, j5, j6, tr float64) error
MoveJointRadians moves each of the AR3's joints to an absolute angle defined relative to the calibration position for each joint. Angles are defined as radians here.
func (*AR3exec) MoveSteppers ¶
func (ar3 *AR3exec) MoveSteppers(speed, accdur, accspd, dccdur, dccspd, j1, j2, j3, j4, j5, j6, tr int) error
MoveSteppers moves each of the AR3's stepper motors to a relative step position between 0 and the step limit for each joint. See moveSteppersRelative for full documentation of arguments.
func (*AR3exec) SetDirections ¶
SetDirections sets the directions of the AR3 arm.
type AR3simulate ¶
type AR3simulate struct {
// contains filtered or unexported fields
}
AR3simulate struct represents an AR3 robotic arm interface for testing purposes.
func ConnectMock ¶
func ConnectMock() *AR3simulate
ConnectMock connects to a mock AR3simulate interface.
func (*AR3simulate) Calibrate ¶
func (ar3 *AR3simulate) Calibrate(speed int, j1, j2, j3, j4, j5, j6, tr bool) error
Calibrate simulates AR3exec.Calibrate()
Example ¶
arm := ConnectMock() // Calibrate the arm. 50 is a good default speed. err := arm.Calibrate(50, true, true, true, true, true, true, true) if err == nil { fmt.Println("Calibrated") }
Output: Calibrated
func (*AR3simulate) CurrentJointRadians ¶
func (ar3 *AR3simulate) CurrentJointRadians() [7]float64
CurrentJointRadians simulates AR3exec.CurrentJointRadians().
func (*AR3simulate) CurrentPose ¶
func (ar3 *AR3simulate) CurrentPose() kinematics.Pose
CurrentPose simulates AR3exec.CurrentPose()
func (*AR3simulate) CurrentStepperPosition ¶
func (ar3 *AR3simulate) CurrentStepperPosition() [7]int
CurrentStepperPosition simulates AR3exec.CurrentStepperPosition().
Example ¶
arm := ConnectMock() // Current position. By default, the arm is assumed to be homed at 0 jointVals := arm.CurrentStepperPosition() if jointVals[0] == 0 { fmt.Println("At 0") }
Output: At 0
func (*AR3simulate) GetDirections ¶
func (ar3 *AR3simulate) GetDirections() [7]bool
GetDirections simulates AR3exec.GetDirections().
func (*AR3simulate) Move ¶
func (ar3 *AR3simulate) Move(speed, accdur, accspd, dccdur, dccspd int, pose kinematics.Pose) error
Move to a new end effector Pose using inverse kinematics to solve for the joint angles.
func (*AR3simulate) MoveJointRadians ¶
func (ar3 *AR3simulate) MoveJointRadians(speed, accdur, accspd, dccdur, dccspd int, j1, j2, j3, j4, j5, j6, tr float64) error
MoveJointRadians simulates AR3exec.MoveJointRadians
func (*AR3simulate) MoveSteppers ¶
func (ar3 *AR3simulate) MoveSteppers(speed, accdur, accspd, dccdur, dccspd, j1, j2, j3, j4, j5, j6, tr int) error
MoveSteppers simulates AR3exec.MoveSteppers().
func (*AR3simulate) SetDirections ¶
func (ar3 *AR3simulate) SetDirections(jointDirs [7]bool)
SetDirections simulates AR3exec.SetDirections().
type Arm ¶
type Arm interface { Calibrate(speed int, j1, j2, j3, j4, j5, j6, tr bool) error Echo() error GetDirections() [7]bool SetDirections([7]bool) CurrentJointRadians() [7]float64 CurrentPose() kinematics.Pose CurrentStepperPosition() [7]int MoveSteppers(speed, accdur, accspd, dccdur, dccspd, j1, j2, j3, j4, j5, j6, tr int) error MoveJointRadians(speed, accdur, accspd, dccdur, dccspd int, j1, j2, j3, j4, j5, j6, tr float64) error Move(speed, accdur, accspd, dccdur, dccspd int, pose kinematics.Pose) error }
Arm is the generic interface for interacting with an AR3 robotic arm.