Contains functions for moving in autonomous mode, such as setting the robots trajectory, and getting speeds to set motors. More...
Static Public Member Functions | |
| static void | updateTrajectory (MecaDrive m_drive, Pose2d target, ArrayList< Translation2d > interiorWaypoints) |
| Generate a 2d cartesian trajectory (line/spline) and apply it to robot, with the endpoint given, "target," which reaches every point in interiorWaypoints, all relative to the drive base odometry. | |
| static void | applyChassisSpeeds (MecaDrive m_drive) |
| using the chassis speeds from the trajectory specified by the robot, drive the robot | |
Static Private Member Functions | |
| static ChassisSpeeds | getChassisSpeeds (MecaDrive m_drive) |
| return chassis speeds (to be then scaled and applied to driving the robot) retrived from the trajectory of the robot and the time within the trajectory | |
| static double | linearizeVelocity (double velocity, double maxSpeed) |
| "linearized" in this case means a value that has been turned into a number from -1 to 1, relative to the given "max," which decides what value is associated with a linearized magnitude of 1. | |
| static double | linearizeVelocity (double velocity) |
| linearize velocity using the max velocity of the robot, overloaded (from Constants) | |
Contains functions for moving in autonomous mode, such as setting the robots trajectory, and getting speeds to set motors.
TODO: Untested
Definition at line 18 of file Autonomous.java.
|
static |
using the chassis speeds from the trajectory specified by the robot, drive the robot
TODO: verify functionality and test
| m_drive | MecaDrive drive base |
Definition at line 63 of file Autonomous.java.
References frc.robot.subsystems.MecaDrive.drive(), frc.robot.Constants.DRIVE_MAX_ANGULAR_VELOCITY, frc.robot.subsystems.Autonomous.getChassisSpeeds(), and frc.robot.subsystems.Autonomous.linearizeVelocity().
Referenced by frc.robot.Robot.autonomousPeriodic().
|
staticprivate |
return chassis speeds (to be then scaled and applied to driving the robot) retrived from the trajectory of the robot and the time within the trajectory
(done in robot auton periodic) have mecadrive deal with setting trajectorytime (setTrajectoryTime) within autonomous (eg. knowing where to go, relative to robot's odometry). Probably best to be set within a periodic function.
| m_drive | (MecaDrive) drivebase, to get the trajectory, time, and pose |
Definition at line 47 of file Autonomous.java.
References frc.robot.subsystems.DriveBase.getChassisController(), frc.robot.subsystems.DriveBase.getCurrentTrajectory(), frc.robot.subsystems.DriveBase.getCurrentTrajectoryTime(), and frc.robot.subsystems.MecaDrive.getPose().
Referenced by frc.robot.subsystems.Autonomous.applyChassisSpeeds().
|
staticprivate |
linearize velocity using the max velocity of the robot, overloaded (from Constants)
| velocity | meters/second |
Definition at line 106 of file Autonomous.java.
References frc.robot.subsystems.Autonomous.linearizeVelocity(), and frc.robot.Constants.maxVelocityMetersPerSecond.
|
staticprivate |
"linearized" in this case means a value that has been turned into a number from -1 to 1, relative to the given "max," which decides what value is associated with a linearized magnitude of 1.
TODO: check that this function is working correctly (double-check math)
| velocity | double meters/second |
| maxSpeed | double meters/second |
Definition at line 79 of file Autonomous.java.
Referenced by frc.robot.subsystems.Autonomous.applyChassisSpeeds(), and frc.robot.subsystems.Autonomous.linearizeVelocity().
|
static |
Generate a 2d cartesian trajectory (line/spline) and apply it to robot, with the endpoint given, "target," which reaches every point in interiorWaypoints, all relative to the drive base odometry.
For reference, see link https://docs.wpilib.org/en/stable/docs/software/advanced-controls/trajectories/trajectory-generation.html
| m_drive | drive base, for start pose and trajectory config (MecaDrive) m_drive could be DriveBase instead, but there is no getPose() for tank drive, same thing with getChassisSpeeds |
| target | ending location (Pose2d) |
| interiorWaypoints | the points that the trajectory must reach (ArrayList<Translation2d>) |
Definition at line 32 of file Autonomous.java.
References frc.robot.subsystems.MecaDrive.getPose(), frc.robot.subsystems.DriveBase.getTrajectoryConfig(), and frc.robot.subsystems.DriveBase.setCurrentTrajectory().
Referenced by frc.robot.Robot.autonomousCheckForButtonPresses().