phoenix6.swerve.utility.wheel_force_calculator¶
Module Contents¶
- class phoenix6.swerve.utility.wheel_force_calculator.WheelForceCalculator(module_locations: list[phoenix6.swerve.utility.geometry.Translation2d], mass_kg: float, moi_kg_m_sq: float)¶
Calculates wheel force feedforwards for a SwerveDrivetrain. Wheel force feedforwards can be used to improve accuracy of path following in regions of acceleration.
Many path planning libraries (such as PathPlanner and Choreo) already provide per-module force feedforwards, which should be preferred over this class.
Constructs a new wheel force feedforward calculator for the given drivetrain characteristics.
- Parameters:
module_locations (list[Translation2d]) – The drivetrain swerve module locations
mass_kg (float) – The mass of the robot in kg
moi_kg_m_sq (float) – The moment of inertia of the robot in kg m^2
- class Feedforwards(num_modules: int)¶
Wheel force feedforwards to apply to a swerve drivetrain.
Constructs a new set of wheel force feedforwards.
- Parameters:
num_modules (int) – The number of swerve modules
- x_newtons¶
The X component of the forces in Newtons.
- y_newtons¶
The Y component of the forces in Newtons.
- calculate(ax: float, ay: float, alpha: float, center_of_rotation: phoenix6.swerve.utility.geometry.Translation2d = Translation2d()) Feedforwards¶
Calculates wheel force feedforwards for the desired robot acceleration. This can be used with either robot-centric or field-centric accelerations; the returned force feedforwards will match in being robot-/field-centric.
- Parameters:
ax (float) – Acceleration in the X direction (forward) in m/s^2
ay (float) – Acceleration in the Y direction (left) in m/s^2
alpha (float) – Angular acceleration in rad/s^2
center_of_rotation (Translation2d) – Center of rotation
- Returns:
Wheel force feedforwards to apply
- Return type:
- calculate_from_speeds(dt: float, prev: phoenix6.swerve.utility.kinematics.ChassisSpeeds, current: phoenix6.swerve.utility.kinematics.ChassisSpeeds, center_of_rotation: phoenix6.swerve.utility.geometry.Translation2d = Translation2d()) Feedforwards¶
Calculates wheel force feedforwards for the desired change in speeds. This can be used with either robot-centric or field-centric speeds; the returned force feedforwards will match in being robot-/field-centric.
- Parameters:
dt (float) – The change in time between the path setpoints
prev (ChassisSpeeds) – The previous ChassisSpeeds setpoint of the path
current (ChassisSpeeds) – The new ChassisSpeeds setpoint of the path
center_of_rotation (Translation2d) – Center of rotation
- Returns:
Wheel force feedforwards to apply
- Return type: