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

index

int32_t

A valid Smart Port that the 6-Axis Arm is connected to, written as PORTx, where x is the port number (for example, PORT1).

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 Functions
bool moveTo( 
  double x, 
  double y, 
  double z, 
  bool   waitForCompletion = true );

Parameters

Parameter

Type

Description

x

double

The X coordinate to move to, in millimeters.

y

double

The Y coordinate to move to, in millimeters.

z

double

The Z coordinate to move to, in millimeters.

waitForCompletion

bool

  • true (default) — The project waits until the function finishes before executing the next line of code.
  • false — The project starts the action and moves on to the next line of code right away, without waiting for the function to finish.

Return Values

Returns a Boolean indicating whether the arm reached the target position.

  • true if the arm reached the target position.

  • false if the arm did not reach the target position or if waitForCompletion parameter is set to false.

Examples
// 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 Functions
bool moveInc( 
  double x, 
  double y, 
  double z, 
  bool   waitForCompletion = true );

Parameters

Parameter

Type

Description

x

double

The distance on the X axis to move for, in millimeters.

y

double

The distance on the Y axis to move for, in millimeters.

z

double

The distance on the Z axis to move for, in millimeters.

waitForCompletion

bool

  • true (default) — The project waits until the function finishes before executing the next line of code.
  • false — The project starts the action and moves on to the next line of code right away, without waiting for the function to finish.

Return Values

Returns a Boolean indicating whether the arm reached the target position.

  • true if the arm reached the target position.

  • false if the arm did not reach the target position or if waitForCompletion parameter is set to false.

Examples
// 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 Functions
bool moveEndEffectorTo( 
  double yaw, 
  double roll = 0, 
  double pitch = 0, 
  bool   waitForCompletion = true);

Parameters

Parameter

Type

Description

yaw

double

The angle around the Z axis that the end effector should point to, in degrees.

roll

double

The angle around the X axis that the end effector should point to, in degrees. Default is 0.

pitch

double

The angle around the Y axis that the end effector should point to, in degrees. Default is 0.

waitForCompletion

bool

  • true (default) — The project waits until the function finishes before executing the next line of code.
  • false — The project starts the action and moves on to the next line of code right away, without waiting for the function to finish.

Return Values

Returns a Boolean indicating whether the end effector reached the target orientation.

  • true if the end effector reached the target orientation.

  • false if the end effector did not reach the target orientation or if waitForCompletion parameter is set to false.

Examples
// 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 Functions
bool moveEndEffectorInc( 
  double yaw, 
  double roll = 0, 
  double pitch = 0, 
  bool   waitForCompletion = true );

Parameters

Parameter

Type

Description

yaw

double

The angle around the Z axis that the end effector should change by, in degrees.

roll

double

The angle around the X axis that the end effector should change by, in degrees. Default is 0.

pitch

double

The angle around the Y axis that the end effector should change by, in degrees. Default is 0.

waitForCompletion

bool

  • true (default) — The project waits until the function finishes before executing the next line of code.
  • false — The project starts the action and moves on to the next line of code right away, without waiting for the function to finish.

Return Values

Returns a Boolean indicating whether the end effector reached the target orientation.

  • true if the end effector reached the target orientation.

  • false if the end effector did not reach the target orientation or if waitForCompletion parameter is set to false.

Examples
// Orient the end effector -50 degrees on the Y axis
Arm.moveEndEffectorInc(0, 0, -50);

setSpeed#

Sets the speed for arm movements.

Available Functions
void setSpeed( 
  uint32_t speed );

Parameters

Parameter

Type

Description

speed

uint32_t

The speed at which the arm should move in mm/s.

Return Values

This function does not return a value.

setEndEffectorType#

Sets the end effector type to magnet or pen.

Available Functions
bool setEndEffectorType( 
  endEffectorType type, 
  bool            waitForCompletion = true));

Parameters

Parameter

Type

Description

type

endEffectorType

An end effector type:

  • magnet
  • pen

waitForCompletion

bool

  • true (default) — The project waits until the function finishes before executing the next line of code.
  • false — The project starts the action and moves on to the next line of code right away, without waiting for the function to finish.

Return Values

Returns a Boolean indicating whether the requested type was set.

  • true if the requested type was set.

  • false if the requested type was not set or if waitForCompletion parameter is set to false.

Examples
// Set the end effector to the Magnet Pickup Tool.
Arm.setEndEffectorType(magnet);

setEndEffectorMagnet#

Sets the end effector magnet to enabled or disabled.

Available Functions
void setEndEffectorMagnet( 
  bool enabled );

Parameters

Parameter

Type

Description

enabled

bool

  • true – enable the magnet
  • false – disable the magnet

Return Values

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 Functions
void setPenOffset( 
  double zOffset );

Parameters

Parameter

Type

Description

zOffset

double

The new offset in millimeters. A positive z value indicates up.

Return Values

This function does not return a value.

setControlStop#

Disables the arm and places joint motors in brake mode.

