|
librmb 1.0
Rambunction 4330 Utility Library
|
#include <rmb/drive/SwerveDrive.h>
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, NumModules > | getModuleStates () const |
| std::array< frc::SwerveModulePosition, NumModules > | getModulePositions () 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, NumModules > | getTargetModuleStates () 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 |
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.
| NumModules | Number fo swerve modules on the drivetrain. |
| 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.
| modules | Array of swerve modules aprt of the drivetrain. |
| gyro | Monitors the robots heading for odometry. |
| holonomicController | Feedbakc controller for keeping the robot on path. |
| visionTable | Path to the NetworkTables table for listening for vision updates. |
| maxModuleSpeed | Maximum speed any module can turn |
| initialPose | Starting position of the robot for odometry. |
| 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.
| modules | Array of swerve modules aprt of the drivetrain. |
| gyro | Monitors the robots heading for odometry. |
| holonomicController | Feedback controller for keeping the robot on path. |
| maxModuleSpeed | Maximum speed any module can turn |
| initialPose | Starting position of the robot for odometry. |
|
overridevirtual |
Updates the current position of the robot using latency compensated vision data.
| poseEstimate | The estimated position of the robot from vision. |
| time | The 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.
| 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
|
overridevirtual |
Drives the robot via the speeds of the Chassis.
| chassisSpeeds | Desired speeds of the robot Chassis. |
Implements rmb::BaseDrive.
|
overridevirtual |
Generates a command to follow PathPlanner Trajectory.
| trajectory | The trajectory to follow. |
| driveRequirements | The subsystems required for driving the robot (ie. the one that contains this class) |
Implements rmb::BaseDrive.
|
overridevirtual |
Generates a command to follow WPILib Trajectory.
| trajectory | The trajectory to follow. |
| driveRequirements | The subsystems required for driving the robot (ie. the one that contains this class) |
Implements rmb::BaseDrive.
|
overridevirtual |
Returns the speeds of the robot chassis.
Implements rmb::BaseDrive.
|
overridevirtual |
Returns the current poition without modifying it.
Implements rmb::BaseDrive.
|
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.
|
overridevirtual |
Resets the estimated robot poition.
Implements rmb::BaseDrive.
|
overridevirtual |
Change accuratly vision data is expected to be.
| standardDevs | The 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.
|
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.
Implements rmb::BaseDrive.