M-File Help: Arbotix | View code for Arbotix |
Interface to Arbotix robot-arm controller
A concrete subclass of the abstract Machine class that implements a connection over a serial port to an Arbotix robot-arm controller.
Arbotix | Constructor, establishes serial communications |
delete | Destructor, closes serial connection |
getpos | Get joint angles |
setpos | Set joint angles and optionally speed |
setpath | Load a trajectory into Arbotix RAM |
relax | Control relax (zero torque) state |
setled | Control LEDs on servos |
gettemp | Temperature of motors |
writedata1 | Write byte data to servo control table |
writedata2 | Write word data to servo control table |
readdata | Read servo control table |
command | Execute command on servo |
flush | Flushes serial data buffer |
receive | Receive data |
arb=Arbotix('port', '/dev/tty.usbserial-A800JDPN', 'nservos', 5); q = arb.getpos(); arb.setpos(q + 0.1);
Create Arbotix interface object
arb = Arbotix(options) is an object that represents a connection to a chain of Arbotix servos connected via an Arbotix controller and serial link to the host computer.
'port', P | Name of the serial port device, eg. /dev/tty.USB0 |
'baud', B | Set baud rate (default 38400) |
'debug', D | Debug level, show communications packets (default 0) |
'nservos', N | Number of servos in the chain |
Convert angle to encoder
E = ARB.A2E(a) is a vector of encoder values E corresponding to the vector of joint angles a. TODO:
Convert Arbotix status to string
C = ARB.char() is a string that succinctly describes the status of the Arbotix controller link.
Execute command on servo
R = ARB.COMMAND(id, instruc) executes the instruction instruc on servo id.
R = ARB.COMMAND(id, instruc, data) as above but the vector data forms the payload of the command message, and all numeric values in data must be in the range 0 to 255.
The optional output argument R is a structure holding the return status.
Arbotix.receive, Arbotix.flush
Connect to the physical robot controller
ARB.connect() establish a serial connection to the physical robot controller.
Disconnect from the physical robot controller
ARB.disconnect() closes the serial connection.
Display parameters
ARB.display() displays the servo parameters in compact single line format.
Convert encoder to angle
a = ARB.E2A(E) is a vector of joint angles a corresponding to the vector of encoder values E.
TODO:
Flush the receive buffer
ARB.FLUSH() flushes the serial input buffer, data is discarded.
s = ARB.FLUSH() as above but returns a vector of all bytes flushed from the channel.
Arbotix.receive, Arbotix.parse
Get position
p = ARB.GETPOS(id) is the position (0-1023) of servo id.
p = ARB.GETPOS([]) is a vector (1xN) of positions of servos 1 to N.
Get temperature
T = ARB.GETTEMP(id) is the tempeature (deg C) of servo id.
T = ARB.GETTEMP() is a vector (1xN) of the temperature of servos 1 to N.
Parse Arbotix return strings
ARB.PARSE(s) parses the string returned from the Arbotix controller and prints diagnostic text. The string s contains a mixture of Dynamixel style return packets and diagnostic text.
Arbotix.flush, Arbotix.command
Read byte data from servo control table
R = ARB.READDATA(id, addr) reads the successive elements of the servo control table for servo id, starting at address addr. The complete return status in the structure R, and the byte data is a vector in the field 'params'.
Arbotix.receive, Arbotix.command
Decode Arbotix return packet
R = ARB.RECEIVE() reads and parses the return packet from the Arbotix and returns a structure with the following fields:
id | The id of the servo that sent the message |
error | Error code, 0 means OK |
params | The returned parameters, can be a vector of byte values |
Control relax state
ARB.RELAX(id) causes the servo id to enter zero-torque (relax state) ARB.RELAX(id, FALSE) causes the servo id to enter position-control mode ARB.RELAX([]) causes servos 1 to N to relax ARB.RELAX() as above ARB.RELAX([], FALSE) causes servos 1 to N to enter position-control mode.
Set LEDs on servos
ARB.led(id, status) sets the LED on servo id to on or off according to the status (logical).
ARB.led([], status) as above but the LEDs on servos 1 to N are set.
Load a path into Arbotix controller
ARB.setpath(jt) stores the path jt (PxN) in the Arbotix controller where P is the number of points on the path and N is the number of robot joints. Allows for smooth multi-axis motion.
Set position
ARB.SETPOS(id, pos) sets the position (0-1023) of servo id. ARB.SETPOS(id, pos, SPEED) as above but also sets the speed.
ARB.SETPOS(pos) sets the position of servos 1-N to corresponding elements of the vector pos (1xN). ARB.SETPOS(pos, SPEED) as above but also sets the velocity SPEED (1xN).
Write byte data to servo control table
ARB.WRITEDATA1(id, addr, data) writes the successive elements of data to the servo control table for servo id, starting at address addr. The values of data must be in the range 0 to 255.
Arbotix.writedata2, Arbotix.command
Write word data to servo control table
ARB.WRITEDATA2(id, addr, data) writes the successive elements of data to the servo control table for servo id, starting at address addr. The values of data must be in the range 0 to 65535.
Arbotix.writedata1, Arbotix.command
© 1990-2014 Peter Corke.