Solución de problemas

Solución a fallas totales

Hay algunas cosas que pueden causar una falla total en tu robot. La lista inferior cubre algunos de estos errores comunes.

  • Mi robot no se mueve

    • ¿En verdad esta dando energía a sus motores?

    • Si a usted le esta apareciendo el mensaje MalformedSplineException en la driver station, vaya a la sección MalformedSplineException

    • ¿Su trayectoria es muy corta o está en unidades equivocadas?

  • Mi robot gira alrededor para conducir la trayectoria en la otra dirección

  • Mi robot simplemente conduce en línea recta aunque debería girar.

    • ¿Su giróscopo está configurado correctamente y devuelve buenos datos?

    • ¿Está pasando su giróscopo rumbo a su objeto de odometría con las unidades correctas?

    • ¿Es correcto el ancho de su ruta? ¿Está en las unidades correctas?

  • Apareció el mensaje MalformedSplineException impreso en la driver station y el robot no se mueve

  • Mi robot conduce demasiado lejos.

    • ¿Están configuradas correctamente las conversiones de unidades de codificador?

    • ¿Están tus enconders conectados?

  • Mi robot generalmente hace lo correcto, pero es un poco inexacto.

    • Diríjase a la siguiente sección

Solución de problemas de bajo rendimiento

Nota

Esta sección se ocupa principalmente de la resolución de problemas de rendimiento de seguimiento de trayectoria deficiente, como un metro de error, no fallas catastróficas como errores de compilación, robots que giran y van en la dirección incorrecta o MalformedSplineExceptions.

Nota

Esta sección está diseñada para robots de accionamiento diferencial, pero la mayoría de las ideas se pueden adaptar para desvío o mecanum.

El rendimiento deficiente del seguimiento de la trayectoria puede ser difícil de solucionar. Aunque el generador de trayectoria y el seguidor están pensados ​​para ser fáciles de usar y con un rendimiento inmediato, hay situaciones en las que su robot no termina donde debería. El generador de trayectoria y los seguidores tienen muchas perillas para sintonizar y muchas partes móviles, por lo que puede ser difícil saber por dónde empezar, especialmente porque es difícil localizar la fuente de los problemas de trayectoria a partir del comportamiento general del robot.

Debido a que puede ser muy difícil de localizar la capa de el generador de trayectoria y los siguientes que se están portando mal, se recomienda un enfoque sistemático capa por capa para un rendimiento de seguimiento deficiente en general (por ejemplo, el robot se aleja unos pocos pies o más de veinte grados ). Los pasos siguientes se enumeran en el orden en el que debe realizarlos; Es importante seguir este orden para poder aislar los efectos de los diferentes pasos entre sí.

Nota

The below examples put diagnostic values onto NetworkTables. The easiest way to graph these values is to use Shuffleboard’s graphing capabilities.

Verifique la odometría

Si su odometría es mala, entonces su controlador Ramsete puede comportarse mal, porque modifica las velocidades objetivo de su robot en función de dónde cree que la odometría está el robot.

Nota

Sending your robot pose and trajectory to field2d can help verify that your robot is driving correctly relative to the robot trajectory.

  1. Configure su código para que registre la posición del robot cada vez que se actualice la odometría.

NetworkTableEntry m_xEntry = NetworkTableInstance.getDefault().getTable("troubleshooting").getEntry("X");
NetworkTableEntry m_yEntry = NetworkTableInstance.getDefault().getTable("troubleshooting").getEntry("Y");

@Override
public void periodic() {
    // Update the odometry in the periodic block
    m_odometry.update(Rotation2d.fromDegrees(getHeading()), m_leftEncoder.getDistance(),
        m_rightEncoder.getDistance());

    var translation = m_odometry.getPoseMeters().getTranslation();
    m_xEntry.setNumber(translation.getX());
    m_yEntry.setNumber(translation.getY());
}
NetworkTableEntry m_xEntry = nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting")->GetEntry("X");
NetworkTableEntry m_yEntry = nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting")->GetEntry("Y");

