mirror of
https://github.com/BroncBotz3481/YAGSL
synced 2026-06-19 06:21:40 +00:00
612 lines
42 KiB
HTML
612 lines
42 KiB
HTML
<!DOCTYPE HTML>
|
|
<html lang="en">
|
|
<head>
|
|
<!-- Generated by javadoc (17) -->
|
|
<title>SwerveSubsystem (YAGSL-Example API)</title>
|
|
<meta name="viewport" content="width=device-width, initial-scale=1">
|
|
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
|
|
<meta name="description" content="declaration: package: frc.robot.subsystems.swervedrive, class: SwerveSubsystem">
|
|
<meta name="generator" content="javadoc/ClassWriterImpl">
|
|
<link rel="stylesheet" type="text/css" href="../../../../stylesheet.css" title="Style">
|
|
<link rel="stylesheet" type="text/css" href="../../../../script-dir/jquery-ui.min.css" title="Style">
|
|
<link rel="stylesheet" type="text/css" href="../../../../jquery-ui.overrides.css" title="Style">
|
|
<script type="text/javascript" src="../../../../script.js"></script>
|
|
<script type="text/javascript" src="../../../../script-dir/jquery-3.6.0.min.js"></script>
|
|
<script type="text/javascript" src="../../../../script-dir/jquery-ui.min.js"></script>
|
|
</head>
|
|
<body class="class-declaration-page">
|
|
<script type="text/javascript">var evenRowColor = "even-row-color";
|
|
var oddRowColor = "odd-row-color";
|
|
var tableTab = "table-tab";
|
|
var activeTableTab = "active-table-tab";
|
|
var pathtoroot = "../../../../";
|
|
loadScripts(document, 'script');</script>
|
|
<noscript>
|
|
<div>JavaScript is disabled on your browser.</div>
|
|
</noscript>
|
|
<div class="flex-box">
|
|
<header role="banner" class="flex-header">
|
|
<nav role="navigation">
|
|
<!-- ========= START OF TOP NAVBAR ======= -->
|
|
<div class="top-nav" id="navbar-top">
|
|
<div class="skip-nav"><a href="#skip-navbar-top" title="Skip navigation links">Skip navigation links</a></div>
|
|
<ul id="navbar-top-firstrow" class="nav-list" title="Navigation">
|
|
<li><a href="../../../../index.html">Overview</a></li>
|
|
<li><a href="package-summary.html">Package</a></li>
|
|
<li class="nav-bar-cell1-rev">Class</li>
|
|
<li><a href="package-tree.html">Tree</a></li>
|
|
<li><a href="../../../../index-all.html">Index</a></li>
|
|
<li><a href="../../../../help-doc.html#class">Help</a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="sub-nav">
|
|
<div>
|
|
<ul class="sub-nav-list">
|
|
<li>Summary: </li>
|
|
<li>Nested | </li>
|
|
<li><a href="#field-summary">Field</a> | </li>
|
|
<li><a href="#constructor-summary">Constr</a> | </li>
|
|
<li><a href="#method-summary">Method</a></li>
|
|
</ul>
|
|
<ul class="sub-nav-list">
|
|
<li>Detail: </li>
|
|
<li><a href="#field-detail">Field</a> | </li>
|
|
<li><a href="#constructor-detail">Constr</a> | </li>
|
|
<li><a href="#method-detail">Method</a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="nav-list-search"><label for="search-input">SEARCH:</label>
|
|
<input type="text" id="search-input" value="search" disabled="disabled">
|
|
<input type="reset" id="reset-button" value="reset" disabled="disabled">
|
|
</div>
|
|
</div>
|
|
<!-- ========= END OF TOP NAVBAR ========= -->
|
|
<span class="skip-nav" id="skip-navbar-top"></span></nav>
|
|
</header>
|
|
<div class="flex-content">
|
|
<main role="main">
|
|
<!-- ======== START OF CLASS DATA ======== -->
|
|
<div class="header">
|
|
<div class="sub-title"><span class="package-label-in-type">Package</span> <a href="package-summary.html">frc.robot.subsystems.swervedrive</a></div>
|
|
<h1 title="Class SwerveSubsystem" class="title">Class SwerveSubsystem</h1>
|
|
</div>
|
|
<div class="inheritance" title="Inheritance Tree"><a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html" title="class or interface in java.lang" class="external-link">java.lang.Object</a>
|
|
<div class="inheritance">edu.wpi.first.wpilibj2.command.SubsystemBase
|
|
<div class="inheritance">frc.robot.subsystems.swervedrive.SwerveSubsystem</div>
|
|
</div>
|
|
</div>
|
|
<section class="class-description" id="class-description">
|
|
<dl class="notes">
|
|
<dt>All Implemented Interfaces:</dt>
|
|
<dd><code>edu.wpi.first.util.sendable.Sendable</code>, <code>edu.wpi.first.wpilibj2.command.Subsystem</code></dd>
|
|
</dl>
|
|
<hr>
|
|
<div class="type-signature"><span class="modifiers">public class </span><span class="element-name type-name-label">SwerveSubsystem</span>
|
|
<span class="extends-implements">extends edu.wpi.first.wpilibj2.command.SubsystemBase</span></div>
|
|
</section>
|
|
<section class="summary">
|
|
<ul class="summary-list">
|
|
<!-- =========== FIELD SUMMARY =========== -->
|
|
<li>
|
|
<section class="field-summary" id="field-summary">
|
|
<h2>Field Summary</h2>
|
|
<div class="caption"><span>Fields</span></div>
|
|
<div class="summary-table three-column-summary">
|
|
<div class="table-header col-first">Modifier and Type</div>
|
|
<div class="table-header col-second">Field</div>
|
|
<div class="table-header col-last">Description</div>
|
|
<div class="col-first even-row-color"><code>double</code></div>
|
|
<div class="col-second even-row-color"><code><a href="#maximumSpeed" class="member-name-link">maximumSpeed</a></code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Maximum speed of the robot in meters per second, used to limit acceleration.</div>
|
|
</div>
|
|
</div>
|
|
</section>
|
|
</li>
|
|
<!-- ======== CONSTRUCTOR SUMMARY ======== -->
|
|
<li>
|
|
<section class="constructor-summary" id="constructor-summary">
|
|
<h2>Constructor Summary</h2>
|
|
<div class="caption"><span>Constructors</span></div>
|
|
<div class="summary-table two-column-summary">
|
|
<div class="table-header col-first">Constructor</div>
|
|
<div class="table-header col-last">Description</div>
|
|
<div class="col-constructor-name even-row-color"><code><a href="#%3Cinit%3E(java.io.File)" class="member-name-link">SwerveSubsystem</a><wbr>(<a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/io/File.html" title="class or interface in java.io" class="external-link">File</a> directory)</code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Initialize <a href="../../../../swervelib/SwerveDrive.html" title="class in swervelib"><code>SwerveDrive</code></a> with the directory provided.</div>
|
|
</div>
|
|
<div class="col-constructor-name odd-row-color"><code><a href="#%3Cinit%3E(swervelib.parser.SwerveDriveConfiguration,swervelib.parser.SwerveControllerConfiguration)" class="member-name-link">SwerveSubsystem</a><wbr>(<a href="../../../../swervelib/parser/SwerveDriveConfiguration.html" title="class in swervelib.parser">SwerveDriveConfiguration</a> driveCfg,
|
|
<a href="../../../../swervelib/parser/SwerveControllerConfiguration.html" title="class in swervelib.parser">SwerveControllerConfiguration</a> controllerCfg)</code></div>
|
|
<div class="col-last odd-row-color">
|
|
<div class="block">Construct the swerve drive.</div>
|
|
</div>
|
|
</div>
|
|
</section>
|
|
</li>
|
|
<!-- ========== METHOD SUMMARY =========== -->
|
|
<li>
|
|
<section class="method-summary" id="method-summary">
|
|
<h2>Method Summary</h2>
|
|
<div id="method-summary-table">
|
|
<div class="table-tabs" role="tablist" aria-orientation="horizontal"><button id="method-summary-table-tab0" role="tab" aria-selected="true" aria-controls="method-summary-table.tabpanel" tabindex="0" onkeydown="switchTab(event)" onclick="show('method-summary-table', 'method-summary-table', 3)" class="active-table-tab">All Methods</button><button id="method-summary-table-tab2" role="tab" aria-selected="false" aria-controls="method-summary-table.tabpanel" tabindex="-1" onkeydown="switchTab(event)" onclick="show('method-summary-table', 'method-summary-table-tab2', 3)" class="table-tab">Instance Methods</button><button id="method-summary-table-tab4" role="tab" aria-selected="false" aria-controls="method-summary-table.tabpanel" tabindex="-1" onkeydown="switchTab(event)" onclick="show('method-summary-table', 'method-summary-table-tab4', 3)" class="table-tab">Concrete Methods</button></div>
|
|
<div id="method-summary-table.tabpanel" role="tabpanel">
|
|
<div class="summary-table three-column-summary" aria-labelledby="method-summary-table-tab0">
|
|
<div class="table-header col-first">Modifier and Type</div>
|
|
<div class="table-header col-second">Method</div>
|
|
<div class="table-header col-last">Description</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#addFakeVisionReading()" class="member-name-link">addFakeVisionReading</a>()</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Add a fake vision reading for testing purposes.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#drive(edu.wpi.first.math.geometry.Translation2d,double,boolean)" class="member-name-link">drive</a><wbr>(edu.wpi.first.math.geometry.Translation2d translation,
|
|
double rotation,
|
|
boolean fieldRelative)</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">The primary method for controlling the drivebase.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#drive(edu.wpi.first.math.kinematics.ChassisSpeeds)" class="member-name-link">drive</a><wbr>(edu.wpi.first.math.kinematics.ChassisSpeeds velocity)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Drive according to the chassis robot oriented velocity.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#driveFieldOriented(edu.wpi.first.math.kinematics.ChassisSpeeds)" class="member-name-link">driveFieldOriented</a><wbr>(edu.wpi.first.math.kinematics.ChassisSpeeds velocity)</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Drive the robot given a chassis field oriented velocity.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.wpilibj2.command.Command</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getAutonomousCommand(java.lang.String,boolean)" class="member-name-link">getAutonomousCommand</a><wbr>(<a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/String.html" title="class or interface in java.lang" class="external-link">String</a> pathName,
|
|
boolean setOdomToStart)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Get the path follower with events.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.kinematics.ChassisSpeeds</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getFieldVelocity()" class="member-name-link">getFieldVelocity</a>()</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Gets the current field-relative velocity (x, y and omega) of the robot</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.geometry.Rotation2d</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getHeading()" class="member-name-link">getHeading</a>()</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Gets the current yaw angle of the robot, as reported by the imu.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.kinematics.SwerveDriveKinematics</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getKinematics()" class="member-name-link">getKinematics</a>()</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Get the swerve drive kinematics object.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.geometry.Rotation2d</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getPitch()" class="member-name-link">getPitch</a>()</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Gets the current pitch angle of the robot, as reported by the imu.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.geometry.Pose2d</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getPose()" class="member-name-link">getPose</a>()</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Gets the current pose (position and rotation) of the robot, as reported by odometry.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.kinematics.ChassisSpeeds</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getRobotVelocity()" class="member-name-link">getRobotVelocity</a>()</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Gets the current velocity (x, y and omega) of the robot</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="../../../../swervelib/SwerveController.html" title="class in swervelib">SwerveController</a></code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getSwerveController()" class="member-name-link">getSwerveController</a>()</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Get the <a href="../../../../swervelib/SwerveController.html" title="class in swervelib"><code>SwerveController</code></a> in the swerve drive.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="../../../../swervelib/parser/SwerveDriveConfiguration.html" title="class in swervelib.parser">SwerveDriveConfiguration</a></code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getSwerveDriveConfiguration()" class="member-name-link">getSwerveDriveConfiguration</a>()</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Get the <a href="../../../../swervelib/parser/SwerveDriveConfiguration.html" title="class in swervelib.parser"><code>SwerveDriveConfiguration</code></a> object.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.kinematics.ChassisSpeeds</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getTargetSpeeds(double,double,double,double)" class="member-name-link">getTargetSpeeds</a><wbr>(double xInput,
|
|
double yInput,
|
|
double headingX,
|
|
double headingY)</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Get the chassis speeds based on controller input of 2 joysticks.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>edu.wpi.first.math.kinematics.ChassisSpeeds</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#getTargetSpeeds(double,double,edu.wpi.first.math.geometry.Rotation2d)" class="member-name-link">getTargetSpeeds</a><wbr>(double xInput,
|
|
double yInput,
|
|
edu.wpi.first.math.geometry.Rotation2d angle)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Get the chassis speeds based on controller input of 1 joystick and one angle.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#lock()" class="member-name-link">lock</a>()</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Lock the swerve drive to prevent it from moving.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#periodic()" class="member-name-link">periodic</a>()</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"> </div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#postTrajectory(edu.wpi.first.math.trajectory.Trajectory)" class="member-name-link">postTrajectory</a><wbr>(edu.wpi.first.math.trajectory.Trajectory trajectory)</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Post the trajectory to the field.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#resetOdometry(edu.wpi.first.math.geometry.Pose2d)" class="member-name-link">resetOdometry</a><wbr>(edu.wpi.first.math.geometry.Pose2d initialHolonomicPose)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Resets odometry to the given pose.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#setChassisSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds)" class="member-name-link">setChassisSpeeds</a><wbr>(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds)</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Set chassis speeds with closed-loop velocity control.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#setMotorBrake(boolean)" class="member-name-link">setMotorBrake</a><wbr>(boolean brake)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Sets the drive motors to brake/coast mode.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#setupPathPlanner()" class="member-name-link">setupPathPlanner</a>()</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Setup AutoBuilder for PathPlanner.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#simulationPeriodic()" class="member-name-link">simulationPeriodic</a>()</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"> </div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code>void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#zeroGyro()" class="member-name-link">zeroGyro</a>()</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.</div>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
<div class="inherited-list">
|
|
<h3 id="methods-inherited-from-class-edu.wpi.first.wpilibj2.command.SubsystemBase">Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase</h3>
|
|
<code>addChild, getName, getSubsystem, initSendable, setName, setSubsystem</code></div>
|
|
<div class="inherited-list">
|
|
<h3 id="methods-inherited-from-class-java.lang.Object">Methods inherited from class java.lang.<a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html" title="class or interface in java.lang" class="external-link">Object</a></h3>
|
|
<code><a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#clone()" title="class or interface in java.lang" class="external-link">clone</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#equals(java.lang.Object)" title="class or interface in java.lang" class="external-link">equals</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#finalize()" title="class or interface in java.lang" class="external-link">finalize</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#getClass()" title="class or interface in java.lang" class="external-link">getClass</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#hashCode()" title="class or interface in java.lang" class="external-link">hashCode</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#notify()" title="class or interface in java.lang" class="external-link">notify</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#notifyAll()" title="class or interface in java.lang" class="external-link">notifyAll</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#toString()" title="class or interface in java.lang" class="external-link">toString</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#wait()" title="class or interface in java.lang" class="external-link">wait</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#wait(long)" title="class or interface in java.lang" class="external-link">wait</a>, <a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/Object.html#wait(long,int)" title="class or interface in java.lang" class="external-link">wait</a></code></div>
|
|
<div class="inherited-list">
|
|
<h3 id="methods-inherited-from-class-edu.wpi.first.wpilibj2.command.Subsystem">Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem</h3>
|
|
<code>defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, startEnd</code></div>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
<section class="details">
|
|
<ul class="details-list">
|
|
<!-- ============ FIELD DETAIL =========== -->
|
|
<li>
|
|
<section class="field-details" id="field-detail">
|
|
<h2>Field Details</h2>
|
|
<ul class="member-list">
|
|
<li>
|
|
<section class="detail" id="maximumSpeed">
|
|
<h3>maximumSpeed</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">double</span> <span class="element-name">maximumSpeed</span></div>
|
|
<div class="block">Maximum speed of the robot in meters per second, used to limit acceleration.</div>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
</li>
|
|
<!-- ========= CONSTRUCTOR DETAIL ======== -->
|
|
<li>
|
|
<section class="constructor-details" id="constructor-detail">
|
|
<h2>Constructor Details</h2>
|
|
<ul class="member-list">
|
|
<li>
|
|
<section class="detail" id="<init>(java.io.File)">
|
|
<h3>SwerveSubsystem</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="element-name">SwerveSubsystem</span><wbr><span class="parameters">(<a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/io/File.html" title="class or interface in java.io" class="external-link">File</a> directory)</span></div>
|
|
<div class="block">Initialize <a href="../../../../swervelib/SwerveDrive.html" title="class in swervelib"><code>SwerveDrive</code></a> with the directory provided.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>directory</code> - Directory of swerve drive config files.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="<init>(swervelib.parser.SwerveDriveConfiguration,swervelib.parser.SwerveControllerConfiguration)">
|
|
<h3>SwerveSubsystem</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="element-name">SwerveSubsystem</span><wbr><span class="parameters">(<a href="../../../../swervelib/parser/SwerveDriveConfiguration.html" title="class in swervelib.parser">SwerveDriveConfiguration</a> driveCfg,
|
|
<a href="../../../../swervelib/parser/SwerveControllerConfiguration.html" title="class in swervelib.parser">SwerveControllerConfiguration</a> controllerCfg)</span></div>
|
|
<div class="block">Construct the swerve drive.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>driveCfg</code> - SwerveDriveConfiguration for the swerve.</dd>
|
|
<dd><code>controllerCfg</code> - Swerve Controller.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
</li>
|
|
<!-- ============ METHOD DETAIL ========== -->
|
|
<li>
|
|
<section class="method-details" id="method-detail">
|
|
<h2>Method Details</h2>
|
|
<ul class="member-list">
|
|
<li>
|
|
<section class="detail" id="setupPathPlanner()">
|
|
<h3>setupPathPlanner</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">setupPathPlanner</span>()</div>
|
|
<div class="block">Setup AutoBuilder for PathPlanner.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getAutonomousCommand(java.lang.String,boolean)">
|
|
<h3>getAutonomousCommand</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.wpilibj2.command.Command</span> <span class="element-name">getAutonomousCommand</span><wbr><span class="parameters">(<a href="https://docs.oracle.com/en/java/javase/17/docs/api/java.base/java/lang/String.html" title="class or interface in java.lang" class="external-link">String</a> pathName,
|
|
boolean setOdomToStart)</span></div>
|
|
<div class="block">Get the path follower with events.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>pathName</code> - PathPlanner path name.</dd>
|
|
<dd><code>setOdomToStart</code> - Set the odometry position to the start of the path.</dd>
|
|
<dt>Returns:</dt>
|
|
<dd><code>AutoBuilder.followPath(PathPlannerPath)</code> path command.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="drive(edu.wpi.first.math.geometry.Translation2d,double,boolean)">
|
|
<h3>drive</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">drive</span><wbr><span class="parameters">(edu.wpi.first.math.geometry.Translation2d translation,
|
|
double rotation,
|
|
boolean fieldRelative)</span></div>
|
|
<div class="block">The primary method for controlling the drivebase. Takes a <code>Translation2d</code> and a rotation rate, and
|
|
calculates and commands module states accordingly. Can use either open-loop or closed-loop velocity control for
|
|
the wheel velocities. Also has field- and robot-relative modes, which affect how the translation vector is used.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>translation</code> - <code>Translation2d</code> that is the commanded linear velocity of the robot, in meters per
|
|
second. In robot-relative mode, positive x is torwards the bow (front) and positive y is
|
|
torwards port (left). In field-relative mode, positive x is away from the alliance wall
|
|
(field North) and positive y is torwards the left wall when looking through the driver station
|
|
glass (field West).</dd>
|
|
<dd><code>rotation</code> - Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot
|
|
relativity.</dd>
|
|
<dd><code>fieldRelative</code> - Drive mode. True for field-relative, false for robot-relative.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="driveFieldOriented(edu.wpi.first.math.kinematics.ChassisSpeeds)">
|
|
<h3>driveFieldOriented</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">driveFieldOriented</span><wbr><span class="parameters">(edu.wpi.first.math.kinematics.ChassisSpeeds velocity)</span></div>
|
|
<div class="block">Drive the robot given a chassis field oriented velocity.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>velocity</code> - Velocity according to the field.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="drive(edu.wpi.first.math.kinematics.ChassisSpeeds)">
|
|
<h3>drive</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">drive</span><wbr><span class="parameters">(edu.wpi.first.math.kinematics.ChassisSpeeds velocity)</span></div>
|
|
<div class="block">Drive according to the chassis robot oriented velocity.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>velocity</code> - Robot oriented <code>ChassisSpeeds</code></dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="periodic()">
|
|
<h3>periodic</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">periodic</span>()</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="simulationPeriodic()">
|
|
<h3>simulationPeriodic</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">simulationPeriodic</span>()</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getKinematics()">
|
|
<h3>getKinematics</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.kinematics.SwerveDriveKinematics</span> <span class="element-name">getKinematics</span>()</div>
|
|
<div class="block">Get the swerve drive kinematics object.</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd><code>SwerveDriveKinematics</code> of the swerve drive.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="resetOdometry(edu.wpi.first.math.geometry.Pose2d)">
|
|
<h3>resetOdometry</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">resetOdometry</span><wbr><span class="parameters">(edu.wpi.first.math.geometry.Pose2d initialHolonomicPose)</span></div>
|
|
<div class="block">Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this
|
|
method. However, if either gyro angle or module position is reset, this must be called in order for odometry to
|
|
keep working.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>initialHolonomicPose</code> - The pose to set the odometry to</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getPose()">
|
|
<h3>getPose</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.geometry.Pose2d</span> <span class="element-name">getPose</span>()</div>
|
|
<div class="block">Gets the current pose (position and rotation) of the robot, as reported by odometry.</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd>The robot's pose</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="setChassisSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds)">
|
|
<h3>setChassisSpeeds</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">setChassisSpeeds</span><wbr><span class="parameters">(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds)</span></div>
|
|
<div class="block">Set chassis speeds with closed-loop velocity control.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>chassisSpeeds</code> - Chassis Speeds to set.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="postTrajectory(edu.wpi.first.math.trajectory.Trajectory)">
|
|
<h3>postTrajectory</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">postTrajectory</span><wbr><span class="parameters">(edu.wpi.first.math.trajectory.Trajectory trajectory)</span></div>
|
|
<div class="block">Post the trajectory to the field.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>trajectory</code> - The trajectory to post.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="zeroGyro()">
|
|
<h3>zeroGyro</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">zeroGyro</span>()</div>
|
|
<div class="block">Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="setMotorBrake(boolean)">
|
|
<h3>setMotorBrake</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">setMotorBrake</span><wbr><span class="parameters">(boolean brake)</span></div>
|
|
<div class="block">Sets the drive motors to brake/coast mode.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>brake</code> - True to set motors to brake mode, false for coast.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getHeading()">
|
|
<h3>getHeading</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.geometry.Rotation2d</span> <span class="element-name">getHeading</span>()</div>
|
|
<div class="block">Gets the current yaw angle of the robot, as reported by the imu. CCW positive, not wrapped.</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd>The yaw angle</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getTargetSpeeds(double,double,double,double)">
|
|
<h3>getTargetSpeeds</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.kinematics.ChassisSpeeds</span> <span class="element-name">getTargetSpeeds</span><wbr><span class="parameters">(double xInput,
|
|
double yInput,
|
|
double headingX,
|
|
double headingY)</span></div>
|
|
<div class="block">Get the chassis speeds based on controller input of 2 joysticks. One for speeds in which direction. The other for
|
|
the angle of the robot.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>xInput</code> - X joystick input for the robot to move in the X direction.</dd>
|
|
<dd><code>yInput</code> - Y joystick input for the robot to move in the Y direction.</dd>
|
|
<dd><code>headingX</code> - X joystick which controls the angle of the robot.</dd>
|
|
<dd><code>headingY</code> - Y joystick which controls the angle of the robot.</dd>
|
|
<dt>Returns:</dt>
|
|
<dd><code>ChassisSpeeds</code> which can be sent to th Swerve Drive.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getTargetSpeeds(double,double,edu.wpi.first.math.geometry.Rotation2d)">
|
|
<h3>getTargetSpeeds</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.kinematics.ChassisSpeeds</span> <span class="element-name">getTargetSpeeds</span><wbr><span class="parameters">(double xInput,
|
|
double yInput,
|
|
edu.wpi.first.math.geometry.Rotation2d angle)</span></div>
|
|
<div class="block">Get the chassis speeds based on controller input of 1 joystick and one angle.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>xInput</code> - X joystick input for the robot to move in the X direction.</dd>
|
|
<dd><code>yInput</code> - Y joystick input for the robot to move in the Y direction.</dd>
|
|
<dd><code>angle</code> - The angle in as a <code>Rotation2d</code>.</dd>
|
|
<dt>Returns:</dt>
|
|
<dd><code>ChassisSpeeds</code> which can be sent to th Swerve Drive.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getFieldVelocity()">
|
|
<h3>getFieldVelocity</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.kinematics.ChassisSpeeds</span> <span class="element-name">getFieldVelocity</span>()</div>
|
|
<div class="block">Gets the current field-relative velocity (x, y and omega) of the robot</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd>A ChassisSpeeds object of the current field-relative velocity</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getRobotVelocity()">
|
|
<h3>getRobotVelocity</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.kinematics.ChassisSpeeds</span> <span class="element-name">getRobotVelocity</span>()</div>
|
|
<div class="block">Gets the current velocity (x, y and omega) of the robot</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd>A <code>ChassisSpeeds</code> object of the current velocity</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getSwerveController()">
|
|
<h3>getSwerveController</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type"><a href="../../../../swervelib/SwerveController.html" title="class in swervelib">SwerveController</a></span> <span class="element-name">getSwerveController</span>()</div>
|
|
<div class="block">Get the <a href="../../../../swervelib/SwerveController.html" title="class in swervelib"><code>SwerveController</code></a> in the swerve drive.</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd><a href="../../../../swervelib/SwerveController.html" title="class in swervelib"><code>SwerveController</code></a> from the <a href="../../../../swervelib/SwerveDrive.html" title="class in swervelib"><code>SwerveDrive</code></a>.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getSwerveDriveConfiguration()">
|
|
<h3>getSwerveDriveConfiguration</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type"><a href="../../../../swervelib/parser/SwerveDriveConfiguration.html" title="class in swervelib.parser">SwerveDriveConfiguration</a></span> <span class="element-name">getSwerveDriveConfiguration</span>()</div>
|
|
<div class="block">Get the <a href="../../../../swervelib/parser/SwerveDriveConfiguration.html" title="class in swervelib.parser"><code>SwerveDriveConfiguration</code></a> object.</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd>The <a href="../../../../swervelib/parser/SwerveDriveConfiguration.html" title="class in swervelib.parser"><code>SwerveDriveConfiguration</code></a> fpr the current drive.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="lock()">
|
|
<h3>lock</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">lock</span>()</div>
|
|
<div class="block">Lock the swerve drive to prevent it from moving.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="getPitch()">
|
|
<h3>getPitch</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.geometry.Rotation2d</span> <span class="element-name">getPitch</span>()</div>
|
|
<div class="block">Gets the current pitch angle of the robot, as reported by the imu.</div>
|
|
<dl class="notes">
|
|
<dt>Returns:</dt>
|
|
<dd>The heading as a <code>Rotation2d</code> angle</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="addFakeVisionReading()">
|
|
<h3>addFakeVisionReading</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">void</span> <span class="element-name">addFakeVisionReading</span>()</div>
|
|
<div class="block">Add a fake vision reading for testing purposes.</div>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
<!-- ========= END OF CLASS DATA ========= -->
|
|
</main>
|
|
</div>
|
|
</div>
|
|
</body>
|
|
</html>
|