Swerve Drive Kinematiği
`` SwerveDriveKinematics`` sınıfı, bir `` ChassisSpeeds`` nesnesi ile bir swerve sürücü robotunun her bir dönüş modülü için hızları ve açıları içeren birkaç `` SwerveModuleState`` nesnesi arasında dönüşüm sağlayan kullanışlı bir araçtır.
Not
Swerve drive kinematics uses a common coordinate system. You may wish to reference the Coordinate System section for details.
Swerve modülü durum sınıfı
SwerveModuleState
sınıfı, bir swerve sürücüsünün tekil modülünün hızı ve açısı hakkında bilgi içerir. Bir SwerveModuleState
in constructor’ı iki argüman alır: modüldeki çarkın hızı ve modülün açısı.
Not
In Java / Python, the velocity of the wheel must be in meters per second. In C++, the units library can be used to provide the velocity using any linear velocity unit.
Not
0 açı, öne bakan modüllere karşılık gelir.
Kinematik Nesnesinin Oluşturulması
SwerveDriveKinematics
sınıfı, değişken sayıda yapıcı argümanı kabul eder, her argüman robot merkezine göre bir swerve modülünün konumu olur (Translation2d
olarak. Constructor argümanlarının sayısı, swerve modüllerinin sayısına karşılık gelir.
Not
Swerve sürücüsünün 2 veya daha fazla modülü olmalıdır.
Not
C++ ‘da, sınıf modül sayısına göre şablonlanır. Bu nedenle, bir sınıfın üye değişkeni olarak bir SwerveDriveKinematics
nesnesi oluştururken, modül sayısı bir şablon argümanı olarak iletilmelidir. Örneğin, dört modüllü tipik bir swerve sürücü için kinematik nesnesi şu şekilde oluşturulmalıdır: frc:: SwerveDriveKinematics<4> m_kinematics{...}
.
Modüllerin konumları, robotun merkezine göre olmalıdır. Pozitif x değerleri robotun önüne doğru hareket etmeyi temsil ederken, pozitif y değerleri robotun soluna doğru hareket etmeyi temsil eder.
// Locations for the swerve drive modules relative to the robot center.
Translation2d m_frontLeftLocation = new Translation2d(0.381, 0.381);
Translation2d m_frontRightLocation = new Translation2d(0.381, -0.381);
Translation2d m_backLeftLocation = new Translation2d(-0.381, 0.381);
Translation2d m_backRightLocation = new Translation2d(-0.381, -0.381);
// Creating my kinematics object using the module locations
SwerveDriveKinematics m_kinematics = new SwerveDriveKinematics(
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation
);
// Locations for the swerve drive modules relative to the robot center.
frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m};
frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m};
frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m};
frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
// Creating my kinematics object using the module locations.
frc::SwerveDriveKinematics<4> m_kinematics{
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
m_backRightLocation};
# Python requires using the right class for the number of modules you have
from wpimath.geometry import Translation2d
from wpimath.kinematics import SwerveDrive4Kinematics
# Locations for the swerve drive modules relative to the robot center.
frontLeftLocation = Translation2d(0.381, 0.381)
frontRightLocation = Translation2d(0.381, -0.381)
backLeftLocation = Translation2d(-0.381, 0.381)
backRightLocation = Translation2d(-0.381, -0.381)
# Creating my kinematics object using the module locations
self.kinematics = SwerveDrive4Kinematics(
frontLeftLocation, frontRightLocation, backLeftLocation, backRightLocation
)
Şase hızlarını modül durumlarına dönüştürme
The toSwerveModuleStates(ChassisSpeeds speeds)
(Java / Python) / ToSwerveModuleStates(ChassisSpeeds speeds)
(C++) method should be used to convert a ChassisSpeeds
object to a an array of SwerveModuleState
objects. This is useful in situations where you have to convert a forward velocity, sideways velocity, and an angular velocity into individual module states.
Bu yöntemle döndürülen dizideki öğeler, kinematik nesnesinin oluşturulduğu sırayla aynıdır. Örneğin, kinematik nesnesi ön sol modül konumu, ön sağ modül konumu, arka sol modül konumu ve bu sırayla sağ arka modül konumu ile oluşturulmuşsa, dizideki öğeler ön sol modül durumu, ön bu sırayla sağ modül durumu, arka sol modül durumu ve arka sağ modül durumu olacaktır.
// Example chassis speeds: 1 meter per second forward, 3 meters
// per second to the left, and rotation at 1.5 radians per second
// counterclockwise.
ChassisSpeeds speeds = new ChassisSpeeds(1.0, 3.0, 1.5);
// Convert to module states
SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(speeds);
// Front left module state
SwerveModuleState frontLeft = moduleStates[0];
// Front right module state
SwerveModuleState frontRight = moduleStates[1];
// Back left module state
SwerveModuleState backLeft = moduleStates[2];
// Back right module state
SwerveModuleState backRight = moduleStates[3];
// Example chassis speeds: 1 meter per second forward, 3 meters
// per second to the left, and rotation at 1.5 radians per second
// counterclockwise.
frc::ChassisSpeeds speeds{1_mps, 3_mps, 1.5_rad_per_s};
// Convert to module states. Here, we can use C++17's structured
// bindings feature to automatically split up the array into its
// individual SwerveModuleState components.
auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(speeds);
from wpimath.kinematics import ChassisSpeeds
# Example chassis speeds: 1 meter per second forward, 3 meters
# per second to the left, and rotation at 1.5 radians per second
# counterclockwise.
speeds = ChassisSpeeds(1.0, 3.0, 1.5)
# Convert to module states
frontLeft, frontRight, backLeft, backRight = self.kinematics.toSwerveModuleStates(speeds)
Modül açısı optimizasyonu
Başlıktaki değişikliği en aza indirmek için. SwerveModuleState
sınıfı, belirli bir SwerveModuleState
in hız ve açı ayar noktasını “optimize etmek” için kullanılan statik bir``optimize()`` (Java) / Optimize()
(C++) yöntemini içerir. Örneğin, belirli bir modülün ters kinematikten açısal set noktası 90 derece ise, ancak mevcut açınız -89 derecedir, bu yöntem modülün ayar noktasının hızını otomatik olarak geçersiz kılar ve modülün gitmesi gereken mesafeyi azaltmak için açısal ayar noktasını -90 derece yapar.
Bu yöntem iki parametre alır: istenen durum (genellikle toSwerveModuleStates
metodundan) ve geçerli açı. Geri bildirim kontrol döngünüzde ayar noktası olarak kullanabileceğiniz yeni optimize edilmiş durumu döndürecektir.
var frontLeftOptimized = SwerveModuleState.optimize(frontLeft,
new Rotation2d(m_turningEncoder.getDistance()));
auto flOptimized = frc::SwerveModuleState::Optimize(fl,
units::radian_t(m_turningEncoder.GetDistance()));
from wpimath.kinematics import SwerveModuleState
from wpimath.geometry import Rotation2d
frontLeftOptimized = SwerveModuleState.optimize(frontLeft,
Rotation2d(self.m_turningEncoder.getDistance()))
Field-oriented / Saha-odaklı sürüş
Recall bir ChassisSpeeds
nesnesinin istenen saha odaklı hızlardan oluşturulabileceğini hatırlayın. Bu özellik, istenen saha odaklı hızlardan modül durumlarını elde etmek için kullanılabilir.
// The desired field relative speed here is 2 meters per second
// toward the opponent's alliance station wall, and 2 meters per
// second toward the left field boundary. The desired rotation
// is a quarter of a rotation per second counterclockwise. The current
// robot angle is 45 degrees.
ChassisSpeeds speeds = ChassisSpeeds.fromFieldRelativeSpeeds(
2.0, 2.0, Math.PI / 2.0, Rotation2d.fromDegrees(45.0));
// Now use this in our kinematics
SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(speeds);
// The desired field relative speed here is 2 meters per second
// toward the opponent's alliance station wall, and 2 meters per
// second toward the left field boundary. The desired rotation
// is a quarter of a rotation per second counterclockwise. The current
// robot angle is 45 degrees.
frc::ChassisSpeeds speeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds(
2_mps, 2_mps, units::radians_per_second_t(std::numbers::pi / 2.0), Rotation2d(45_deg));
// Now use this in our kinematics
auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(speeds);
from wpimath.kinematics import ChassisSpeeds
import math
from wpimath.geometry import Rotation2d
# The desired field relative speed here is 2 meters per second
# toward the opponent's alliance station wall, and 2 meters per
# second toward the left field boundary. The desired rotation
# is a quarter of a rotation per second counterclockwise. The current
# robot angle is 45 degrees.
speeds = ChassisSpeeds.fromFieldRelativeSpeeds(
2.0, 2.0, math.pi / 2.0, Rotation2d.fromDegrees(45.0))
# Now use this in our kinematics
self.moduleStates = self.kinematics.toSwerveModuleStates(speeds)
Özel döndürme merkezlerini kullanma
Bazen, belirli kaçamak manevralar için belirli bir köşenin etrafında dönmek istenebilir. Bu tür davranış WPILib sınıfları tarafından da desteklenir. Aynı `` ToSwerveModuleStates ()`` yöntemi, dönüş merkezi için ikinci bir parametre kabul eder (`` Translation2d`` olarak). Tıpkı tekerlek konumlarında olduğu gibi, dönme merkezini temsil eden `` Translation2d`` de robot merkezine göre olmalıdır.
Not
Tüm robotlar sabit bir çerçeve olduğundan, ChassisSpeeds
nesnesinden sağlanan vx
ve vy
hızları, robotun tamamı için geçerli olmaya devam edecektir. Bununla birlikte, ChassisSpeeds
nesnesindeki omega
, dönüş merkezinden ölçülecektir.
Örneğin, belirli bir modülde dönme merkezi ayarlanabilir ve sağlanan ChassisSpeeds
nesnesinin bir vx
ve vy
si sıfır ve sıfır olmayan bir omega
ise robot, söz konusu dönüş modülü etrafında dönüyormuş gibi görünecektir.
Modül durumlarını şase hızlarına dönüştürme
One can also use the kinematics object to convert an array of SwerveModuleState
objects to a singular ChassisSpeeds
object. The toChassisSpeeds(SwerveModuleState... states)
(Java / Python) / ToChassisSpeeds(SwerveModuleState... states)
(C++) method can be used to achieve this.
// Example module states
var frontLeftState = new SwerveModuleState(23.43, Rotation2d.fromDegrees(-140.19));
var frontRightState = new SwerveModuleState(23.43, Rotation2d.fromDegrees(-39.81));
var backLeftState = new SwerveModuleState(54.08, Rotation2d.fromDegrees(-109.44));
var backRightState = new SwerveModuleState(54.08, Rotation2d.fromDegrees(-70.56));
// Convert to chassis speeds
ChassisSpeeds chassisSpeeds = kinematics.toChassisSpeeds(
frontLeftState, frontRightState, backLeftState, backRightState);
// Getting individual speeds
double forward = chassisSpeeds.vxMetersPerSecond;
double sideways = chassisSpeeds.vyMetersPerSecond;
double angular = chassisSpeeds.omegaRadiansPerSecond;
// Example module States
frc::SwerveModuleState frontLeftState{23.43_mps, Rotation2d(-140.19_deg)};
frc::SwerveModuleState frontRightState{23.43_mps, Rotation2d(-39.81_deg)};
frc::SwerveModuleState backLeftState{54.08_mps, Rotation2d(-109.44_deg)};
frc::SwerveModuleState backRightState{54.08_mps, Rotation2d(-70.56_deg)};
// Convert to chassis speeds. Here, we can use C++17's structured bindings
// feature to automatically break up the ChassisSpeeds struct into its
// three components.
auto [forward, sideways, angular] = kinematics.ToChassisSpeeds(
frontLeftState, frontRightState, backLeftState, backRightState);
from wpimath.kinematics import SwerveModuleState
from wpimath.geometry import Rotation2d
# Example module states
frontLeftState = SwerveModuleState(23.43, Rotation2d.fromDegrees(-140.19))
frontRightState = SwerveModuleState(23.43, Rotation2d.fromDegrees(-39.81))
backLeftState = SwerveModuleState(54.08, Rotation2d.fromDegrees(-109.44))
backRightState = SwerveModuleState(54.08, Rotation2d.fromDegrees(-70.56))
# Convert to chassis speeds
chassisSpeeds = self.kinematics.toChassisSpeeds(
frontLeftState, frontRightState, backLeftState, backRightState)
# Getting individual speeds
forward = chassisSpeeds.vx
sideways = chassisSpeeds.vy
angular = chassisSpeeds.omega
Module state visualization with AdvantageScope
By recording a set of swerve module states using NetworkTables or WPILib data logs, AdvantageScope can be used to visualize the state of a swerve drive. The code below shows how a set of SwerveModuleState
objects can be published to NetworkTables.
public class Example {
private final StructArrayPublisher<SwerveModuleState> publisher;
public Example() {
// Start publishing an array of module states with the "/SwerveStates" key
publisher = NetworkTableInstance.getDefault()
.getStructArrayTopic("/SwerveStates", SwerveModuleState.struct).publish();
}
public void periodic() {
// Periodically send a set of module states
publisher.set(new SwerveModuleState[] {
frontLeftState,
frontRightState,
backLeftState,
backRightState
});
}
}
class Example {
nt::StructArrayPublisher<frc::SwerveModuleState> publisher
public:
Example() {
// Start publishing an array of module states with the "/SwerveStates" key
publisher = nt::NetworkTableInstance::GetDefault()
.GetStructArrayTopic<frc::SwerveModuleState>("/SwerveStates").Publish();
}
void Periodic() {
// Periodically send a set of module states
swervePublisher.Set(
std::vector{
frontLeftState,
frontRightState,
backLeftState,
backRightState
}
);
}
};
import ntcore
from wpimath.kinematics import SwerveModuleState
# get the default instance of NetworkTables
nt = ntcore.NetworkTableInstance.getDefault()
# Start publishing an array of module states with the "/SwerveStates" key
topic = nt.getStructArrayTopic("/SwerveStates", SwerveModuleState)
self.pub = topic.publish()
def periodic(self):
# Periodically send a set of module states
self.pub.set([frontLeftState,frontRightState,backLeftState,backRightState])
See the documentation for the swerve tab for more details on visualizing this data using AdvantageScope.