void DriveSubsystem::Periodic() {
    // Implementation of subsystem periodic method goes here.
    m_odometry.Update(frc::Rotation2d(units::degree_t(GetHeading())),
                        units::meter_t(m_leftEncoder.GetDistance()),
                        units::meter_t(m_rightEncoder.GetDistance()));

    auto translation = m_odometry.GetPose().Translation();
    m_xEntry.SetDouble(translation.X().value());
    m_yEntry.SetDouble(translation.Y().value());
}
  1. Coloque una cinta métrica paralela a su robot y empuje su robot aproximadamente un metro a lo largo de la cinta métrica. Coloque una cinta métrica a lo largo del eje Y y comience de nuevo, empujando su robot un metro a lo largo del eje X y un metro a lo largo del eje Y en un arco aproximado.

  2. Compare X and Y reported by the robot to actual X and Y. If X is off by more than 5 centimeters in the first test then you should check that you measured your wheel diameter correctly, and that your wheels are not worn down. If the second test is off by more than 5 centimeters in either X or Y then your track width (distance from the center of the left wheel to the center of the right wheel) may be incorrect; if you’re sure that you measured the track width correctly with a tape measure then your robot’s wheels may be slipping in a way that is not accounted for by track width, so try increasing the track width number or measuring it programmatically.

Verificar Feedforward

Si sus feedforwards son malos, entonces los controladores P para cada lado del robot no seguirán tan bien, y su DifferentialDriveVoltageConstraint no limitará la aceleración de su robot con precisión. En general, queremos apagar los controladores P de la rueda para poder aislar y probar los feedforwards.

  1. Primero, debemos configurar la desactivación del controlador P para cada rueda. Poner la ganancia P a 0 para cada controlador. En el ejemplo de «Comando Ramsete», pondrías «kPDriveVel» a 0:

123            new PIDController(DriveConstants.kPDriveVel, 0, 0),
124            new PIDController(DriveConstants.kPDriveVel, 0, 0),
81      frc::PIDController{DriveConstants::kPDriveVel, 0, 0},
82      frc::PIDController{DriveConstants::kPDriveVel, 0, 0},
  1. Next, we want to disable the Ramsete controller to make it easier to isolate our problematic behavior. To do so, simply call setEnabled(false) on the RamseteController passed into your RamseteCommand:

RamseteController m_disabledRamsete = new RamseteController();
m_disabledRamsete.setEnabled(false);

// Be sure to pass your new disabledRamsete variable
RamseteCommand ramseteCommand = new RamseteCommand(
    exampleTrajectory,
    m_robotDrive::getPose,
    m_disabledRamsete,
    ...
);
frc::RamseteController m_disabledRamsete;
m_disabledRamsete.SetEnabled(false);

// Be sure to pass your new disabledRamsete variable
frc2::RamseteCommand ramseteCommand(
  exampleTrajectory,
  [this]() { return m_drive.GetPose(); },
  m_disabledRamsete,
  ...
);
  1. Finalmente, necesitamos registrar la velocidad de la rueda deseada y la velocidad real de la rueda (deberías poner las velocidades real y deseada en el mismo gráfico si estás usando Shuffleboard, o si tu software de gráficos tiene esa capacidad):

var table = NetworkTableInstance.getDefault().getTable("troubleshooting");
var leftReference = table.getEntry("left_reference");
var leftMeasurement = table.getEntry("left_measurement");
var rightReference = table.getEntry("right_reference");
var rightMeasurement = table.getEntry("right_measurement");

var leftController = new PIDController(kPDriveVel, 0, 0);
var rightController = new PIDController(kPDriveVel, 0, 0);
RamseteCommand ramseteCommand = new RamseteCommand(
    exampleTrajectory,
    m_robotDrive::getPose,
    disabledRamsete, // Pass in disabledRamsete here
    new SimpleMotorFeedforward(ksVolts, kvVoltSecondsPerMeter, kaVoltSecondsSquaredPerMeter),
    kDriveKinematics,
    m_robotDrive::getWheelSpeeds,
    leftController,
    rightController,
    // RamseteCommand passes volts to the callback
    (leftVolts, rightVolts) -> {
        m_robotDrive.tankDriveVolts(leftVolts, rightVolts);

        leftMeasurement.setNumber(m_robotDrive.getWheelSpeeds().leftMetersPerSecond);
        leftReference.setNumber(leftController.getSetpoint());

        rightMeasurement.setNumber(m_robotDrive.getWheelSpeeds().rightMetersPerSecond);
        rightReference.setNumber(rightController.getSetpoint());
    },
    m_robotDrive
);
auto table =
    nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting");
auto leftRef = table->GetEntry("left_reference");
auto leftMeas = table->GetEntry("left_measurement");
auto rightRef = table->GetEntry("right_reference");
auto rightMeas = table->GetEntry("right_measurement");

