2023 Drive base
 
Loading...
Searching...
No Matches
frc.robot.subsystems.Autonomous Class Reference

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)
 

Detailed Description

Contains functions for moving in autonomous mode, such as setting the robots trajectory, and getting speeds to set motors.

TODO: Untested

Author
xoth42

Definition at line 18 of file Autonomous.java.

Member Function Documentation

◆ applyChassisSpeeds()

static void frc.robot.subsystems.Autonomous.applyChassisSpeeds ( MecaDrive  m_drive)
static

using the chassis speeds from the trajectory specified by the robot, drive the robot

TODO: verify functionality and test

Parameters
m_driveMecaDrive drive base

Definition at line 63 of file Autonomous.java.

63 {
64 ChassisSpeeds currentChassisSpeeds = getChassisSpeeds(m_drive);
65
66 // linearize speed is needed because the mecanum cartesian drive takes arguments (velocities) actually as ratios, from 1 to -1. See MecaDrive.drive
67 m_drive.drive(linearizeVelocity(currentChassisSpeeds.vxMetersPerSecond), linearizeVelocity(currentChassisSpeeds.vyMetersPerSecond), linearizeVelocity(currentChassisSpeeds.omegaRadiansPerSecond, Constants.DRIVE_MAX_ANGULAR_VELOCITY));
68 }
static ChassisSpeeds getChassisSpeeds(MecaDrive m_drive)
return chassis speeds (to be then scaled and applied to driving the robot) retrived from the trajecto...
Definition: Autonomous.java:47
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,...
Definition: Autonomous.java:79

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().

◆ getChassisSpeeds()

static ChassisSpeeds frc.robot.subsystems.Autonomous.getChassisSpeeds ( MecaDrive  m_drive)
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.

Parameters
m_drive(MecaDrive) drivebase, to get the trajectory, time, and pose
Returns
ChassisSpeeds - https://github.wpilib.org/allwpilib/docs/release/java/edu/wpi/first/math/kinematics/ChassisSpeeds.html

Definition at line 47 of file Autonomous.java.

47 {
48 // get a (pose on spline) of the trajectory at "trajectoryTime" seconds relative to the beginning of the trajectory
49 Trajectory.State goal = m_drive.getCurrentTrajectory().sample(m_drive.getCurrentTrajectoryTime());
50
51
52 // return the chassis speeds (controller compares current pose of robot and goal to find the adequate speeds)
53 return m_drive.getChassisController().calculate(m_drive.getPose(), goal);
54 }

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().

◆ linearizeVelocity() [1/2]

static double frc.robot.subsystems.Autonomous.linearizeVelocity ( double  velocity)
staticprivate

linearize velocity using the max velocity of the robot, overloaded (from Constants)

Parameters
velocitymeters/second
Returns
velocity from -1 to 1

Definition at line 106 of file Autonomous.java.

106 {
107 return linearizeVelocity(velocity, Constants.maxVelocityMetersPerSecond);
108 }

References frc.robot.subsystems.Autonomous.linearizeVelocity(), and frc.robot.Constants.maxVelocityMetersPerSecond.

◆ linearizeVelocity() [2/2]

static double frc.robot.subsystems.Autonomous.linearizeVelocity ( double  velocity,
double  maxSpeed 
)
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)

Parameters
velocitydouble meters/second
maxSpeeddouble meters/second
Returns

Definition at line 79 of file Autonomous.java.

79 {
80 // Speed is a scalar, (velocity is not scalar, negative matters) which means that maxSpeed has no direction, and thus a negative value in this case would imply a incorrect usage for maxSpeed.
81 if (maxSpeed <= 0){
82 throw new IllegalArgumentException("maxSpeed must be positive and greater than 0");
83 }
84
85 double linearizedVelocity; // from 1 to -1
86
87 if (velocity == 0) {
88 linearizedVelocity = 0;
89 }
90 else if (velocity < 0) {
91 // if velocity is in greater magnitude than maxSpeed, divide it by maxspeed so that it is in the range [0, 1]
92 linearizedVelocity = Math.max(-1, velocity / maxSpeed);
93 }
94 else {
95 linearizedVelocity = Math.min(1, velocity / maxSpeed);
96 }
97
98 return linearizedVelocity;
99 }

Referenced by frc.robot.subsystems.Autonomous.applyChassisSpeeds(), and frc.robot.subsystems.Autonomous.linearizeVelocity().

◆ updateTrajectory()

static void frc.robot.subsystems.Autonomous.updateTrajectory ( MecaDrive  m_drive,
Pose2d  target,
ArrayList< Translation2d >  interiorWaypoints 
)
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

Parameters
m_drivedrive 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
targetending location (Pose2d)
interiorWaypointsthe points that the trajectory must reach (ArrayList<Translation2d>)

Definition at line 32 of file Autonomous.java.

32 {
33 // https://github.wpilib.org/allwpilib/docs/release/java/edu/wpi/first/math/trajectory/TrajectoryGenerator.html
34 // interior waypoints to-be-used, refrence https://docs.wpilib.org/en/stable/docs/software/advanced-controls/trajectories/trajectory-generation.html
35 Trajectory trajectory = TrajectoryGenerator.generateTrajectory(m_drive.getPose(), interiorWaypoints, target, m_drive.getTrajectoryConfig());
36 m_drive.setCurrentTrajectory(trajectory);
37 }

References frc.robot.subsystems.MecaDrive.getPose(), frc.robot.subsystems.DriveBase.getTrajectoryConfig(), and frc.robot.subsystems.DriveBase.setCurrentTrajectory().

Referenced by frc.robot.Robot.autonomousCheckForButtonPresses().


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