librmb 1.0
Rambunction 4330 Utility Library
Loading...
Searching...
No Matches
rmb::SwerveDrive< NumModules > Class Template Reference

#include <rmb/drive/SwerveDrive.h>

Inheritance diagram for rmb::SwerveDrive< NumModules >:
rmb::BaseDrive

Public Member Functions

 SwerveDrive (const SwerveDrive &)=delete
 
 SwerveDrive (SwerveDrive &&)=delete
 
 SwerveDrive (std::array< SwerveModule, NumModules > modules, std::shared_ptr< const rmb::Gyro > gyro, frc::HolonomicDriveController holonomicController, std::string visionTable, units::meters_per_second_t maxModuleSpeed, const frc::Pose2d &initialPose=frc::Pose2d())
 
 SwerveDrive (std::array< SwerveModule, NumModules > modules, std::shared_ptr< const rmb::Gyro > gyro, frc::HolonomicDriveController holonomicController, units::meters_per_second_t maxModuleSpeed, const frc::Pose2d &initialPose=frc::Pose2d())
 
void driveCartesian (double xSpeed, double ySpeed, double zRotation, bool fieldOriented)
 
void drivePolar (double speed, const frc::Rotation2d &angle, double zRotation, bool fieldOriented)
 
void driveModulePowers (std::array< SwerveModulePower, NumModules > powers)
 
void driveModuleStates (std::array< frc::SwerveModuleState, NumModules > states)
 
std::array< frc::SwerveModuleState, NumModulesgetModuleStates () const
 
std::array< frc::SwerveModulePosition, NumModulesgetModulePositions () const
 
const std::array< rmb::SwerveModule, NumModules > & getModules () const
 
void driveChassisSpeeds (frc::ChassisSpeeds chassisSpeeds) override
 
frc::ChassisSpeeds getChassisSpeeds () const override
 
frc::Pose2d getPose () const override
 
std::array< frc::SwerveModuleState, NumModulesgetTargetModuleStates () const
 
frc::Pose2d updatePose () override
 
void resetPose (const frc::Pose2d &pose=frc::Pose2d()) override
 
void addVisionMeasurments (const frc::Pose2d &poseEstimate, units::second_t time) override
 
void setVisionSTDevs (wpi::array< double, 3 > standardDevs) override
 
bool isHolonomic () const override
 
frc2::CommandPtr followWPILibTrajectory (frc::Trajectory trajectory, std::initializer_list< frc2::Subsystem * > driveRequirements) override
 
frc2::CommandPtr followPPPath (std::shared_ptr< pathplanner::PathPlannerPath > path, std::initializer_list< frc2::Subsystem * > driveRequirements) override
 
