CTE Arm#
Introduction#
The arm class provides control for the 6-Axis CTE Arm, allowing precise positioning and movement of the robotic arm in 3D space. This class supports both absolute and relative positioning, end effector control, and various sensor functions for monitoring arm status and capabilities.
Class Constructors#
arm(
int32_t index );
Class Destructor#
Destroys the arm object and releases associated resources.
~arm();
Parameters#
Parameter |
Type |
Description |
|---|---|---|
|
|
A valid Smart Port that the 6-Axis Arm is connected to, written as |
Example#
// Create the arm instance in Port 1
arm Arm = arm(PORT1);
Member Functions#
The arm classes includes the following member functions:
moveTo - Moves the end effector to the requested x, y, and z coordinates.
moveInc - Moves the end effector by the requested x, y, and z distances relative to its current position.
moveEndEffectorTo - Moves the end effector to the requested absolute yaw, roll, and pitch orientation.
moveEndEffectorInc - Moves the end effector to the requested relative yaw, roll, and pitch orientation.
setEndEffectorType - Sets the type of end effector attached to the arm.
setEndEffectorMagnet - Sets the end effector magnet to enabled or disabled.
setPenOffset - Sets the pen end effector z-axis offset.
setControlStop - Disables the arm and places joint motors in brake mode.
controlStopped - Registers a function to be called when the arm control stop is enabled.
canArmReachTo - Returns if the end effector can move to the requested x, y, and z coordinates.
canArmReachInc - Returns if the end effector can move for a distance along the x, y, and z axes.
canEndEffectorReachTo - Returns if the end effector can move to the requested absolute yaw, roll, and pitch orientation.
canEndEffectorReachInc - Returns if the end effector can move for a distance along the yaw, pitch, or roll orientations.
isDone – Returns the status of arm movement.
getX – Returns the X position of the end effector.
getY – Returns the y-position of the end effector.
getZ – Returns the 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.
setTimeout – Sets the timeout value used when moving the Arm.
isConnected – Returns if the CTE arm is connected.
timestamp – Returns the timestamp of the last received status packet from the Arm.
installed – Returns if the device is connected.
moveTo#
Moves the end effector to the requested x, y, and z coordinates.
Available Functionsbool moveTo(
double x,
double y,
double z,
bool waitForCompletion = true );
Parameter |
Type |
Description |
|---|---|---|
|
|
The X coordinate to move to, in millimeters. |
|
|
The Y coordinate to move to, in millimeters. |
|
|
The Z coordinate to move to, in millimeters. |
|
|
|
Returns a Boolean indicating whether the arm reached the target position.
trueif the arm reached the target position.falseif the arm did not reach the target position or ifwaitForCompletionparameter is set tofalse.
// Move the arm to the (200, 0, 100)
Arm.moveTo(200, 0, 100);
moveInc#
Moves the end effector by the requested x, y, and z distances relative to its current position.
Available Functionsbool moveInc(
double x,
double y,
double z,
bool waitForCompletion = true );
Parameter |
Type |
Description |
|---|---|---|
|
|
The distance on the X axis to move for, in millimeters. |
|
|
The distance on the Y axis to move for, in millimeters. |
|
|
The distance on the Z axis to move for, in millimeters. |
|
|
|
Returns a Boolean indicating whether the arm reached the target position.
trueif the arm reached the target position.falseif the arm did not reach the target position or ifwaitForCompletionparameter is set tofalse.
// Move the Arm +100 millimeters on the Y axis
Arm.moveInc(0, 100, 0);
moveEndEffectorTo#
Moves the end effector to the requested absolute yaw, roll, and pitch orientation.
Available Functionsbool moveEndEffectorTo(
double yaw,
double roll = 0,
double pitch = 0,
bool waitForCompletion = true);
Parameter |
Type |
Description |
|---|---|---|
|
|
The angle around the Z axis that the end effector should point to, in degrees. |
|
|
The angle around the X axis that the end effector should point to, in degrees. Default is 0. |
|
|
The angle around the Y axis that the end effector should point to, in degrees. Default is 0. |
|
|
|
Returns a Boolean indicating whether the end effector reached the target orientation.
trueif the end effector reached the target orientation.falseif the end effector did not reach the target orientation or ifwaitForCompletionparameter is set tofalse.
// Orient the end effector to point towards
// 90 degrees around the X axis
Arm.moveEndEffectorTo(0, 90, 0);
moveEndEffectorInc#
Moves the end effector to the requested relative yaw, roll, and pitch orientation.
Available Functionsbool moveEndEffectorInc(
double yaw,
double roll = 0,
double pitch = 0,
bool waitForCompletion = true );
Parameter |
Type |
Description |
|---|---|---|
|
|
The angle around the Z axis that the end effector should change by, in degrees. |
|
|
The angle around the X axis that the end effector should change by, in degrees. Default is 0. |
|
|
The angle around the Y axis that the end effector should change by, in degrees. Default is 0. |
|
|
|
Returns a Boolean indicating whether the end effector reached the target orientation.
trueif the end effector reached the target orientation.falseif the end effector did not reach the target orientation or ifwaitForCompletionparameter is set tofalse.
// Orient the end effector -50 degrees on the Y axis
Arm.moveEndEffectorInc(0, 0, -50);
setSpeed#
Sets the speed for arm movements.
Available Functionsvoid setSpeed(
uint32_t speed );
Parameter |
Type |
Description |
|---|---|---|
|
|
The speed at which the arm should move in mm/s. |
This function does not return a value.
setEndEffectorType#
Sets the end effector type to magnet or pen.
Available Functionsbool setEndEffectorType(
endEffectorType type,
bool waitForCompletion = true));
Parameter |
Type |
Description |
|---|---|---|
|
|
An end effector type:
|
|
|
|
Returns a Boolean indicating whether the requested type was set.
trueif the requested type was set.falseif the requested type was not set or ifwaitForCompletionparameter is set tofalse.
// Set the end effector to the Magnet Pickup Tool.
Arm.setEndEffectorType(magnet);
setEndEffectorMagnet#
Sets the end effector magnet to enabled or disabled.
Available Functionsvoid setEndEffectorMagnet(
bool enabled );
Parameter |
Type |
Description |
|---|---|---|
|
|
|
This function does not return a value.
Examples// Enable the Magnet Pickup Tool
Arm.setEndEffectorMagnet(true);
setPenOffset#
Sets the pen end effector Z axis offset.
Available Functionsvoid setPenOffset(
double zOffset );
Parameter |
Type |
Description |
|---|---|---|
|
|
The new offset in millimeters. A positive z value indicates up. |
This function does not return a value.
setControlStop#
Disables the arm and places joint motors in brake mode.
Available Functionsvoid setControlStop(
bool state = true);
Parameter |
Type |
Description |
|---|---|---|
|
|
|
This function does not return a value.
controlStopped#
Registers a function to be called when the arm control stop is enabled.
Available Functionsvoid controlStopped(
void (* callback)(void) );
Parameter |
Type |
Description |
|---|---|---|
|
|
A function that will be called when the arm is control stopped. |
This function does not return a value.
Examples// 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");
}
// Run whenControlStopped when the the arm is control stopped.
Arm.controlStopped(whenControlStopped);
canArmReachTo#
Returns if the end effector can move to the requested x, y, and z coordinates.
Available Functionsbool canArmReachTo( double x, double y, double z );
Parameter |
Type |
Description |
|---|---|---|
|
|
The X coordinate to move to, in millimeters. |
|
|
The Y coordinate to move to, in millimeters. |
|
|
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#
Returns if the end effector can move for a distance along the x, y, and z axes.
Available Functionsbool canArmReachInc(
double x,
double y,
double z );
Parameter |
Type |
Description |
|---|---|---|
|
|
The distance on the X axis to move for, in millimeters. |
|
|
The distance on the Y axis to move for, in millimeters. |
|
|
The distance on the Z axis to move for, in millimeters. |
Returns a Boolean indicating whether the arm can move to the requested position.
trueif the arm can move to the requested position.falseif the arm cannot move to the requested position.
// 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#
Returns if the end effector can move to the requested absolute yaw, roll, and pitch orientation.
Available Functionsbool canEndEffectorReachTo(
double yaw,
double roll = 0,
double pitch = 0 );
Parameter |
Type |
Description |
|---|---|---|
|
|
The angle around the Z axis that the end effector should point to, in degrees. |
|
|
The angle around the X axis that the end effector should point to, in degrees. Default is 0. |
|
|
The angle around the Y axis that the end effector should point to, in degrees. Default is 0. |
Returns a Boolean indicating whether the end effector can move to the requested orientation.
trueif the end effector can move to the requested orientation.falseif the end effector cannot move to the requested orientation.
// 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#
Returns if the end effector can move for a distance along the yaw, pitch, or roll orientations.
Available Functionsbool canEndEffectorReachInc(
double yaw,
double roll = 0,
double pitch = 0 );
Parameter |
Type |
Description |
|---|---|---|
|
|
The angle around the z-axis that the end effector will move for, in degrees. |
|
|
The angle around the x-axis that the end effector will move for, in degrees. Default is 0. |
|
|
The angle around the y-axis that the end effector will move for, in degrees. Default is 0. |
Returns a Boolean indicating whether the end effector can move to the requested orientation.
trueif the end effector can move to the requested orientation.falseif the end effector cannot move to the requested orientation.
// 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#
Returns the status of arm movement.
Available Functionsbool isDone();
This function does not have parameters.
Return ValuesReturns a Boolean indicating whether the arm has completed its movement.
trueif the arm has completed its movement.falseif the arm is still moving.
// 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#
Returns the X position of the end effector.
Available Functionsfloat getX();
This function does not have parameters.
Return ValuesReturns a float representing the X position of the end effector in millimeters.
// Print the current x-position of the arm in degrees
Brain.Screen.print(Arm.getX());
getY#
Returns the y-position of the end effector.
Available Functionsfloat getY();
This function does not have parameters.
Return ValuesReturns a float representing the y-position of the end effector in millimeters.
// Print the current y-position of the Arm in degrees
Brain.Screen.print(Arm.getY());
getZ#
Returns the z-position of the end effector.
Available Functionsfloat getZ();
This function does not have parameters.
Return ValuesReturns a float representing the z-position of the end effector in millimeters.
// Print the current z-position of the Arm in degrees
Brain.Screen.print(Arm.getZ());
getYaw#
Returns the current yaw of the end effector.
Available Functionsfloat getYaw();
This function does not have parameters.
Return ValuesReturns 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#
Returns the current roll of the end effector.
Available Functionsfloat getRoll();
This function does not have parameters.
Return ValuesReturns 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#
Returns the current pitch of the end effector.
Available Functionsfloat getPitch();
This function does not have parameters.
Return ValuesReturns 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#
Sets the timeout value used when moving the Arm.
Available Functionsvoid setTimeout(
int32_t timeout,
timeUnits units );
Parameter |
Type |
Description |
|---|---|---|
|
|
The new timeout value. |
|
|
The unit that represents the time:
|
This function does not return a value.
isConnected#
Returns if the CTE arm is connected. This is a compatibility function that returns the same as the installed() function.
Available Functionsbool isConnected();
This function does not have parameters.
Return ValuesReturns a Boolean indicating whether the arm is connected to the brain on the associated smartport.
trueif the arm is connected to the brain on the associated smartport.falseif the arm is not connected to the brain on the associated smartport.
timestamp#
Returns the timestamp of the last received status packet from the Arm.
Available Functionsuint32_t timestamp();
This function does not have parameters.
Return ValuesReturns the timestamp of the last status packet as a uint32_t in milliseconds.
installed#
Returns if the device is connected.
Available Functionsbool installed();
This function does not have parameters.
Return ValuesReturns a Boolean indicating whether the device is connected.
trueif the device is connected.falseif the device is not connected.