Available Functions
void setControlStop( 
  bool state = true);

Parameters

Parameter

Type

Description

state

bool

  • true (default) — Disable further linear or joint moves.
  • false — Enable further linear or joint moves.

Return Values

This function does not return a value.

controlStopped#

Registers a function to be called when the arm control stop is enabled.

Available Functions
void controlStopped( 
  void (* callback)(void) );

Parameters

Parameter

Type

Description

callback

void (*)(void)

A function that will be called when the arm is control stopped.

Return Values

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 Functions
bool canArmReachTo( double x, double y, double z );

Parameters

Parameter

Type

Description

x

double

The X coordinate to move to, in millimeters.

y

double

The Y coordinate to move to, in millimeters.

z

double

The Z coordinate to move to, in millimeters.

Return Values

Returns true if the arm can move to the requested position, false if it cannot.

Examples
// 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 Functions
bool canArmReachInc( 
  double x, 
  double y, 
  double z );

Parameters

Parameter

Type

Description

x

double

The distance on the X axis to move for, in millimeters.

y

double

The distance on the Y axis to move for, in millimeters.

z

double

The distance on the Z axis to move for, in millimeters.

Return Values

Returns a Boolean indicating whether the arm can move to the requested position.

  • true if the arm can move to the requested position.

  • false if the arm cannot move to the requested position.

Examples
// 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 Functions
bool canEndEffectorReachTo( 
  double yaw, 
  double roll = 0, 
  double pitch = 0 );

Parameters

Parameter

Type

Description

yaw

double

The angle around the Z axis that the end effector should point to, in degrees.

roll

double

The angle around the X axis that the end effector should point to, in degrees. Default is 0.

pitch

double

The angle around the Y axis that the end effector should point to, in degrees. Default is 0.

Return Values

Returns a Boolean indicating whether the end effector can move to the requested orientation.

  • true if the end effector can move to the requested orientation.

  • false if the end effector cannot move to the requested orientation.

Examples
// 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 Functions
bool canEndEffectorReachInc( 
  double yaw, 
  double roll = 0, 
  double pitch = 0 );

Parameters

Parameter

Type

Description

yaw

double

The angle around the z-axis that the end effector will move for, in degrees.

roll

double

The angle around the x-axis that the end effector will move for, in degrees. Default is 0.

pitch

double

The angle around the y-axis that the end effector will move for, in degrees. Default is 0.

Return Values

Returns a Boolean indicating whether the end effector can move to the requested orientation.

  • true if the end effector can move to the requested orientation.

  • false if the end effector cannot move to the requested orientation.

Examples
// 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 Functions
bool isDone();

Parameters

This function does not have parameters.

Return Values

Returns a Boolean indicating whether the arm has completed its movement.

  • true if the arm has completed its movement.

  • false if the arm is still moving.

Examples
// 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 Functions
float getX();

Parameters

This function does not have parameters.

Return Values

Returns a float representing the X position of the end effector in millimeters.

Examples
// 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 Functions
float getY();

Parameters

This function does not have parameters.

Return Values

Returns a float representing the y-position of the end effector in millimeters.

Examples
// 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 Functions
float getZ();

Parameters

This function does not have parameters.

Return Values

Returns a float representing the z-position of the end effector in millimeters.

Examples
// 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 Functions
float getYaw();

Parameters

This function does not have parameters.

Return Values

Returns a float representing the current yaw of the end effector in degrees.

Examples
// Print the current yaw of the Arm in degrees
Brain.Screen.print(Arm.getYaw());

getRoll#

Returns the current roll of the end effector.

Available Functions
float getRoll();

Parameters

This function does not have parameters.

Return Values

Returns a float representing the current roll of the end effector in degrees.

Examples
// Print the current roll of the Arm in degrees
Brain.Screen.print(Arm.getRoll());

getPitch#

Returns the current pitch of the end effector.

Available Functions
float getPitch();

Parameters

This function does not have parameters.

Return Values

Returns a float representing the current pitch of the end effector in degrees.

Examples
// 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 Functions
void setTimeout( 
  int32_t   timeout, 
  timeUnits units );

Parameters

Parameter

Type

Description

timeout

int32_t

The new timeout value.

units

timeUnits

The unit that represents the time:

  • sec
  • – seconds
  • msec
  • – milliseconds

Return Values

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 Functions
bool isConnected();

Parameters

This function does not have parameters.

Return Values

Returns a Boolean indicating whether the arm is connected to the brain on the associated smartport.

  • true if the arm is connected to the brain on the associated smartport.

  • false if 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 Functions
uint32_t timestamp();

Parameters

This function does not have parameters.

Return Values

Returns the timestamp of the last status packet as a uint32_t in milliseconds.

installed#

Returns if the device is connected.

Available Functions
bool installed();

Parameters

This function does not have parameters.

Return Values

Returns a Boolean indicating whether the device is connected.

  • true if the device is connected.

  • false if the device is not connected.