frc2::CommandPtr FollowGeneratedPPPath (frc::Pose2d targetPose, pathplanner::PathConstraints constraints, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
void updateNTDebugInfo (bool openLoopVelocity=false)
 
void stop ()
 
- Public Member Functions inherited from rmb::BaseDrive
virtual frc2::CommandPtr followWPILibTrajectoryGroup (std::vector< frc::Trajectory > trajectoryGroup, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
virtual frc2::CommandPtr followPPPathWithEvents (pathplanner::PathPlannerPath path, std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
virtual frc2::CommandPtr fullPPAuto (pathplanner::PathPlannerPath path, std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
virtual frc2::CommandPtr fullPPAuto (std::vector< pathplanner::PathPlannerTrajectory > trajectoryGroup, std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap, std::initializer_list< frc2::Subsystem * > driveRequirements)
 

Additional Inherited Members

- Protected Member Functions inherited from rmb::BaseDrive
 BaseDrive (std::string visionTable)
 
- Protected Attributes inherited from rmb::BaseDrive
nt::DoubleArraySubscriber poseSubscriber
 
nt::DoubleArraySubscriber stdDevSubscriber
 
NT_Listener poseListener
 
NT_Listener stdDevListener
 

Detailed Description

template<size_t NumModules>
class rmb::SwerveDrive< NumModules >

Class to manage most aspects of a swerve drivetrain from basic teleop drive funtions to odometry and full path following for both WPIL ib and PathPlanner trajectories.

Template Parameters
NumModulesNumber fo swerve modules on the drivetrain.

Constructor & Destructor Documentation

◆ SwerveDrive() [1/2]

template<size_t NumModules>
rmb::SwerveDrive< NumModules >::SwerveDrive ( std::array< SwerveModule, NumModules > modules,
std::shared_ptr< const rmb::Gyro > gyro,
frc::HolonomicDriveController holonomicController,
std::string visionTable,
units::meters_per_second_t maxModuleSpeed,
const frc::Pose2d & initialPose = frc::Pose2d() )

Constructs a SwerveDrive object that automatically incorrperates vision measurments over the network for odometry.

Parameters
modulesArray of swerve modules aprt of the drivetrain.
gyroMonitors the robots heading for odometry.
holonomicControllerFeedbakc controller for keeping the robot on path.
visionTablePath to the NetworkTables table for listening for vision updates.
maxModuleSpeedMaximum speed any module can turn
initialPoseStarting position of the robot for odometry.

◆ SwerveDrive() [2/2]

template<size_t NumModules>
rmb::SwerveDrive< NumModules >::SwerveDrive ( std::array< SwerveModule, NumModules > modules,
std::shared_ptr< const rmb::Gyro > gyro,
frc::HolonomicDriveController holonomicController,
units::meters_per_second_t maxModuleSpeed,
const frc::Pose2d & initialPose = frc::Pose2d() )

Constructs a SwerveDrive object that does not automatically incorrperates vision measurments over the network for odometry.

Parameters
modulesArray of swerve modules aprt of the drivetrain.
gyroMonitors the robots heading for odometry.
holonomicControllerFeedback controller for keeping the robot on path.
maxModuleSpeedMaximum speed any module can turn
initialPoseStarting position of the robot for odometry.

Member Function Documentation

◆ addVisionMeasurments()

template<size_t NumModules>
void rmb::SwerveDrive< NumModules >::addVisionMeasurments ( const frc::Pose2d & poseEstimate,
units::second_t time )
overridevirtual

Updates the current position of the robot using latency compensated vision data.

Parameters
poseEstimateThe estimated position of the robot from vision.
timeThe time at which the data that produces this estimate was captures. This is an absolute time with with the zero eposh being the same as wpi::Now() and o
  nt::Now(). This is usually extracted from network
                tables.

Implements rmb::BaseDrive.

◆ driveCartesian()

template<size_t NumModules>
void rmb::SwerveDrive< NumModules >::driveCartesian ( double xSpeed,
double ySpeed,
double zRotation,
bool fieldOriented )

https://dominik.win/blog/programming-swerve-drive/

output = \vec{v} + w * perpendicular{m} where v is the net translational velocity and m is the module's translation from the center

And we define our perpendicular functions as perpendicular(x, y) => (y, -x)

so, output_x = vx * 1 + vy * 0 + w * y output_y = vx * 0 + vy * 1 + w * -x

◆ driveChassisSpeeds()

template<size_t NumModules>
void rmb::SwerveDrive< NumModules >::driveChassisSpeeds ( frc::ChassisSpeeds chassisSpeeds)
overridevirtual

Drives the robot via the speeds of the Chassis.

Parameters
chassisSpeedsDesired speeds of the robot Chassis.

Implements rmb::BaseDrive.

◆ followPPPath()

template<size_t NumModules>
frc2::CommandPtr rmb::SwerveDrive< NumModules >::followPPPath ( std::shared_ptr< pathplanner::PathPlannerPath > path,
std::initializer_list< frc2::Subsystem * > driveRequirements )
overridevirtual

Generates a command to follow PathPlanner Trajectory.

Parameters
trajectoryThe trajectory to follow.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a trajectory.

Implements rmb::BaseDrive.

◆ followWPILibTrajectory()

template<size_t NumModules>
frc2::CommandPtr rmb::SwerveDrive< NumModules >::followWPILibTrajectory ( frc::Trajectory trajectory,
std::initializer_list< frc2::Subsystem * > driveRequirements )
overridevirtual

Generates a command to follow WPILib Trajectory.

Parameters
trajectoryThe trajectory to follow.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a trajectory.

Implements rmb::BaseDrive.

◆ getChassisSpeeds()

template<size_t NumModules>
frc::ChassisSpeeds rmb::SwerveDrive< NumModules >::getChassisSpeeds ( ) const
overridevirtual

Returns the speeds of the robot chassis.

Implements rmb::BaseDrive.

◆ getPose()

template<size_t NumModules>
frc::Pose2d rmb::SwerveDrive< NumModules >::getPose ( ) const
overridevirtual

Returns the current poition without modifying it.

Implements rmb::BaseDrive.

◆ isHolonomic()

template<size_t NumModules>
bool rmb::SwerveDrive< NumModules >::isHolonomic ( ) const
inlineoverridevirtual

Returns wherther the drive train is holonomic, meanign can move in all directions. This is nessesry for determining how to rezero a robot at the beginning of a path.

Implements rmb::BaseDrive.

◆ resetPose()

template<size_t NumModules>
void rmb::SwerveDrive< NumModules >::resetPose ( const frc::Pose2d & pose = frc::Pose2d())
overridevirtual

Resets the estimated robot poition.

Returns
The position to reset the robots estimated position to.

Implements rmb::BaseDrive.

◆ setVisionSTDevs()

template<size_t NumModules>
void rmb::SwerveDrive< NumModules >::setVisionSTDevs ( wpi::array< double, 3 > standardDevs)
overridevirtual

Change accuratly vision data is expected to be.

Parameters
standardDevsThe standar deviation of vision measurments. This is by how much teh actual robot positioon varies from the actual posiotion of the robot. A larger value means less acurate data. These are in units of meters and radians ordered X, Y, Theta.

Implements rmb::BaseDrive.

◆ updatePose()

template<size_t NumModules>
frc::Pose2d rmb::SwerveDrive< NumModules >::updatePose ( )
overridevirtual

Updates the current position of the robot using encoder and gyroscope data.

Note: Vision estimations are updated on a separate thread generated at object construction.

Returns
The updated position.

Implements rmb::BaseDrive.


The documentation for this class was generated from the following files: