Transmisión#
Introducción#
El robot VEX IQ (segunda generación) utiliza un sistema de transmisión para desplazarse y girar. Este sistema se compone de motores y ruedas que trabajan conjuntamente para mover el robot.
Un sistema de transmisión configurado puede usar un sensor giroscópico conectado (Sensing/Gyro.md), el sensor inercial integrado del sistema (Inertial.md) o ningún sensor. Cuando se usa un sensor, el sistema de transmisión lo utiliza para ayudar al robot a moverse y girar con precisión. Al inicio de cada proyecto, el sistema de transmisión calibra el sensor automáticamente. Mantenga el robot inmóvil durante aproximadamente 2 segundos durante la calibración para que pueda moverse y girar correctamente.
This page uses drivetrain as the example drivetrain name. Replace it with your own configured name as needed.
Existen muchas maneras de programar el sistema de transmisión. A continuación se muestra una lista de todos los métodos del sistema de transmisión:
Acciones: Mover y girar el robot.
drive— Moves the robot forward or reverse forever.drive_for— Moves the robot forward or reverse for a specific distance.turn— Turns the robot left or right forever.turn_for— Turns the robot left or right for a specific number of degrees.turn_to_heading— Turns the robot to face a specific heading from -359 to 359 degrees. The robot will turn the shortest direction to reach the target heading.turn_to_rotation— Turns the robot to a specific rotation.stop— Stops the robot’s movement.calibrate_drivetrain— Calibrates the sensor configured with the drivetrain.
Motadores: Ajusta la configuración de la transmisión.
set_drive_velocity— Tells the robot how fast to drive.set_turn_velocity— Tells the robot how fast to turn.set_stopping— Tells how the robot will stop moving: by braking, coasting, or holding.set_timeout— Sets how much time the robot will try to finish a movement.set_heading— Changes the robot’s current heading to a new heading.set_rotation— Changes the robot’s current rotation to a new rotation.set_turn_threshold— Tells how close the robot must get to a target angle before a turn is complete.set_turn_constant— Changes how strongly the robot corrects its turns.
Obtenedores: comprobar el estado del movimiento.
heading— Returns the robot’s current heading from 0 to 359 degrees.rotation— Returns the robot’s current rotation.velocity— Returns how fast the robot is driving.current— Returns how much electrical current the drivetrain is using.is_moving— Returns whether the robot is moving, as a Boolean value.is_done— Returns whether the robot is finished moving, as a Boolean value.is_turning— Returns whether the robot is turning, as a Boolean value.power— Returns how quickly the drivetrain is using energy.torque— Returns how much torque the drivetrain is using.efficiency— Returns how efficiently the drivetrain is using power.temperature— Returns how warm the drivetrain is.
Constructores: creen y configuren manualmente el sistema de transmisión.
DriveTrain— Creates a drivetrain without a Gyro Sensor or Inertial Sensor.SmartDrive— Creates a drivetrain with a Gyro Sensor or Inertial Sensor.
Comportamiento#
drive#
drive moves the robot forward or reverse forever. The robot will continue to move until it is given another action, like turning or stopping.
Usage:
drivetrain.drive(direction, velocity, units)
Parámetros |
Descripción |
|---|---|
|
The direction the robot moves: |
|
Optional. The velocity to drive with from 0% to 100% when using |
|
Optional. The velocity unit: |
# Drive forward then stop
drivetrain.drive(FORWARD)
wait(2, SECONDS)
drivetrain.stop()
# Drive slowly in reverse then stop
drivetrain.drive(REVERSE, 20, PERCENT)
wait(2, SECONDS)
drivetrain.stop()
drive_for#
drive_for moves the robot forward or reverse for a specific distance. The project will wait until the robot is done moving before the next line of code runs.
Usage:
drivetrain.drive_for(direction, distance, units, velocity, units_v, wait)
Parámetros |
Descripción |
|---|---|
|
The direction the robot moves: |
|
The distance the robot drives. This can be an |
|
Optional. The distance unit: |
|
Optional. The velocity to drive with from 0% to 100% when using |
|
Optional. The velocity unit: |
|
Optional. |
# Drive forward and backward
drivetrain.drive_for(FORWARD, 10)
drivetrain.drive_for(REVERSE, 10)
# Quickly drive forward and backward
drivetrain.drive_for(FORWARD, 200, MM, 100, PERCENT)
drivetrain.drive_for(REVERSE, 200, MM, 100, PERCENT)
turn#
turn turns the robot left or right forever. The robot will continue to turn until it is given another action, like driving or stopping.
Usage:
drivetrain.turn(direction, velocity, units)
Parámetros |
Descripción |
|---|---|
|
The direction the robot turns: |
|
Optional. The velocity to turn with from 0% to 100% when using |
|
Optional. The velocity unit: |
# Turn right and left, then stop
drivetrain.turn(RIGHT)
wait(2, SECONDS)
drivetrain.turn(LEFT)
wait(2, SECONDS)
drivetrain.stop()
# Quickly turn right and left, then stop
drivetrain.turn(RIGHT, 100, PERCENT)
wait(2, SECONDS)
drivetrain.turn(LEFT, 100, PERCENT)
wait(2, SECONDS)
drivetrain.stop()
turn_for#
turn_for turns the robot left or right for a specific number of degrees or turns. The turn is relative to the current position of the robot. The project will wait until the robot is done turning before the next line of code runs.
Usage:
drivetrain.turn_for(direction, angle, units, velocity, units_v, wait)
Parámetros |
Descripción |
|---|---|
|
The direction the robot turns: |
|
The amount the robot turns. This can be an |
|
Optional. The turn unit: |
|
Optional. The velocity to turn with from 0% to 100% when using |
|
Optional. The velocity unit: |
|
Optional. |
# Turn the robot right and left
drivetrain.turn_for(RIGHT, 90, DEGREES)
wait(1, SECONDS)
drivetrain.turn_for(LEFT, 90, DEGREES)
# Quickly turn the robot right and left
drivetrain.turn_for(RIGHT, 90, DEGREES, 100, PERCENT)
wait(1, SECONDS)
drivetrain.turn_for(LEFT, 90, DEGREES, 100, PERCENT)
turn_to_heading#
A heading is the direction the robot is facing, measured in degrees. turn_to_heading turns the robot to face a specific heading from -359 to 359 degrees. The robot will turn the shortest direction to reach the target heading.
La dirección inicial del robot es de 0 grados.
El proyecto esperará a que el robot termine de girar antes de ejecutar la siguiente línea de código.
Usage:
drivetrain.turn_to_heading(angle, units, velocity, units_v, wait)
Parámetros |
Descripción |
|---|---|
|
The direction the robot should face, in degrees. This can be an |
|
Optional. The heading unit: |
|
Optional. The velocity to turn with from 0% to 100% when using |
|
Optional. The velocity unit: |
|
Optional. |
# Turn to face the cardinal directions
drivetrain.turn_to_heading(90, DEGREES)
wait(1, SECONDS)
drivetrain.turn_to_heading(180, DEGREES)
wait(1, SECONDS)
drivetrain.turn_to_heading(270, DEGREES)
wait(1, SECONDS)
drivetrain.turn_to_heading(0, DEGREES)
# Turn twice slowly
drivetrain.turn_to_heading(90, DEGREES, 20, PERCENT)
wait(1, SECONDS)
drivetrain.turn_to_heading(180, DEGREES, 20, PERCENT)
turn_to_rotation#
turn_to_rotation turns the robot to a specific rotation.
Rotation is how much the robot has turned, measured in degrees or turns. At the beginning of a project, the rotation value is set to 0 degrees. Rotation can also be set using the set_rotation method.
Los valores de rotación son absolutos. Esto significa que la dirección del giro depende de la rotación actual del robot. Girar a la derecha aumenta la rotación, y girar a la izquierda la disminuye.
Por ejemplo, si el robot comienza en 0 grados y se le da una rotación de 720 grados, girará dos veces a la derecha. Si luego se le da una rotación de 360 grados, girará una vez a la izquierda, ya que 360 es menor que 720.
El proyecto esperará a que el robot termine de girar antes de ejecutar la siguiente línea de código.
Usage:
drivetrain.turn_to_rotation(angle, units, velocity, units_v, wait)
Parámetros |
Descripción |
|---|---|
|
The rotation value, in degrees or turns, that the robot will turn to. This can be an |
|
Optional. The rotation unit: |
|
Optional. The velocity to turn with from 0% to 100% when using |
|
Optional. The velocity unit: |
|
Optional. |
# Turn left, then spin in a circle
# clockwise and face right
drivetrain.turn_to_rotation(-90, DEGREES)
wait(1, SECONDS)
drivetrain.turn_to_rotation(450, DEGREES)
# Turn left then slowly spin in a
# circle clockwise
drivetrain.turn_to_rotation(-90, DEGREES)
wait(1, SECONDS)
drivetrain.turn_to_rotation(450, DEGREES, 20, PERCENT)
stop#
stop stops the robot’s movement.
Usage:
drivetrain.stop(mode)
Parámetros |
Descripción |
|---|---|
|
Optional. How the robot will stop:
|
# Drive forward then stop
drivetrain.drive(FORWARD)
wait(2, SECONDS)
drivetrain.stop()
# Drive forward and coast to a stop
drivetrain.set_drive_velocity(100, PERCENT)
drivetrain.drive(FORWARD)
wait(2, SECONDS)
drivetrain.stop(COAST)
calibrate_drivetrain#
calibrate_drivetrain is a built-in function that calibrates the Gyro Sensor or Inertial Sensor configured with the drivetrain.
La calibración ayuda al sensor a medir el movimiento correctamente. Mantenga el robot quieto durante aproximadamente 2 segundos durante la calibración. Si el robot se mueve durante la calibración, es posible que el sensor no mida el movimiento correctamente.
El proyecto esperará a que finalice la calibración antes de ejecutar la siguiente línea de código.
Nota: Esta función no se puede utilizar dentro de VS Code.
Usage:
calibrate_drivetrain()
Parámetros |
Descripción |
|---|---|
Esta función no tiene parámetros. |
Mutadores#
set_drive_velocity#
set_drive_velocity tells the robot how fast to drive. A higher percentage makes the robot drive faster and a lower percentage makes the robot drive slower.
Todos los proyectos comienzan con el robot conduciendo al 50% de su velocidad por defecto.
Nota: Una mayor velocidad hace que el robot se desplace más rápido, pero puede ser menos preciso. Una menor velocidad hace que el robot se desplace más despacio, pero puede ser más preciso.
Usage:
drivetrain.set_drive_velocity(velocity, units)
Parámetros |
Descripción |
|---|---|
|
The velocity to drive with from 0% to 100% when using |
|
Optional. The velocity unit: |
# Drive forward at different velocities
# Default velocity
drivetrain.drive_for(FORWARD, 150, MM)
wait(1, SECONDS)
# Drive slower
drivetrain.set_drive_velocity(20, PERCENT)
drivetrain.drive_for(FORWARD, 150, MM)
wait(1, SECONDS)
# Drive faster
drivetrain.set_drive_velocity(100, PERCENT)
drivetrain.drive_for(FORWARD, 150, MM)
set_turn_velocity#
set_turn_velocity tells the robot how fast to turn. A higher percentage makes the robot turn faster and a lower percentage makes the robot turn slower.
Todos los proyectos comienzan con el robot girando al 50% de su velocidad por defecto.
Nota: Una mayor velocidad hace que el robot gire más rápido, pero puede ser menos preciso. Una menor velocidad hace que el robot gire más despacio, pero puede ser más preciso.
Usage:
drivetrain.set_turn_velocity(velocity, units)
Parámetros |
Descripción |
|---|---|
|
The velocity to turn with from 0% to 100% when using |
|
Optional. The velocity unit: |
# Turn at different velocities
# Default velocity
drivetrain.turn_for(RIGHT, 360)
wait(1, SECONDS)
# Turn slower
drivetrain.set_turn_velocity(20, PERCENT)
drivetrain.turn_for(RIGHT, 360)
wait(1, SECONDS)
# Turn faster
drivetrain.set_turn_velocity(100, PERCENT)
drivetrain.turn_for(RIGHT, 360)
set_stopping#
set_stopping sets how the robot will stop moving: by braking, coasting, or holding.
Usage:
drivetrain.set_stopping(mode)
Parámetros |
Descripción |
|---|---|
|
How the robot will stop:
|
If this method is not used, the robot will use BRAKE when stopping.
set_timeout#
set_timeout sets how much time the robot will try to finish a movement. If the robot cannot finish in that time, it will stop trying and move on to the next line of code. This keeps the robot from getting stuck on a movement.
Usage:
drivetrain.set_timeout(value, units)
Parámetros |
Descripción |
|---|---|
|
The amount of time the robot can try to finish a movement. This can be a positive |
|
Optional. The unit of time: |
# Turn right after driving forward
drivetrain.set_timeout(1, SECONDS)
drivetrain.drive_for(FORWARD, 25, INCHES)
drivetrain.turn_for(RIGHT, 90)
set_heading#
A heading is the direction the robot is facing, measured in degrees. set_heading changes the robot’s current heading to a new heading value.
Por ejemplo, si el robot ha girado para mirar hacia la derecha, al establecer la orientación a 0 grados, esa posición mirando hacia la derecha se convierte en la nueva posición de 0 grados. Entonces, el robot puede girar a otras posiciones en función de esa nueva orientación.
Usage:
drivetrain.set_heading(heading, units)
Parámetros |
Descripción |
|---|---|
|
The heading value, in degrees or turns, to set for the robot. This can be an |
|
Optional. The heading unit: |
# Face the new 0 degrees
drivetrain.set_heading(90, DEGREES)
drivetrain.turn_to_heading(0, DEGREES)
set_rotation#
Rotation is how much the robot has turned, measured in degrees or turns. At the beginning of a project, the rotation value is set to 0 degrees. set_rotation changes the robot’s current rotation to a new value.
Por ejemplo, si el robot ha dado dos vueltas completas a la derecha, su valor de rotación será de 720 grados. Si se establece la rotación en 0 grados, esta volverá a su valor original. A partir de ahí, el robot podrá girar según ese nuevo valor.
Usage:
drivetrain.set_rotation(rotation, units)
Parámetros |
Descripción |
|---|---|
|
The rotation value, in degrees or turns, to set for the robot. This can be an |
|
Optional. The rotation unit: |
# Spin counterclockwise two times
drivetrain.set_rotation(720, DEGREES)
drivetrain.turn_to_rotation(0, DEGREES)
set_turn_threshold#
set_turn_threshold sets how close the robot must get to a target angle before a turn is complete.
Un umbral más pequeño puede hacer que los giros sean más precisos, pero el robot podría tardar más en terminar de girar. Un umbral más grande puede hacer que los giros terminen antes, pero podrían ser menos precisos.
Usage:
drivetrain.set_turn_threshold(value)
Parámetros |
Descripción |
|---|---|
|
The turn threshold, in degrees. This can be an |
# Set the turn threshold to 5 degrees
drivetrain.set_turn_threshold(5)
set_turn_constant#
set_turn_constant changes how strongly the robot corrects its turns.
Un valor más alto hace que el robot corrija los giros con mayor fuerza. Un valor más bajo hace que los giros sean más suaves. El valor predeterminado es 1.0.
Usage:
drivetrain.set_turn_constant(value)
Parámetros |
Descripción |
|---|---|
|
The turn constant. This can be a decimal ( |
# Increase the turn constant to 2.0
drivetrain.set_turn_constant(2.0)
Captadores#
heading#
A heading is the direction the robot is facing, measured in degrees. heading returns the robot’s current heading from 0 to 359 degrees.
La dirección inicial del robot es de 0 grados.
Usage:
drivetrain.heading(units)
Parámetros |
Descripción |
|---|---|
|
Optional. The unit to return heading in: |
# Display the heading after turning
drivetrain.turn_for(RIGHT, 450, DEGREES)
brain.screen.print("Heading: ")
brain.screen.print(drivetrain.heading())
rotation#
Rotation is how much the robot has turned, measured in degrees or turns. At the beginning of a project, the rotation value is set to 0 degrees. rotation returns the robot’s current rotation.
Girar a la derecha aumenta la rotación, y girar a la izquierda la disminuye. Por ejemplo, dar dos vueltas completas a la derecha produce una rotación de 720 grados.
Usage:
drivetrain.rotation(units)
Parámetros |
Descripción |
|---|---|
|
Optional. The unit to return rotation in: |
# Display the rotation after turning
drivetrain.turn_for(RIGHT, 450, DEGREES)
brain.screen.print("Rotation: ")
brain.screen.print(drivetrain.rotation())
velocity#
velocity returns how fast the robot is driving.
It can return velocity as a percentage from -100% to 100%, in RPM from -127 rpm to 127 rpm, or in VelocityUnits.DPS (degrees per second). A positive value means the robot is driving forward. A negative value means the robot is driving in reverse.
Usage:
drivetrain.velocity(units)
Parámetros |
Descripción |
|---|---|
|
Optional. The unit to return velocity in: |
current#
current returns how much electrical current the drivetrain is using, measured in amps (amperes). Current is the amount of electricity flowing through the drivetrain.
Un valor de corriente más alto significa que el sistema de transmisión está utilizando más corriente eléctrica. Esto puede ocurrir cuando el robot empuja contra un objeto o intenta moverse cuando está atascado.
Esto puede utilizarse para comprobar si el sistema de transmisión tiene dificultades durante el movimiento. Si la corriente se mantiene alta, el sistema de transmisión puede sobrecalentarse o consumir energía de forma menos eficiente.
Usage:
drivetrain.current(units)
Parámetros |
Descripción |
|---|---|
|
Optional. The unit to return current in: |
is_moving#
is_moving returns whether the robot is moving, as a Boolean value. This can be used to control the timing of other behaviors based on the robot’s movement.
True— The robot is moving.False— The robot is not moving.
This method works together with the following Drivetrain methods that have the wait parameter: drive_for, turn_for, turn_to_heading, and turn_to_rotation.
Usage:
drivetrain.is_moving()
Parámetros |
Descripción |
|---|---|
Este método no tiene parámetros. |
is_done#
is_done returns whether the robot is finished moving, as a Boolean value. This can be used to control the timing of other behaviors based on the robot’s movement.
True— The robot is finished moving.False— The robot is still moving.
This method works together with the following Drivetrain methods that have the wait parameter: drive_for, turn_for, turn_to_heading, and turn_to_rotation.
Usage:
drivetrain.is_done()
Parámetros |
Descripción |
|---|---|
Este método no tiene parámetros. |
is_turning#
is_turning returns whether the robot is turning, as a Boolean value. This can be used to control the timing of other behaviors based on the robot’s movement.
True— The robot is turning.False— The robot is not turning.
This method works together with the following Drivetrain methods that have the wait parameter: turn_for, turn_to_heading, and turn_to_rotation.
Usage:
drivetrain.is_turning()
Parámetros |
Descripción |
|---|---|
Este método no tiene parámetros. |
power#
power returns how much power the drivetrain is using, measured in watts. Power shows how quickly the drivetrain is using energy.
Un valor de potencia más alto significa que el sistema de transmisión consume energía más rápidamente. Esto puede ocurrir cuando el robot empuja contra un objeto o intenta moverse cuando está atascado.
Esto puede utilizarse para comparar movimientos o comprobar si la transmisión está teniendo dificultades. Si la potencia se mantiene alta, la transmisión puede calentarse o consumir energía de forma menos eficiente.
Usage:
drivetrain.power()
Parámetros |
Descripción |
|---|---|
Este método no tiene parámetros. |
torque#
El par motor indica la fuerza con la que el sistema de transmisión puede empujar o tirar mientras las ruedas giran.
torque returns how much torque the drivetrain is using, measured in Newton-meters (Nm) or inch-pounds (InLb).
Un valor de par motor más elevado indica que el sistema de transmisión está ejerciendo mayor fuerza de empuje o tracción. Esto puede ocurrir cuando el robot empuja contra un objeto o intenta moverse estando atascado.
Esto puede utilizarse para comprobar si el sistema de transmisión está teniendo dificultades o para comparar la fuerza que requieren los diferentes movimientos.
Usage:
drivetrain.torque(units)
Parámetros |
Descripción |
|---|---|
|
Optional. The unit to return torque in: |
efficiency#
efficiency returns how efficiently the drivetrain is using power, as a percentage from 0% to 100%.
La eficiencia indica cuánta potencia del sistema de transmisión se utiliza para el movimiento. Un valor de eficiencia más alto significa que se utiliza más potencia del sistema de transmisión para el movimiento. Un valor de eficiencia más bajo puede ocurrir cuando el sistema de transmisión trabaja intensamente pero no genera mucho movimiento, como cuando el robot está atascado o empujando contra un objeto.
Esto puede utilizarse para comparar movimientos o comprobar si el sistema de transmisión está desperdiciando energía en lugar de utilizarla para el movimiento.
Usage:
drivetrain.efficiency()
Parámetros |
Descripción |
|---|---|
Este método no tiene parámetros. |
temperature#
temperature returns the average temperature of the drivetrain in the selected temperature unit.
La temperatura indica el grado de calentamiento de los motores del sistema de transmisión. Una temperatura más alta significa que los motores se calientan durante su funcionamiento. Para que los motores funcionen a pleno rendimiento, deben mantenerse por debajo de los 55 °C.
Si los motores se sobrecalientan, reducirán su corriente máxima para protegerse. A 70 °C, los motores dejarán de funcionar hasta que se enfríen.
Esto puede utilizarse para comprobar si el sistema de transmisión se calienta demasiado durante movimientos repetidos, recorridos largos o cuando ejerce presión contra un objeto.
Usage:
drivetrain.temperature(units)
Parámetros |
Descripción |
|---|---|
|
Optional. The unit to return temperature in: |
Constructores#
Constructors are used to create DriveTrain and SmartDrive objects in code. This is useful when configuring a drivetrain without using the Devices window.
At least two Motor or MotorGroup objects must be created before creating a drivetrain.
DriveTrain#
DriveTrain creates a drivetrain without a Gyro Sensor or Inertial Sensor.
Usage:
DriveTrain(lm, rm, wheelTravel, trackWidth, wheelBase, units, externalGearRatio)
Parámetro |
Descripción |
|---|---|
|
El motor o grupo motor izquierdo. |
|
El motor o grupo motor derecho. |
|
Opcional. La circunferencia de las ruedas de la transmisión. El valor predeterminado es de 300 milímetros. |
|
Opcional. El ancho entre las ruedas izquierda y derecha. El valor predeterminado es de 320 milímetros. |
|
Opcional. Distancia entre las ruedas delanteras y traseras. El valor predeterminado es de 320 milímetros. |
|
Optional. The unit for |
|
Optional. The gear ratio used to adjust drive distances if gears are used. This can be an |
# Create left and right drive motor objects
left_drive_smart = Motor(Ports.PORT1, 1.0, False)
right_drive_smart = Motor(Ports.PORT2, 1.0, True)
'''
Create a Drivetrain with the following values:
wheelTravel: 200
trackWidth: 173
wheelBase: 76
units: MM
externalGearRatio: 1
'''
drivetrain = DriveTrain(left_drive_smart, right_drive_smart, 200, 173, 76, MM, 1)
# Create two motor group objects for left and right motors
left_motor_a = Motor(Ports.PORT1, 1.0, False)
left_motor_b = Motor(Ports.PORT2, 1.0, False)
left_drive_smart = MotorGroup(left_motor_a, left_motor_b)
right_motor_a = Motor(Ports.PORT3, 1.0, True)
right_motor_b = Motor(Ports.PORT4, 1.0, True)
right_drive_smart = MotorGroup(right_motor_a, right_motor_b)
'''
Create a Drivetrain with the following values:
wheelTravel: 200
trackWidth: 173
wheelBase: 76
units: MM
externalGearRatio: 1
'''
drivetrain = DriveTrain(left_drive_smart, right_drive_smart, 200, 173, 76, MM, 1)
SmartDrive#
SmartDrive creates a drivetrain with a Gyro Sensor or Inertial Sensor.
Usage:
SmartDrive(lm, rm, g, wheelTravel, trackWidth, wheelBase, units, externalGearRatio)
Parámetro |
Descripción |
|---|---|
|
El motor o grupo motor izquierdo. |
|
El motor o grupo motor derecho. |
|
El Sensor giroscópico o Sensor inercial utilizado por el sistema de transmisión. |
|
Opcional. La circunferencia de las ruedas de la transmisión. El valor predeterminado es de 300 milímetros. |
|
Opcional. El ancho entre las ruedas izquierda y derecha. El valor predeterminado es de 320 milímetros. |
|
Opcional. Distancia entre las ruedas delanteras y traseras. El valor predeterminado es de 320 milímetros. |
|
Optional. The unit for |
|
Optional. The gear ratio used to adjust drive distances if gears are used. This can be an |
# Create the Inertial Sensor
brain_inertial = Inertial()
# Make left and right drive motors
left_drive_smart = Motor(Ports.PORT1, 1.0, False)
right_drive_smart = Motor(Ports.PORT6, 1.0, True)
# Create a SmartDrive object with wheelTravel 200
drivetrain = SmartDrive(left_drive_smart, right_drive_smart, brain_inertial, 200)
Si se va a crear un sistema de transmisión inteligente con varios motores, es necesario crear los motores por separado antes de agruparlos en un grupo de motores.
# Create the Inertial Sensor
brain_inertial = Inertial()
# Create two motor groups for left and right motors
left_motor_a = Motor(Ports.PORT1, 1.0, False)
left_motor_b = Motor(Ports.PORT2, 1.0, False)
left_drive_smart = MotorGroup(left_motor_a, left_motor_b)
right_motor_a = Motor(Ports.PORT5, 1.0, True)
right_motor_b = Motor(Ports.PORT6, 1.0, True)
right_drive_smart = MotorGroup(right_motor_a, right_motor_b)
# Create a SmartDrive object with wheelTravel 200 mm
drivetrain = SmartDrive(left_drive_smart, right_drive_smart, brain_inertial, 200)