CTE Arm#
Introduction#
The arm class provides control for the 6-Axis Arm used in the CTE Workcell. In VEX EXP C++, the 6-Axis Arm can move an end effector to positions in three-dimensional space, rotate the end effector, check whether movements are possible, and control attached tools such as the Magnet Pickup Tool or Pen Holder Tool.
The examples on this page use a configured 6-Axis Arm named Arm.
Constructors#
arm#
arm creates a 6-Axis Arm object.
Available Function
arm(int32_t index);
Parameter |
Type |
Description |
|---|---|---|
|
|
The Smart Port that the 6-Axis Arm is connected to, written as |
Example
// Create a 6-Axis Arm named Arm on Port 1
arm Arm = arm(PORT1);
Destructor#
~arm#
~arm destroys the arm object and releases associated resources.
Available Function
~arm();
Member Functions#
The arm class includes the following member functions:
Actions — Move the 6-Axis Arm to positions or orientations.
moveTo— Moves the end effector to a specified x, y, and z coordinate.moveInc— Moves the end effector by a specified distance from its current position.moveEndEffectorTo— Rotates the end effector to a specified yaw, roll, and pitch orientation.moveEndEffectorInc— Rotates the end effector by a specified yaw, roll, and pitch amount.
Mutators — Configure movement, tools, and control settings.
setSpeed— Sets the movement speed used by the 6-Axis Arm.setEndEffectorType— Sets the type of end effector attached to the 6-Axis Arm.setEndEffectorMagnet— Enables or disables the Magnet Pickup Tool.setPenOffset— Sets the z-axis offset used with the Pen Holder Tool.setControlStop— Enables or disables control stop for the 6-Axis Arm.setTimeout— Sets the timeout used by 6-Axis Arm movement functions.
Getters — Return motion status, position, orientation, and connection values.
isDone— Returns whether the 6-Axis Arm has finished moving.isCrashed— Returns whether the 6-Axis Arm has crashed while moving.getX— Returns the current x position of the end effector.getY— Returns the current y position of the end effector.getZ— Returns the current z position of the end effector.getYaw— Returns the current yaw of the end effector.getRoll— Returns the current roll of the end effector.getPitch— Returns the current pitch of the end effector.canArmReachTo— Returns whether the 6-Axis Arm can reach a specified position.canArmReachInc— Returns whether the 6-Axis Arm can move by a specified distance.canEndEffectorReachTo— Returns whether the end effector can reach a specified orientation.canEndEffectorReachInc— Returns whether the end effector can rotate by a specified amount.isConnected— Returns whether the 6-Axis Arm is connected to the EXP Brain.timestamp— Returns the timestamp of the last received status packet from the 6-Axis Arm.installed— Returns whether the 6-Axis Arm is connected.
Callbacks — Run functions when arm events occur.
controlStopped— Registers a function to run when control stop is enabled.crashed— Registers a function to run when a crash is detected.
Actions#
moveTo#
moveTo moves the 6-Axis Arm to a specified x, y, and z coordinate.
The x, y, and z coordinates describe the position of the end effector in three-dimensional space. Use canArmReachTo before this function if the target position may be outside the 6-Axis Arm’s reachable workspace.
Available Function
bool moveTo(
double x,
double y,
double z,
bool waitForCompletion = true
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The x-coordinate of the target position in millimeters. |
|
|
The y-coordinate of the target position in millimeters. |
|
|
The z-coordinate of the target position in millimeters. |
|
|
Optional. |
Return Value
Returns a Boolean value.
true— The 6-Axis Arm reached the target position.false— The 6-Axis Arm did not reach the target position, orwaitForCompletionwas set tofalse.
Examples
// Move the 6-Axis Arm to (200, 0, 100)
Arm.moveTo(200, 0, 100);
// Start moving, then print the y-position while the arm moves
Arm.moveTo(-100, 200, 100, false);
while (!Arm.isDone()) {
Brain.Screen.print(Arm.getY());
Brain.Screen.newLine();
wait(0.25, seconds);
}
moveInc#
moveInc moves the 6-Axis Arm by a specified distance from its current position along the x, y, and z axes.
Use this function to move relative to where the end effector is now. Use canArmReachInc before this function if the movement may place the 6-Axis Arm outside its reachable workspace.
Available Function
bool moveInc(
double x,
double y,
double z,
bool waitForCompletion = true
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The distance to move along the x-axis in millimeters. |
|
|
The distance to move along the y-axis in millimeters. |
|
|
The distance to move along the z-axis in millimeters. |
|
|
Optional. |
Return Value
Returns a Boolean value.
true— The 6-Axis Arm reached the requested position.false— The 6-Axis Arm did not reach the requested position, orwaitForCompletionwas set tofalse.
Example
// Move the 6-Axis Arm 100 millimeters along the y-axis
Arm.moveInc(0, 100, 0);
moveEndEffectorTo#
moveEndEffectorTo rotates the 6-Axis Arm’s end effector to a specified yaw, roll, and pitch orientation.
Orientation describes how the end effector is rotated. yaw rotates around the z-axis, roll rotates around the x-axis, and pitch rotates around the y-axis.
Available Function
bool moveEndEffectorTo(
double yaw,
double roll = 0,
double pitch = 0,
bool waitForCompletion = true
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The target yaw angle in degrees. |
|
|
Optional. The target roll angle in degrees. The default is |
|
|
Optional. The target pitch angle in degrees. The default is |
|
|
Optional. |
Return Value
Returns a Boolean value.
true— The end effector reached the target orientation.false— The end effector did not reach the target orientation, orwaitForCompletionwas set tofalse.
Example
// Rotate the end effector to 90 degrees of roll
Arm.moveEndEffectorTo(0, 90, 0);
moveEndEffectorInc#
moveEndEffectorInc rotates the 6-Axis Arm’s end effector by a specified yaw, roll, and pitch amount from its current orientation.
Use this function to rotate relative to the end effector’s current yaw, roll, or pitch.
Available Function
bool moveEndEffectorInc(
double yaw,
double roll = 0,
double pitch = 0,
bool waitForCompletion = true
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The change in yaw, in degrees. |
|
|
Optional. The change in roll, in degrees. The default is |
|
|
Optional. The change in pitch, in degrees. The default is |
|
|
Optional. |
Return Value
Returns a Boolean value.
true— The end effector reached the requested orientation.false— The end effector did not reach the requested orientation, orwaitForCompletionwas set tofalse.
Example
// Rotate the end effector -50 degrees in pitch
Arm.moveEndEffectorInc(0, 0, -50);
Mutators#
setSpeed#
setSpeed sets the movement speed used by the 6-Axis Arm.
Available Function
void setSpeed(uint32_t speed);
Parameter |
Type |
Description |
|---|---|---|
|
|
The speed at which the 6-Axis Arm should move, in millimeters per second. |
Return Value
This function does not return a value.
Example
// Set the 6-Axis Arm movement speed
Arm.setSpeed(100);
setEndEffectorType#
setEndEffectorType sets the type of end effector attached to the 6-Axis Arm.
When the end effector type is changed, the 6-Axis Arm automatically adjusts its z-offset to match the selected tool.
Available Function
bool setEndEffectorType(
endEffectorType type,
bool waitForCompletion = true
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The tool attached to the 6-Axis Arm: |
|
|
Optional. |
Return Value
Returns a Boolean value.
true— The requested type was set.false— The requested type was not set, orwaitForCompletionwas set tofalse.
Example
// Set the end effector type to the Magnet Pickup Tool
Arm.setEndEffectorType(magnet);
setEndEffectorMagnet#
setEndEffectorMagnet enables or disables the Magnet Pickup Tool.
Available Function
void setEndEffectorMagnet(bool enabled);
Parameter |
Type |
Description |
|---|---|---|
|
|
|
Return Value
This function does not return a value.
Example
// Pick up objects and then drop them
Arm.setEndEffectorType(magnet);
Arm.setEndEffectorMagnet(true);
wait(2, seconds);
Arm.setEndEffectorMagnet(false);
setPenOffset#
setPenOffset sets the z-axis offset used when the Pen Holder Tool is attached to the 6-Axis Arm.
Set the end effector type to pen before using this function. If the Pen Holder Tool is not selected, this function has no effect.
The pen offset is the distance from the top of the Pen Holder Tool to the tip of the Dry-Erase Marker. A positive z value moves the offset upward from the tool mount point.
Available Function
void setPenOffset(double zOffset);
Parameter |
Type |
Description |
|---|---|---|
|
|
The pen offset value in millimeters. |
Return Value
This function does not return a value.
Example
// Set the end effector type to the Pen Holder Tool and set the pen offset
Arm.setEndEffectorType(pen);
Arm.setPenOffset(25);
setControlStop#
setControlStop enables or disables control stop for the 6-Axis Arm.
When control stop is enabled, the 6-Axis Arm immediately stops movement and prevents further linear or joint movements.
Available Function
void setControlStop(bool state = true);
Parameter |
Type |
Description |
|---|---|---|
|
|
Optional. |
Return Value
This function does not return a value.
Example
// Stop the 6-Axis Arm and prevent further movement
Arm.setControlStop();
setTimeout#
setTimeout sets the timeout value used when moving the 6-Axis Arm.
If a movement does not finish before the timeout is reached, the project continues to the next line of code.
Available Function
void setTimeout(
int32_t timeout,
timeUnits units
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The new timeout value. |
|
|
The time unit: |
Return Value
This function does not return a value.
Example
// Set the 6-Axis Arm timeout to 2 seconds
Arm.setTimeout(2, sec);
Getters#
isDone#
isDone returns whether the 6-Axis Arm has finished moving.
This function is useful after a movement function is called with waitForCompletion set to false.
Available Function
bool isDone();
Parameters
This function does not have parameters.
Return Value
Returns a Boolean value.
true— The 6-Axis Arm has finished moving.false— The 6-Axis Arm is still moving.
Example
// Display the 6-Axis Arm's y-position while it moves
Arm.moveTo(-100, 200, 100, false);
while (!Arm.isDone()) {
Brain.Screen.print(Arm.getY());
Brain.Screen.newLine();
wait(0.25, seconds);
}
isCrashed#
isCrashed returns whether the 6-Axis Arm has crashed while moving.
When a crash is detected, the 6-Axis Arm stops motor movement and may appear to go limp. This reduces strain and helps protect the motors from accidental damage.
Available Function
bool isCrashed();
Parameters
This function does not have parameters.
Return Value
Returns a Boolean value.
true— The 6-Axis Arm has crashed.false— The 6-Axis Arm has not crashed.
Example
// Quickly move to a new location
Arm.setSpeed(100);
Arm.moveTo(-40, 250, 40, false);
// While moving, check for a crash
while (true) {
if (Arm.isCrashed()) {
// Indicate a crash with the Signal Tower and Brain screen
Brain.Screen.print("Crash Detected");
SignalTower6.setColor(signaltower::green, signaltower::off);
SignalTower6.setColor(signaltower::red, signaltower::on);
break;
}
wait(5, msec);
}
getX#
getX returns the current x position of the end effector in millimeters.
Use this function to read where the end effector is currently located along the x-axis.
Available Function
float getX();
Parameters
This function does not have parameters.
Return Value
Returns a float representing the x position of the end effector in millimeters.
Example
// Print the current x position of the 6-Axis Arm
Brain.Screen.print(Arm.getX());
getY#
getY returns the current y position of the end effector in millimeters.
Use this function to read where the end effector is currently located along the y-axis.
Available Function
float getY();
Parameters
This function does not have parameters.
Return Value
Returns a float representing the y position of the end effector in millimeters.
Example
// Print the current y position of the 6-Axis Arm
Brain.Screen.print(Arm.getY());
getZ#
getZ returns the current z position of the end effector in millimeters.
Use this function to read where the end effector is currently located along the z-axis.
Available Function
float getZ();
Parameters
This function does not have parameters.
Return Value
Returns a float representing the z position of the end effector in millimeters.
Example
// Print the current z position of the 6-Axis Arm
Brain.Screen.print(Arm.getZ());
getYaw#
getYaw returns the current yaw of the end effector in degrees.
Available Function
float getYaw();
Parameters
This function does not have parameters.
Return Value
Returns a float representing the current yaw of the end effector in degrees.
Example
// Print the current yaw of the end effector
Brain.Screen.print(Arm.getYaw());
getRoll#
getRoll returns the current roll of the end effector in degrees.
Available Function
float getRoll();
Parameters
This function does not have parameters.
Return Value
Returns a float representing the current roll of the end effector in degrees.
Example
// Print the current roll of the end effector
Brain.Screen.print(Arm.getRoll());
getPitch#
getPitch returns the current pitch of the end effector in degrees.
Available Function
float getPitch();
Parameters
This function does not have parameters.
Return Value
Returns a float representing the current pitch of the end effector in degrees.
Example
// Print the current pitch of the end effector
Brain.Screen.print(Arm.getPitch());
canArmReachTo#
canArmReachTo returns whether the 6-Axis Arm can move the end effector to a specified x, y, and z coordinate.
Use this function to check a target position before using moveTo.
Available Function
bool canArmReachTo(
double x,
double y,
double z
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The x-coordinate of the target position in millimeters. |
|
|
The y-coordinate of the target position in millimeters. |
|
|
The z-coordinate of the target position in millimeters. |
Return Value
Returns a Boolean value.
true— The 6-Axis Arm can reach the requested position.false— The 6-Axis Arm cannot reach the requested position.
Example
// Move the 6-Axis Arm to (100, -20, 50) if it can reach
if (Arm.canArmReachTo(100, -20, 50)) {
Arm.moveTo(100, -20, 50);
}
canArmReachInc#
canArmReachInc returns whether the 6-Axis Arm can move the end effector by a specified x, y, and z distance from its current position.
Use this function to check a relative movement before using moveInc.
Available Function
bool canArmReachInc(
double x,
double y,
double z
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The distance to move along the x-axis in millimeters. |
|
|
The distance to move along the y-axis in millimeters. |
|
|
The distance to move along the z-axis in millimeters. |
Return Value
Returns a Boolean value.
true— The 6-Axis Arm can make the requested movement.false— The 6-Axis Arm cannot make the requested movement.
Example
// Increment the 6-Axis Arm 100 mm along the x-axis if possible
if (Arm.canArmReachInc(100, 0, 0)) {
Arm.moveInc(100, 0, 0);
}
canEndEffectorReachTo#
canEndEffectorReachTo returns whether the end effector can rotate to a specified yaw, roll, and pitch orientation.
Use this function to check a target orientation before using moveEndEffectorTo.
Available Function
bool canEndEffectorReachTo(
double yaw,
double roll = 0,
double pitch = 0
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The target yaw angle in degrees. |
|
|
Optional. The target roll angle in degrees. The default is |
|
|
Optional. The target pitch angle in degrees. The default is |
Return Value
Returns a Boolean value.
true— The end effector can reach the requested orientation.false— The end effector cannot reach the requested orientation.
Example
// Rotate the end effector to 90 degrees of roll if possible
if (Arm.canEndEffectorReachTo(0, 90, 0)) {
Arm.moveEndEffectorTo(0, 90, 0);
}
canEndEffectorReachInc#
canEndEffectorReachInc returns whether the end effector can rotate by a specified yaw, roll, and pitch amount from its current orientation.
Use this function to check a relative orientation movement before using moveEndEffectorInc.
Available Function
bool canEndEffectorReachInc(
double yaw,
double roll = 0,
double pitch = 0
);
Parameter |
Type |
Description |
|---|---|---|
|
|
The change in yaw, in degrees. |
|
|
Optional. The change in roll, in degrees. The default is |
|
|
Optional. The change in pitch, in degrees. The default is |
Return Value
Returns a Boolean value.
true— The end effector can make the requested rotation.false— The end effector cannot make the requested rotation.
Example
// Increment the end effector by 10 degrees of pitch if possible
if (Arm.canEndEffectorReachInc(0, 0, 10)) {
Arm.moveEndEffectorInc(0, 0, 10);
}
isConnected#
isConnected returns whether the 6-Axis Arm is connected to the EXP Brain.
This is a compatibility function that returns the same value as installed.
Available Function
bool isConnected();
Parameters
This function does not have parameters.
Return Value
Returns a Boolean value.
true— The 6-Axis Arm is connected to the EXP Brain.false— The 6-Axis Arm is not connected to the EXP Brain.
Example
// Print whether the 6-Axis Arm is connected
Brain.Screen.print(Arm.isConnected());
timestamp#
timestamp returns the timestamp of the last received status packet from the 6-Axis Arm.
Available Function
uint32_t timestamp();
Parameters
This function does not have parameters.
Return Value
Returns the timestamp of the last status packet as a uint32_t in milliseconds.
installed#
installed returns whether the 6-Axis Arm is connected.
Available Function
bool installed();
Parameters
This function does not have parameters.
Return Value
Returns a Boolean value.
true— The 6-Axis Arm is connected.false— The 6-Axis Arm is not connected.
Callbacks#
controlStopped#
controlStopped registers a function that runs when control stop is enabled.
Available Function
void controlStopped(void (* callback)(void));
Parameter |
Type |
Description |
|---|---|---|
|
|
A function that runs when control stop is enabled. |
Return Value
This function does not return a value.
Example
// Called when the 6-Axis Arm is control stopped
void onControlStopped() {
Brain.Screen.print("Arm control stopped");
}
int main() {
vexcodeInit();
Arm.controlStopped(onControlStopped);
}
crashed#
crashed registers a function that runs when the 6-Axis Arm has crashed while moving.
When a crash is detected, the 6-Axis Arm stops motor movement and may appear to go limp. This reduces strain and helps protect the motors from accidental damage.
Available Function
void crashed(void (* callback)(void));
Parameter |
Type |
Description |
|---|---|---|
|
|
A function that runs when the 6-Axis Arm has crashed while moving. |
Return Value
This function does not return a value.
Example
// Called when the 6-Axis Arm crashes while moving
void onArmCrashed() {
Brain.Screen.print("Crash detected");
SignalTower6.setColor(signaltower::green, signaltower::off);
SignalTower6.setColor(signaltower::red, signaltower::on);
}
int main() {
vexcodeInit();
Arm.crashed(onArmCrashed);
}