CTRE Phoenix 6 C++ 25.0.0-beta-4
|
Simplified swerve drive simulation class. More...
#include <ctre/phoenix6/swerve/SimSwerveDrivetrain.hpp>
Classes | |
class | SimSwerveModule |
Public Member Functions | |
template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >> | |
SimSwerveDrivetrain (std::vector< Translation2d > wheelLocations, sim::Pigeon2SimState &pigeonSim, ModuleConstants const &... moduleConstants) | |
void | Update (units::second_t dt, units::volt_t supplyVoltage, std::vector< std::unique_ptr< SwerveModule > > const &modulesToApply) |
Static Protected Member Functions | |
static units::volt_t | AddFriction (units::volt_t motorVoltage, units::volt_t frictionVoltage) |
Applies the effects of friction to dampen the motor voltage. | |
Protected Attributes | |
sim::Pigeon2SimState & | _pigeonSim |
std::vector< SimSwerveModule > | _modules |
impl::SwerveDriveKinematics | _kinem |
Rotation2d | _lastAngle {} |
Simplified swerve drive simulation class.
This class assumes that the swerve drive is perfect, meaning that there is no scrub and the wheels do not slip.
In addition, it assumes the inertia of the robot is governed only by the inertia of the steer module and the individual drive wheels. Robot-wide inertia is not accounted for, and neither is translational vs rotational inertia of the robot.
These assumptions provide a simplified example that can demonstrate the behavior of a swerve drive in simulation. Users are encouraged to expand this model for their own use.
|
inline |
|
inlinestaticprotected |
Applies the effects of friction to dampen the motor voltage.
motorVoltage | Voltage output by the motor |
frictionVoltage | Voltage required to overcome friction |
|
inline |
|
protected |
|
protected |
|
protected |
|
protected |