Giroscopios - Software
Nota
Esta sección cubre la parte de software de los giroscopios. Para una guía mecánica de estos, véase docs/hardware/sensors/gyros-hardware:Giroscopios - Hardware.
A gyroscope, or «gyro,» is an angular rate sensor typically used in robotics to measure and/or stabilize robot headings. WPILib natively provides specific support for the ADXRS450 gyro available in the kit of parts, as well as more general support for a wider variety of analog gyros through the AnalogGyro class.
There are getters the current angular rate and heading and functions for zeroing the current heading and calibrating the gyro.
Nota
Es crucial que el robot permanezca inmóvil al calibrar el giroscopio.
ADIS16448
The ADIS16448 uses the ADIS16448_IMU
class (Java, C++, Python
). See the Analog Devices ADIS16448 documentation for additional information and examples.
Advertencia
The Analog Devices documentation linked above contains outdated instructions for software installation as the ADIS16448 is now built into WPILib.
// ADIS16448 plugged into the MXP port
ADIS16448_IMU gyro = new ADIS16448_IMU();
// ADIS16448 plugged into the MXP port
ADIS16448_IMU gyro;
from wpilib import ADIS16448_IMU
# ADIS16448 plugged into the MXP port
self.gyro = ADIS16448_IMU()
ADIS16470
The ADIS16470 uses the ADIS16470_IMU
class (Java, C++, Python
). See the Analog Devices ADIS16470 documentation for additional information and examples.
Advertencia
The Analog Devices documentation linked above contains outdated instructions for software installation as the ADIS16470 is now built into WPILib.
// ADIS16470 plugged into the SPI port
ADIS16470_IMU gyro = new ADIS16470_IMU();
// ADIS16470 plugged into the SPI port
ADIS16470_IMU gyro;
# ADIS16470 plugged into the SPI port
self.gyro = ADIS16470_IMU()
ADXRS450_Gyro
The ADXRS450_Gyro
class (Java, C++, Python
) provides support for the Analog Devices ADXRS450 gyro available in the kit of parts, which connects over the SPI bus.
Nota
El uso de varios ADXRS450 Gyro se maneja a través de circuitos especiales en la FPGA, así que solo se debería usar una instancia ADXRS450_Gyro
.
// Creates an ADXRS450_Gyro object on the onboard SPI port
ADXRS450_Gyro gyro = new ADXRS450_Gyro();
// Creates an ADXRS450_Gyro object on the onboard SPI port
frc::ADXRS450_Gyro gyro;
# Creates an ADXRS450_Gyro object on the onboard SPI port
self.gyro = ADXRS450_Gyro()
AnalogGyro
The AnalogGyro
class (Java, C++, Python
) provides support for any single-axis gyro with an analog output.
Nota
El uso de varios ADXRS450 Gyro se maneja a través de circuitos especiales en la FPGA, de acuerdo a esto solo se debería usar AnalogGyro
`s en los puertos analógicos 0 y 1.
// Creates an AnalogGyro object on port 0
AnalogGyro gyro = new AnalogGyro(0);
// Creates an AnalogGyro object on port 0
frc::AnalogGyro gyro{0};
# Creates an AnalogGyro object on port 0
self.gyro = AnalogGyro(0)
Pigeon 2
The Pigeon should use the Pigeon2
class. The Pigeon can either be connected with CAN or by data cable to a TalonSRX. The Pigeon IMU User’s Guide contains full details on using the Pigeon.
private final Pigeon2 pidgey = new Pigeon2(1, "rio"); // Pigeon is on roboRIO CAN Bus with device ID 1
ctre::phoenix6::hardware::Pigeon2 pidgey{1, "rio"}; // Pigeon is on roboRIO CAN Bus with device ID 1
import phoenix5
import ctre.sensors
self.gyro = ctre.WPI_PigeonIMU(0); # Pigeon is on CAN Bus with device ID 0
# OR (choose one or the other based on your connection)
talon = ctre.TalonSRX(0); # TalonSRX is on CAN Bus with device ID 0
self.gyro = ctre.WPI_PigeonIMU(talon) # Pigeon uses the talon created above
Usando giroscopios en código
Nota
Como los gyros miden la velocidad en vez de la posición, la posición se infiere integrando (sumando) la señal de la velocidad para obtener el cambio total en el ángulo. Así, todas las mediciones del giroscopio son relativas a un punto cero arbitrario (determinado por el ángulo del giroscopio ya sea cuando se encendió el robot o restableciendo este punto), sufren una acumulación de errores (llamada desvío) que incrementa a medida que el gyro se usa. La cantidad de desvió varía de acuerdo al tipo de gyro.
Los gyros son extremadamente útiles en el FRC tanto para medir como para controlar el rumbo de los robots. Dado que las coincidencias de FRC son generalmente cortas, la deriva total del giróscopo en el curso de un partido de FRC tiende a ser manejablemente pequeña (del orden de un par de grados para un giróscopo de buena calidad). Además, no todas las aplicaciones útiles de los giroscopios requieren que la medición absoluta del rumbo sea precisa durante todo el partido.
Mostrando el rumbo del robot en la dashboard
Shuffleboard includes a widget for displaying heading data from a gyro in the form of a compass. This can be helpful for viewing the robot heading when sight lines to the robot are obscured:
// Use gyro declaration from above here
public Robot() {
// Places a compass indicator for the gyro heading on the dashboard
Shuffleboard.getTab("Example tab").add(gyro);
}
// Use gyro declaration from above here
Robot::Robot() {
// Places a compass indicator for the gyro heading on the dashboard
frc::Shuffleboard.GetTab("Example tab").Add(gyro);
}
from wpilib.shuffleboard import Shuffleboard
def robotInit(self):
# Use gyro declaration from above here
# Places a compass indicator for the gyro heading on the dashboard
Shuffleboard.getTab("Example tab").add(self.gyro)
Estabilizando el rumbo mientras se maneja
Un uso muy común de un gyro es estabilizar el rumbo del robot mientras conduce, para que el robot conduzca recto. Esto es especialmente importante para los impulsos holonómicos como el mecanismo y el desvío, pero también es muy útil para los impulsos de los tanques.
Esto se logra típicamente cerrando un controlador PID en la velocidad de giro o en el rumbo, y canalizando la salida del lazo hacia el control de giro de uno (en el caso del accionamiento de un tanque, esto sería una diferencia de velocidad entre los dos lados de la unidad).
Advertencia
Como con todos los bucles de control, los usuarios deben tener cuidado de asegurarse de que la dirección del sensor y la dirección de giro sean consistentes. Si no lo son, el bucle será inestable y el robot girará salvajemente.
Ejemplo: Estabilización de la conducción del tanque usando la velocidad de giro
El siguiente ejemplo muestra cómo estabilizar el rumbo utilizando un simple bucle P cerrado en la velocidad de giro. Dado que un robot que no está girando debería tener una tasa de giro de cero, el punto de ajuste del bucle es implícitamente cero, lo que hace que este método sea muy simple.
// Use gyro declaration from above here
// The gain for a simple P loop
double kP = 1;
// Initialize motor controllers and drive
Spark leftLeader = new Spark(0);
Spark leftFollower = new Spark(1);
Spark rightLeader = new Spark(2);
Spark rightFollower = new Spark(3);
DifferentialDrive drive = new DifferentialDrive(leftLeader::set, rightLeader::set);
public Robot() {
// Configures the encoder's distance-per-pulse
// The robot moves forward 1 foot per encoder rotation
// There are 256 pulses per encoder rotation
encoder.setDistancePerPulse(1./256.);
// Invert the right side of the drivetrain. You might have to invert the other side
rightLeader.setInverted(true);
// Configure the followers to follow the leaders
leftLeader.addFollower(leftFollower);
rightLeader.addFollower(rightFollower);
}
@Override
public void autonomousPeriodic() {
// Setpoint is implicitly 0, since we don't want the heading to change
double error = -gyro.getRate();
// Drives forward continuously at half speed, using the gyro to stabilize the heading
drive.tankDrive(.5 + kP * error, .5 - kP * error);
}
// Use gyro declaration from above here
// The gain for a simple P loop
double kP = 1;
// Initialize motor controllers and drive
frc::Spark leftLeader{0};
frc::Spark leftFollower{1};
frc::Spark rightLeader{2};
frc::Spark rightFollower{3};
frc::DifferentialDrive drive{[&](double output) { leftLeader.Set(output); },
[&](double output) { rightLeader.Set(output); }};
Robot::Robot() {
// Invert the right side of the drivetrain. You might have to invert the other side
rightLeader.SetInverted(true);
// Configure the followers to follow the leaders
leftLeader.AddFollower(leftFollower);
rightLeader.AddFollower(rightFollower);
}
void Robot::AutonomousPeriodic() {
// Setpoint is implicitly 0, since we don't want the heading to change
double error = -gyro.GetRate();
// Drives forward continuously at half speed, using the gyro to stabilize the heading
drive.TankDrive(.5 + kP * error, .5 - kP * error);
}
from wpilib import Spark
from wpilib import MotorControllerGroup
from wpilib.drive import DifferentialDrive
def robotInit(self):
# Use gyro declaration from above here
# The gain for a simple P loop
self.kP = 1
# Initialize motor controllers and drive
left1 = Spark(0)
left2 = Spark(1)
right1 = Spark(2)
right2 = Spark(3)
leftMotors = MotorControllerGroup(left1, left2)
rightMotors = MotorControllerGroup(right1, right2)
self.drive = DifferentialDrive(leftMotors, rightMotors)
rightMotors.setInverted(true)
def autonomousPeriodic(self):
# Setpoint is implicitly 0, since we don't want the heading to change
error = -self.gyro.getRate()
# Drives forward continuously at half speed, using the gyro to stabilize the heading
self.drive.tankDrive(.5 + self.kP * error, .5 - self.kP * error)
Nota
MotorControllerGroup is deprecated in 2024. Can you help update the Python example?
Las implementaciones más avanzadas pueden utilizar un bucle de control más complicado. Al cerrar el bucle en la tasa de giro para la estabilización del rumbo, los bucles PI son particularmente efectivos.
Ejemplo: Estabilización de la conducción del tanque usando el rumbo
El siguiente ejemplo muestra cómo estabilizar el rumbo utilizando un simple bucle P cerrado en el rumbo. A diferencia del ejemplo de la velocidad de giro, necesitaremos establecer el punto de ajuste del rumbo actual antes de iniciar el movimiento, lo que hace que este método sea un poco más complicado.
// Use gyro declaration from above here
// The gain for a simple P loop
double kP = 1;
// The heading of the robot when starting the motion
double heading;
// Initialize motor controllers and drive
Spark left1 = new Spark(0);
Spark left2 = new Spark(1);
Spark right1 = new Spark(2);
Spark right2 = new Spark(3);
MotorControllerGroup leftMotors = new MotorControllerGroup(left1, left2);
MotorControllerGroup rightMotors = new MotorControllerGroup(right1, right2);
DifferentialDrive drive = new DifferentialDrive(leftMotors, rightMotors);
public Robot() {
rightMotors.setInverted(true);
}
@Override
public void autonomousInit() {
// Set setpoint to current heading at start of auto
heading = gyro.getAngle();
}
@Override
public void autonomousPeriodic() {
double error = heading - gyro.getAngle();
// Drives forward continuously at half speed, using the gyro to stabilize the heading
drive.tankDrive(.5 + kP * error, .5 - kP * error);
}
// Use gyro declaration from above here
// The gain for a simple P loop
double kP = 1;
// The heading of the robot when starting the motion
double heading;
// Initialize motor controllers and drive
frc::Spark left1{0};
frc::Spark left2{1};
frc::Spark right1{2};
frc::Spark right2{3};
frc::MotorControllerGroup leftMotors{left1, left2};
frc::MotorControllerGroup rightMotors{right1, right2};
frc::DifferentialDrive drive{leftMotors, rightMotors};
Robot::Robot() {
rightMotors.SetInverted(true);
}
void Robot::AutonomousInit() {
// Set setpoint to current heading at start of auto
heading = gyro.GetAngle();
}
void Robot::AutonomousPeriodic() {
double error = heading - gyro.GetAngle();
// Drives forward continuously at half speed, using the gyro to stabilize the heading
drive.TankDrive(.5 + kP * error, .5 - kP * error);
}
from wpilib import Spark
from wpilib import MotorControllerGroup
from wpilib.drive import DifferentialDrive
def robotInit(self):
# Use gyro declaration from above here
# The gain for a simple P loop
self.kP = 1
# Initialize motor controllers and drive
left1 = Spark(0)
left2 = Spark(1)
right1 = Spark(2)
right2 = Spark(3)
leftMotors = MotorControllerGroup(left1, left2)
rightMotors = MotorControllerGroup(right1, right2)
self.drive = DifferentialDrive(leftMotors, rightMotors)
rightMotors.setInverted(true)
def autonomousInit(self):
# Set setpoint to current heading at start of auto
self.heading = self.gyro.getAngle()
def autonomousPeriodic(self):
error = self.heading - self.gyro.getAngle()
# Drives forward continuously at half speed, using the gyro to stabilize the heading
self.drive.tankDrive(.5 + self.kP * error, .5 - self.kP * error)
Las implementaciones más avanzadas pueden utilizar un bucle de control más complicado. Cuando se cierra el bucle en el rumbo para la estabilización del rumbo, los bucles PD son particularmente efectivos.
Pasando a un rumbo fijo
Otra aplicación común y muy útil para un gyro es hacer girar a un robot para que se dirija a una dirección específica. Esto puede ser un componente de una rutina de conducción autónoma, o puede utilizarse durante el control teleoperado para ayudar a alinear un robot con los elementos de campo.
Al igual que con la estabilización del rumbo, esto se logra a menudo con un bucle PID - a diferencia de la estabilización, sin embargo, el bucle sólo puede cerrarse en el rumbo. El siguiente código de ejemplo hará que el robot se enfrente a 90 grados con un simple bucle P:
// Use gyro declaration from above here
// The gain for a simple P loop
double kP = 0.05;
// Initialize motor controllers and drive
Spark left1 = new Spark(0);
Spark left2 = new Spark(1);
Spark right1 = new Spark(2);
Spark right2 = new Spark(3);
MotorControllerGroup leftMotors = new MotorControllerGroup(left1, left2);
MotorControllerGroup rightMotors = new MotorControllerGroup(right1, right2);
DifferentialDrive drive = new DifferentialDrive(leftMotors, rightMotors);
public Robot() {
rightMotors.setInverted(true);
}
@Override
public void autonomousPeriodic() {
// Find the heading error; setpoint is 90
double error = 90 - gyro.getAngle();
// Turns the robot to face the desired direction
drive.tankDrive(kP * error, -kP * error);
}
// Use gyro declaration from above here
// The gain for a simple P loop
double kP = 0.05;
// Initialize motor controllers and drive
frc::Spark left1{0};
frc::Spark left2{1};
frc::Spark right1{2};
frc::Spark right2{3};
frc::MotorControllerGroup leftMotors{left1, left2};
frc::MotorControllerGroup rightMotors{right1, right2};
frc::DifferentialDrive drive{leftMotors, rightMotors};
Robot::Robot() {
rightMotors.SetInverted(true);
}
void Robot::AutonomousPeriodic() {
// Find the heading error; setpoint is 90
double error = 90 - gyro.GetAngle();
// Turns the robot to face the desired direction
drive.TankDrive(kP * error, -kP * error);
}
from wpilib import Spark
from wpilib import MotorControllerGroup
from wpilib.drive import DifferentialDrive
def robotInit(self):
# Use gyro declaration from above here
# The gain for a simple P loop
self.kP = 0.05
# Initialize motor controllers and drive
left1 = Spark(0)
left2 = Spark(1)
right1 = Spark(2)
right2 = Spark(3)
leftMotors = MotorControllerGroup(left1, left2)
rightMotors = MotorControllerGroup(right1, right2)
self.drive = DifferentialDrive(leftMotors, rightMotors)
rightMotors.setInverted(true)
def autonomousPeriodic(self):
# Find the heading error; setpoint is 90
error = 90 - self.gyro.getAngle()
# Drives forward continuously at half speed, using the gyro to stabilize the heading
self.drive.tankDrive(self.kP * error, -self.kP * error)
Al igual que antes, las implementaciones más avanzadas pueden utilizar bucles de control más complicados.
Nota
Los bucles de giro-a-ángulo pueden ser difíciles de afinar correctamente debido a la fricción estática en la transmisión, especialmente si se utiliza un simple bucle P. Hay varias maneras de explicar esto; una de las más comunes/efectivas es añadir una «salida mínima» a la salida del bucle de control. Otra estrategia efectiva es la de conectar en cascada a controladores de velocidad bien ajustados a cada lado de la unidad.