Brazo con CTE#

Introducción#

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.

Constructores#

arm#

arm creates a 6-Axis Arm object.

Función disponible

arm(int32_t index);

Parámetro

Tipo

Descripción

index

int32_t

The Smart Port that the 6-Axis Arm is connected to, written as PORTx, where x is the port number. For example, PORT1.

Ejemplo

// Create a 6-Axis Arm named Arm on Port 1
arm Arm = arm(PORT1);

Incinerador de basuras#

~arm#

~arm destroys the arm object and releases associated resources.

Función disponible

~arm();

Funciones de los miembros#

The arm class includes the following member functions:

Acciones: Mueva el brazo de 6 ejes a posiciones u orientaciones.

  • 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.

Motadores: configura el movimiento, las herramientas y los ajustes de control.

  • 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.

Obtenedores: Devuelven el estado del movimiento, la posición, la orientación y los valores de conexión.

  • 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.

Funciones de devolución de llamada: Ejecuta funciones cuando se producen eventos en el brazo.

  • controlStopped — Registers a function to run when control stop is enabled.

  • crashed — Registers a function to run when a crash is detected.

Comportamiento#

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.

Función disponible

bool moveTo(
  double x,
  double y,
  double z,
  bool   waitForCompletion = true
);

Parámetro

Tipo

Descripción

x

double

La coordenada x de la posición objetivo en milímetros.

y

double

La coordenada y de la posición objetivo en milímetros.

z

double

La coordenada z de la posición objetivo en milímetros.

waitForCompletion

bool

Optional. true (default) waits until the movement is complete before continuing. false starts the movement and immediately continues to the next line of code.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm reached the target position.

  • false — The 6-Axis Arm did not reach the target position, or waitForCompletion was set to false.

Ejemplos

// 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.

Función disponible

bool moveInc(
  double x,
  double y,
  double z,
  bool   waitForCompletion = true
);

Parámetro

Tipo

Descripción

x

double

La distancia a recorrer a lo largo del eje x en milímetros.

y

double

La distancia a recorrer a lo largo del eje y en milímetros.

z

double

La distancia a recorrer a lo largo del eje z en milímetros.

waitForCompletion

bool

Optional. true (default) waits until the movement is complete before continuing. false starts the movement and immediately continues to the next line of code.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm reached the requested position.

  • false — The 6-Axis Arm did not reach the requested position, or waitForCompletion was set to false.

Ejemplo

// 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.

Función disponible

bool moveEndEffectorTo(
  double yaw,
  double roll = 0,
  double pitch = 0,
  bool   waitForCompletion = true
);

Parámetro

Tipo

Descripción

yaw

double

El ángulo de guiñada objetivo en grados.

roll

double

Optional. The target roll angle in degrees. The default is 0.

pitch

double

Optional. The target pitch angle in degrees. The default is 0.

waitForCompletion

bool

Optional. true (default) waits until the movement is complete before continuing. false starts the movement and immediately continues to the next line of code.

Valor de retorno

Devuelve un valor booleano.

  • true — The end effector reached the target orientation.

  • false — The end effector did not reach the target orientation, or waitForCompletion was set to false.

Ejemplo

// 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.

Utilice esta función para rotar en relación con el guiñada, el balanceo o la inclinación actuales del efector final.

Función disponible

bool moveEndEffectorInc(
  double yaw,
  double roll = 0,
  double pitch = 0,
  bool   waitForCompletion = true
);

Parámetro

Tipo

Descripción

yaw

double

El cambio en la guiñada, en grados.

roll

double

Optional. The change in roll, in degrees. The default is 0.

pitch

double

Optional. The change in pitch, in degrees. The default is 0.

waitForCompletion

bool

Optional. true (default) waits until the movement is complete before continuing. false starts the movement and immediately continues to the next line of code.

Valor de retorno

Devuelve un valor booleano.

  • true — The end effector reached the requested orientation.

  • false — The end effector did not reach the requested orientation, or waitForCompletion was set to false.