frc::PIDController leftController(DriveConstants::kPDriveVel, 0, 0);
frc::PIDController rightController(DriveConstants::kPDriveVel, 0, 0);
frc2::RamseteCommand ramseteCommand(
    exampleTrajectory, [this]() { return m_drive.GetPose(); },
    frc::RamseteController(AutoConstants::kRamseteB,
                            AutoConstants::kRamseteZeta),
    frc::SimpleMotorFeedforward<units::meters>(
        DriveConstants::ks, DriveConstants::kv, DriveConstants::ka),
    DriveConstants::kDriveKinematics,
    [this] { return m_drive.GetWheelSpeeds(); }, leftController,
    rightController,
    [=](auto left, auto right) {
        auto leftReference = leftRef;
        auto leftMeasurement = leftMeas;
        auto rightReference = rightRef;
        auto rightMeasurement = rightMeas;

        m_drive.TankDriveVolts(left, right);

        leftMeasurement.SetDouble(m_drive.GetWheelSpeeds().left.value());
        leftReference.SetDouble(leftController.GetSetpoint());

        rightMeasurement.SetDouble(m_drive.GetWheelSpeeds().right.value());
        rightReference.SetDouble(rightController.GetSetpoint());
    },
    {&m_drive});
  1. Ejecute el robot en una variedad de trayectorias (línea curva y recta), y compruebe si la velocidad real sigue la velocidad deseada mirando los gráficos de las NetworkTables.

  2. If the desired and actual are off by a lot then you should check if the wheel diameter and encoderEPR you used for system identification were correct. If you’ve verified that your units and conversions are correct, then you should try recharacterizing on the same floor that you’re testing on to see if you can get better data.

Verificación de la Ganancia P

Si has completado el paso anterior y el problema ha desaparecido, entonces es probable que tu problema se encuentre en uno de los siguientes pasos. En este paso vamos a verificar que los controladores P de tu rueda están bien ajustados. Si estás usando Java entonces queremos que apague Ramsete para que podamos ver nuestros controladores PF por su cuenta.

  1. Debes reutilizar todo el código del paso anterior que registra la velocidad actual frente a la deseada (y el código que desactiva Ramsete, si usas Java), excepto que la ganancia P debe volver a su valor anterior distinto de cero.

  2. Conduzca de nuevo el robot en distintas trayectorias, y revise que las gráficas reales se vean bien en comparación a las gráficas deseadas.

  3. Si las gráficas no se ven bien (ej. la velocidad al momento es muy diferente a la deseada) entonces debería intentar afinar su ganancia P y re ejecutar sus trayectorias de prueba.

Compruebe las restricciones

Nota

Asegúrese de que su ganancia P sea distinta de cero en este paso y que aún tenga el código de registro añadido en los pasos anteriores. Si estás usando Java entonces deberías quitar el código para desactivar Ramsete.

Si su problema de exactitud persiste a través de todos los pasos anteriores, entonces podría tener un problema con sus limitaciones. A continuación hay una lista de síntomas que las diferentes restricciones disponibles exhibirán cuando no estén bien afinadas.

¡Prueba una restricción a la vez! Elimina las otras restricciones, ajusta la que te queda y repite el proceso para cada restricción que quieras usar. La siguiente lista de comprobación supone que sólo se utiliza una restricción a la vez.

  • DifferentialDriveVoltageConstraint:

    • Si tu robot acelera muy lentamente, entonces es posible que el voltaje máximo para esta restricción sea demasiado bajo.

    • If your robot doesn’t reach the end of the path then your system identification data may problematic.

  • DifferentialDriveKinematicsConstraint:

    • Si tu robot termina en el rumbo equivocado, es posible que la velocidad máxima del lado de la transmisión sea demasiado baja, o que sea demasiado alta. La única manera de saberlo es ajustando la velocidad máxima y ver qué pasa.

  • CentripetalAccelerationConstraint:

    • Si su robot termina en la dirección equivocada, entonces este podría ser el culpable. Si su robot no parece girar lo suficiente, entonces debe aumentar la aceleración centrípeta máxima, pero si parece girar en giros cerrados demasiado rápido, entonces debe disminuir la aceleración centrípeta máxima.

Comprobación de los puntos de ruta de la trayectoria

Es posible que su trayectoria en sí no sea muy manejable. Intente mover las coordenadas (y rumbos en las coordenadas, si corresponde) para reducir los giros bruscos.