arm#
Initializing the arm Class#
A 6-Axis Arm is created by using the following constructor:
The arm
constructor creates a 6-Axis CTE Arm in the specified Port.
Parameter |
Description |
---|---|
|
A valid Smart Port that the 6-Axis Arm is connected to. |
// Construct a 6-Axis arm "Arm" with the
// arm class.
arm Arm = arm(PORT1);
This Arm
object will be used in all subsequent examples throughout this API documentation when referring to arm class methods.
Class Methods#
moveTo()#
The moveTo(x, y, z, waitForCompletion)
method moves the end effector to the requested X, Y, and Z absolute position.
This can be a waiting or non-waiting method depending on if the waitForCompletion
parameter is used.
Parameters |
Description |
---|---|
x |
The X coordinate to move to, in millimeters. |
y |
The Y coordinate to move to, in millimeters. |
z |
The Z coordinate to move to, in millimeters. |
waitForCompletion |
Determines whether the command will block subsequent commands ( |
Returns: true
if the arm has moved to the requested position. false
if it did not.
// Move the arm to the (200, 0, 100).
Arm.moveTo(200, 0, 100);
moveInc()#
The moveInc(x, y, z, waitForCompletion)
method moves the end effector by the requested X, Y, and Z distances.
This can be a waiting or non-waiting method depending on if the waitForCompletion
parameter is used.
Parameters |
Description |
---|---|
x |
The distance on the X axis to move for, in millimeters. |
y |
The distance on the Y axis to move for, in millimeters. |
z |
The distance on the Z axis to move for, in millimeters. |
waitForCompletion |
Determines whether the command will block subsequent commands ( |
Returns: true
if the arm has moved to the requested position. false
if it did not.
// Move the Arm +100 millimeters on the Y axis.
Arm.moveInc(0, 100, 0);
moveEndEffectorTo()#
The moveEndEffectorTo(yaw, roll, pitch, waitForCompletion)
method moves the end effector to the requested absolute yaw, roll, and pitch orientation.
This can be a waiting or non-waiting method depending on if the waitForCompletion
parameter is used.
Parameters |
Description |
---|---|
yaw |
The angle around the Z axis that the end effector should point to, in degrees. |
roll |
The angle around the X axis that the end effector should point to, in degrees. |
pitch |
The angle around the Y axis that the end effector should point to, in degrees. |
waitForCompletion |
Determines whether the command will block subsequent commands ( |
Returns: true
if the end effector has moved to the requested orientation. false
if it has not.
// Orient the end effector to point towards
// 90 degrees around the X axis.
Arm.moveEndEffectorTo(0, 90, 0);
moveEndEffectorInc()#
The moveEndEffectorInc(yaw, roll, pitch, waitForCompletion)
method moves the end effector to the requested relative yaw, roll, and pitch orientation.
This can be a waiting or non-waiting method depending on if the waitForCompletion
parameter is used.
Parameters |
Description |
---|---|
yaw |
The angle around the Z axis that the end effector should change by, in degrees. |
roll |
The angle around the X axis that the end effector should change by, in degrees. |
pitch |
The angle around the Y axis that the end effector should change by, in degrees. |
waitForCompletion |
Determines whether the command will block subsequent commands ( |
Returns: true
if the end effector has moved to the requested orientation. false
if it has not.
// Orient the end effector -50 degrees on the Y axis.
Arm.moveEndEffectorInc(0, 0, -50);
setSpeed()#
The setSpeed(speed)
method sets the speed for moves.
Parameters |
Description |
---|---|
speed |
The speed at which the arm should move. |
Returns: None.
setEndEffectorType()#
The setEndEffectorType(type)
method sets the end effector type to magnet or pen.
Parameters |
Description |
---|---|
type |
A valid EndEffectorType. |
Returns: true
if the requested type was set. false
if it was not.
// Set the end effector to the Magnet Pickup Tool.
Arm.setEndEffectorType(magnet);
setEndEffectorMagnet()#
The setEndEffectorMagnet(state)
method sets the end effector magnet to enabled or disabled.
Parameters |
Description |
---|---|
state |
|
Returns: None.
// Enable the Magnet Pickup Tool.
Arm.setEndEffectorMagnet(true);
setPenOffset()#
The setPenOffset(zOffset)
method sets the pen end effector Z axis offset.
Parameters |
Description |
---|---|
zOffset |
The new offset in |
Returns: None.
setControlStop()#
The setControlStop(state)
method disables the arm and places joint motors in brake mode.
Parameters |
Description |
---|---|
state |
|
Returns: None.
controlStopped()#
The controlStopped(callback)
method registers a function to be called when the arm control stop is enabled.
Parameters |
Description |
---|---|
callback |
A function that will be called when the arm is control stopped |
Returns: None.
// Define the whenControlStopped function with a void
// return type, showing it doesn't return a value.
void whenControlStopped() {
// The brain will print that the arm has been control stopped
// on the Brain's screen.
Brain.Screen.print("The arm has been control stopped");
}
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Run whenControlStopped when the the arm is control stopped.
Arm.controlStopped(whenControlStopped);
}
canArmReachTo()#
The canArmReachTo(x, y, z)
method checks if the end effector can move to the requested X, Y, and Z absolute position.
Parameters |
Description |
---|---|
x |
The X coordinate to move to, in millimeters. |
y |
The Y coordinate to move to, in millimeters. |
z |
The Z coordinate to move to, in millimeters. |
Returns: true
if the arm can move to the requested position. false
if it cannot.
// Check if the arm can move to the (100, -20, 50).
if (Arm.canArmReachTo(100, -20, 50)){
// Move the arm to (100, -20, 50).
Arm.moveTo(100, -20, 50);
}
canArmReachInc()#
The Arm.canArmReachInc(x, y, z)
method checks if the end effector can move to the requested X, Y, and Z relative position.
Parameters |
Description |
---|---|
x |
The distance on the X axis to move for, in millimeters. |
y |
The distance on the Y axis to move for, in millimeters. |
z |
The distance on the Z axis to move for, in millimeters. |
Returns: true
if the arm can move to the requested position. false
if it cannot.
// Check if the arm can increment by 100 mm along the x-axis.
if (Arm.canArmReachInc(100, 0, 0)){
// Increment the arm by 100 mm along the X axis.
Arm.moveInc(100, 0, 0);
}
canEndEffectorReachTo()#
The canEndEffectorReachTo(yaw, roll, pitch)
method checks if the end effector can move to the requested absolute yaw, roll, and pitch orientation.
Parameters |
Description |
---|---|
yaw |
The angle around the Z axis that the end effector should point to, in degrees. |
roll |
The angle around the X axis that the end effector should point to, in degrees. |
pitch |
The angle around the Y axis that the end effector should point to, in degrees. |
Returns: true
if the end effector can move to the requested orientation. false
if it cannot.
// Check if the arm can orient 25 degrees around the Z axis.
if (Arm.canEndEffectorReachTo(25, 0, 0)){
// Orient to 25 degrees around the Z axis.
Arm.moveEndEffectorTo(25, 0, 0);
}
canEndEffectorReachInc()#
The canEndEffectorReachInc(yaw, roll, pitch)
method checks if the end effector can move to the requested relative yaw, roll, and pitch orientation.
Parameters |
Description |
---|---|
yaw |
The angle around the Z axis that the end effector will move for, in degrees. |
roll |
This is an optional parameter. The angle around the X axis that the end effector will move for, in degrees. |
pitch |
This is an optional parameter. The angle around the Y axis that the end effector will move for, in degrees. |
Returns: true
if the end effector can move to the requested orientation. false
if it cannot.
// Check If the arm can increment its orientation
// by 10 degrees on the X axis.
if (Arm.canEndEffectorReachInc(0, 10, 0)){
// Move +10 degrees around the X axis.
Arm.moveEndEffectorInc(0, 10, 0);
}
isDone()#
The isDone()
method returns the status of arm movement.
Returns: true
if the arm is currently performing a movement. false
if it is not.
// Move Arm to (-100, 200, 100) and let subsequent methods execute.
Arm.moveTo(-100, 200, 100, false);
// Keep repeating the methods until the Arm is done moving.
while (!Arm.isDone()) {
// Print the Arm's current Y coordinate on the Brain every .25 seconds.
Brain.Screen.print(Arm.getY());
Brain.Screen.newLine();
wait(0.25, seconds);
}
getX()#
The getX()
method returns the X position of the end effector.
Returns: A float representing the X position of the end effector in mm
.
// Print the current X position of the Arm in degrees.
Brain.Screen.print(Arm.getX());
getY()#
The getY()
method returns the Y position of the end effector.
Returns: A float representing the Y position of the end effector in mm
.
// Print the current Y position of the Arm in degrees.
Brain.Screen.print(Arm.getY());
getZ()#
The getZ()
method requests the Z position of the end effector.
Returns: A float representing the Z position of the end effector in mm
.
// Print the current Z position of the Arm in degrees.
Brain.Screen.print(Arm.getZ());
getYaw()#
The getYaw()
method requests the current yaw of the end effector.
Returns: A float representing the current yaw of the end effector in degrees.
// Print the current yaw of the Arm in degrees.
Brain.Screen.print(Arm.getYaw());
getRoll()#
The getRoll()
method requests the current roll of the end effector.
Returns: A float representing the current roll of the end effector in degrees.
// Print the current roll of the Arm in degrees.
Brain.Screen.print(Arm.getRoll());
getPitch()#
The getPitch()
method requests the current pitch of the end effector.
Returns: A float representing the current pitch of the end effector in degrees.
// Print the current pitch of the Arm in degrees.
Brain.Screen.print(Arm.getPitch());
setTimeout()#
The setTimeout(timeout, units)
method sets the timeout value used when moving the Arm.
Parameters |
Description |
---|---|
timeout |
The new timeout value. |
units |
A valid TimeUnit. |
Returns: None.
isConnected()#
The isConnected()
method checks if the CTE arm is connected. This is a compatibility function that returns the same as the installed()
function.
Returns: true
if the arm is connected to the brain on the associated smartport. false
if it is not.
timestamp()#
The timestamp()
method requests the timestamp of the last received status packet from the Arm.
Returns: Timestamp of the last status packet as an unsigned 32-bit integer in milliseconds.
installed()#
The installed()
method returns if the device is connected.
Returns: true
if the device is connected. false
if it is not.