Ejemplo

// Rotate the end effector -50 degrees in pitch
Arm.moveEndEffectorInc(0, 0, -50);

Mutadores#

setSpeed#

setSpeed sets the movement speed used by the 6-Axis Arm.

Función disponible

void setSpeed(uint32_t speed);

Parámetro

Tipo

Descripción

speed

uint32_t

La velocidad a la que debe moverse el brazo de 6 ejes, en milímetros por segundo.

Valor de retorno

Esta función no devuelve ningún valor.

Ejemplo

// Set the 6-Axis Arm movement speed
Arm.setSpeed(100);

setEndEffectorType#

setEndEffectorType sets the type of end effector attached to the 6-Axis Arm.

Cuando se cambia el tipo de efector final, el brazo de 6 ejes ajusta automáticamente su desplazamiento Z para que coincida con la herramienta seleccionada.

Función disponible

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

Parámetro

Tipo

Descripción

type

endEffectorType

The tool attached to the 6-Axis Arm: magnet (Magnet Pickup Tool) or pen (Pen Holder Tool).

waitForCompletion

bool

Optional. true (default) waits until the change is complete before continuing. false starts the change and immediately continues to the next line of code.

Valor de retorno

Devuelve un valor booleano.

  • true — The requested type was set.

  • false — The requested type was not set, or waitForCompletion was set to false.

Ejemplo

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

setEndEffectorMagnet#

setEndEffectorMagnet enables or disables the Magnet Pickup Tool.

Función disponible

void setEndEffectorMagnet(bool enabled);

Parámetro

Tipo

Descripción

enabled

bool

true enables the magnet to pick up and hold objects. false disables the magnet and drops any held object.

Valor de retorno

Esta función no devuelve ningún valor.

Ejemplo

// 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.

El desplazamiento del lápiz es la distancia desde la parte superior del soporte del lápiz hasta la punta del marcador de borrado en seco. Un valor z positivo desplaza el desplazamiento hacia arriba desde el punto de montaje de la herramienta.

Función disponible

void setPenOffset(double zOffset);

Parámetro

Tipo

Descripción

zOffset

double

Valor de desplazamiento del lápiz en milímetros.

Valor de retorno

Esta función no devuelve ningún valor.

Ejemplo

// 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.

Cuando se habilita la parada de control, el brazo de 6 ejes detiene inmediatamente el movimiento e impide cualquier movimiento lineal o articular adicional.

Función disponible

void setControlStop(bool state = true);

Parámetro

Tipo

Descripción

state

bool

Optional. true (default) enables control stop and prevents further linear or joint movements. false disables control stop.

Valor de retorno

Esta función no devuelve ningún valor.

Ejemplo

// Stop the 6-Axis Arm and prevent further movement
Arm.setControlStop();

setTimeout#

setTimeout sets the timeout value used when moving the 6-Axis Arm.

Si un movimiento no finaliza antes de que se agote el tiempo de espera, el proyecto continúa con la siguiente línea de código.

Función disponible

void setTimeout(
  int32_t   timeout,
  timeUnits units
);

Parámetro

Tipo

Descripción

timeout

int32_t

El nuevo valor de tiempo de espera.

units

timeUnits

The time unit: sec (seconds) or msec (milliseconds).

Valor de retorno

Esta función no devuelve ningún valor.

Ejemplo

// 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.

Función disponible

bool isDone();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm has finished moving.

  • false — The 6-Axis Arm is still moving.

Ejemplo

// 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.

Cuando se detecta una colisión, el brazo de 6 ejes detiene el movimiento del motor y puede parecer que se queda inmóvil. Esto reduce la tensión y ayuda a proteger los motores de daños accidentales.

Función disponible

bool isCrashed();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm has crashed.

  • false — The 6-Axis Arm has not crashed.

Ejemplo

// 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.

Utilice esta función para leer la posición actual del efector final a lo largo del eje x.

Función disponible

