Odometría de mando diferencial

Un usuario puede utilizar las clases de cinemática de accionamiento diferencial para realizar: ref:odometría <docs/software/kinematics-and-odometry/intro-and-chassis-speeds:What is odometry?>. WPILib contiene una clase DifferentialDriveOdometry que se puede utilizar para rastrear la posición de un robot de accionamiento diferencial en el campo.

Nota

Debido a que este método solo usa codificadores y un giróscopo, la estimación de la posición del robot en el campo variará con el tiempo, especialmente cuando tu robot entre en contacto con otros robots durante el juego. Sin embargo, la odometría suele ser muy precisa durante el período autónomo.

Creación del objeto de odometría

The DifferentialDriveOdometry class constructor requires three mandatory arguments and one optional argument. The mandatory arguments are:

  • The angle reported by your gyroscope (as a Rotation2d)

  • The initial left and right encoder readings. In Java / Python, these are a number that represents the distance traveled by each side in meters. In C++, the units library must be used to represent your wheel positions.

The optional argument is the starting pose of your robot on the field (as a Pose2d). By default, the robot will start at x = 0, y = 0, theta = 0.

Nota

0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent’s alliance station. As your robot turns to the left, your gyroscope angle should increase. The Gyro interface supplies getRotation2d/GetRotation2d that you can use for this purpose. See Coordinate System for more information about the coordinate system.

// Creating my odometry object. Here,
// our starting pose is 5 meters along the long end of the field and in the
// center of the field along the short end, facing forward.
DifferentialDriveOdometry m_odometry = new DifferentialDriveOdometry(
  m_gyro.getRotation2d(),
  m_leftEncoder.getDistance(), m_rightEncoder.getDistance(),
  new Pose2d(5.0, 13.5, new Rotation2d()));
// Creating my odometry object. Here,
// our starting pose is 5 meters along the long end of the field and in the
// center of the field along the short end, facing forward.
frc::DifferentialDriveOdometry m_odometry{
  m_gyro.GetRotation2d(),
  units::meter_t{m_leftEncoder.GetDistance()},
  units::meter_t{m_rightEncoder.GetDistance()},
  frc::Pose2d{5_m, 13.5_m, 0_rad}};
from wpimath.kinematics import DifferentialDriveOdometry
from wpimath.geometry import Pose2d
from wpimath.geometry import Rotation2d

# Creating my odometry object. Here,
# our starting pose is 5 meters along the long end of the field and in the
# center of the field along the short end, facing forward.
m_odometry = DifferentialDriveOdometry(
  m_gyro.getRotation2d(),
  m_leftEncoder.getDistance(), m_rightEncoder.getDistance(),
  Pose2d(5.0, 13.5, Rotation2d()))

Actualización de la postura del robot

El método de actualización se puede utilizar para actualizar la posición del robot en el campo. Este método debe ser llamado periódicamente, preferiblemente en el método periodic() de un Subsistema. El método de actualización devuelve la nueva pose actualizada del robot. Este método tiene en cuenta el ángulo de giro del robot, junto con la distancia del codificador izquierdo y la distancia del codificador derecho.

Nota

If the robot is moving forward in a straight line, both distances (left and right) must be increasing positively – the rate of change must be positive.

@Override
public void periodic() {
  // Get the rotation of the robot from the gyro.
  var gyroAngle = m_gyro.getRotation2d();

  // Update the pose
  m_pose = m_odometry.update(gyroAngle,
    m_leftEncoder.getDistance(),
    m_rightEncoder.getDistance());
}
void Periodic() override {
  // Get the rotation of the robot from the gyro.
  frc::Rotation2d gyroAngle = m_gyro.GetRotation2d();

  // Update the pose
  m_pose = m_odometry.Update(gyroAngle,
    units::meter_t{m_leftEncoder.GetDistance()},
    units::meter_t{m_rightEncoder.GetDistance()});
}
def periodic(self):
  # Get the rotation of the robot from the gyro.
  gyroAngle = m_gyro.getRotation2d()

  # Update the pose
  m_pose = m_odometry.update(gyroAngle,
    m_leftEncoder.getDistance(),
    m_rightEncoder.getDistance())

Restablecer la postura del robot

The robot pose can be reset via the resetPosition method. This method accepts four arguments: the current gyro angle, the left and right wheel positions, and the new field-relative pose.

Importante

If at any time, you decide to reset your gyroscope or encoders, the resetPosition method MUST be called with the new gyro angle and wheel distances.

Nota

A full example of a differential drive robot with odometry is available here: C++ / Java / Python

In addition, the GetPose (C++) / getPoseMeters (Java / Python) methods can be used to retrieve the current robot pose without an update.