float getX();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

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

Ejemplo

// 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.

Utilice esta función para leer la posición actual del efector final a lo largo del eje Y.

Función disponible

float getY();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

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

Ejemplo

// 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.

Utilice esta función para leer la posición actual del efector final a lo largo del eje z.

Función disponible

float getZ();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

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

Ejemplo

// 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.

Función disponible

float getYaw();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

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

Ejemplo

// 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.

Función disponible

float getRoll();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

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

Ejemplo

// 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.

Función disponible

float getPitch();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

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

Ejemplo

// 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.

Función disponible

bool canArmReachTo(
  double x,
  double y,
  double z
);

Parámetro

Tipo

Descripción

x

double

La coordenada x de la posición objetivo en milímetros.

y

double

La coordenada y de la posición objetivo en milímetros.

z

double

La coordenada z de la posición objetivo en milímetros.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm can reach the requested position.

  • false — The 6-Axis Arm cannot reach the requested position.

Ejemplo

// 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.

Función disponible

bool canArmReachInc(
  double x,
  double y,
  double z
);

Parámetro

Tipo

Descripción

x

double

La distancia a recorrer a lo largo del eje x en milímetros.

y

double

La distancia a recorrer a lo largo del eje y en milímetros.

z

double

La distancia a recorrer a lo largo del eje z en milímetros.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm can make the requested movement.

  • false — The 6-Axis Arm cannot make the requested movement.

Ejemplo

// 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.

Función disponible

bool canEndEffectorReachTo(
  double yaw,
  double roll = 0,
  double pitch = 0
);

Parámetro

Tipo

Descripción

yaw

double

El ángulo de guiñada objetivo en grados.

roll

double

Optional. The target roll angle in degrees. The default is 0.

pitch

double

Optional. The target pitch angle in degrees. The default is 0.

Valor de retorno

Devuelve un valor booleano.

  • true — The end effector can reach the requested orientation.

  • false — The end effector cannot reach the requested orientation.

Ejemplo

// 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.

Función disponible

bool canEndEffectorReachInc(
  double yaw,
  double roll = 0,
  double pitch = 0
);

Parámetro

Tipo

Descripción

yaw

double

El cambio en la guiñada, en grados.

roll

double

Optional. The change in roll, in degrees. The default is 0.

pitch

double

Optional. The change in pitch, in degrees. The default is 0.

Valor de retorno

Devuelve un valor booleano.

  • true — The end effector can make the requested rotation.

  • false — The end effector cannot make the requested rotation.

Ejemplo

// 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.

Función disponible

bool isConnected();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm is connected to the EXP Brain.

  • false — The 6-Axis Arm is not connected to the EXP Brain.

Ejemplo

// 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.

Función disponible

uint32_t timestamp();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

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

installed#

installed returns whether the 6-Axis Arm is connected.

Función disponible

bool installed();

Parámetros

Esta función no tiene parámetros.

Valor de retorno

Devuelve un valor booleano.

  • true — The 6-Axis Arm is connected.

  • false — The 6-Axis Arm is not connected.

Devoluciones de llamada#

controlStopped#

controlStopped registers a function that runs when control stop is enabled.

Función disponible

void controlStopped(void (* callback)(void));

Parámetro

Tipo

Descripción

callback

void (*)(void)

Una función que se ejecuta cuando se habilita la parada de control.

Valor de retorno

Esta función no devuelve ningún valor.

Ejemplo

// 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.

Cuando se detecta una colisión, el brazo de 6 ejes detiene el movimiento del motor y puede parecer que se queda inmóvil. Esto reduce la tensión y ayuda a proteger los motores de daños accidentales.

Función disponible

void crashed(void (* callback)(void));

Parámetro

Tipo

Descripción

callback

void (*)(void)

Una función que se ejecuta cuando el brazo de 6 ejes se ha bloqueado durante el movimiento.

Valor de retorno

Esta función no devuelve ningún valor.

Ejemplo

// 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);
}