mirror of
https://github.com/BroncBotz3481/YAGSL
synced 2026-06-19 06:21:40 +00:00
867 lines
36 KiB
HTML
867 lines
36 KiB
HTML
<!DOCTYPE HTML>
|
|
<!-- NewPage -->
|
|
<html lang="en">
|
|
<head>
|
|
<!-- Generated by javadoc (11.0.17) on Mon Feb 13 14:36:54 CST 2023 -->
|
|
<title>SwerveDrive</title>
|
|
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
|
|
<meta name="dc.created" content="2023-02-13">
|
|
<link rel="stylesheet" type="text/css" href="../../../../../stylesheet.css" title="Style">
|
|
<link rel="stylesheet" type="text/css" href="../../../../../jquery/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="../../../../../jquery/jszip/dist/jszip.min.js"></script>
|
|
<script type="text/javascript" src="../../../../../jquery/jszip-utils/dist/jszip-utils.min.js"></script>
|
|
<!--[if IE]>
|
|
<script type="text/javascript" src="../../../../../jquery/jszip-utils/dist/jszip-utils-ie.min.js"></script>
|
|
<![endif]-->
|
|
<script type="text/javascript" src="../../../../../jquery/jquery-3.6.0.min.js"></script>
|
|
<script type="text/javascript" src="../../../../../jquery/jquery-ui.min.js"></script>
|
|
</head>
|
|
<body>
|
|
<script type="text/javascript"><!--
|
|
try {
|
|
if (location.href.indexOf('is-external=true') == -1) {
|
|
parent.document.title="SwerveDrive";
|
|
}
|
|
}
|
|
catch(err) {
|
|
}
|
|
//-->
|
|
var data = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10,"i6":10,"i7":10,"i8":10,"i9":10,"i10":10,"i11":10,"i12":10,"i13":10,"i14":10,"i15":10,"i16":10};
|
|
var tabs = {65535:["t0","All Methods"],2:["t2","Instance Methods"],8:["t4","Concrete Methods"]};
|
|
var altColor = "altColor";
|
|
var rowColor = "rowColor";
|
|
var tableTab = "tableTab";
|
|
var activeTableTab = "activeTableTab";
|
|
var pathtoroot = "../../../../../";
|
|
var useModuleDirectories = true;
|
|
loadScripts(document, 'script');</script>
|
|
<noscript>
|
|
<div>JavaScript is disabled on your browser.</div>
|
|
</noscript>
|
|
<header role="banner">
|
|
<nav role="navigation">
|
|
<div class="fixedNav">
|
|
<!-- ========= START OF TOP NAVBAR ======= -->
|
|
<div class="topNav"><a id="navbar.top">
|
|
<!-- -->
|
|
</a>
|
|
<div class="skipNav"><a href="#skip.navbar.top" title="Skip navigation links">Skip navigation links</a></div>
|
|
<a id="navbar.top.firstrow">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="navList" title="Navigation">
|
|
<li><a href="../../../../../index.html">Overview</a></li>
|
|
<li><a href="package-summary.html">Package</a></li>
|
|
<li class="navBarCell1Rev">Class</li>
|
|
<li><a href="package-tree.html">Tree</a></li>
|
|
<li><a href="../../../../../deprecated-list.html">Deprecated</a></li>
|
|
<li><a href="../../../../../index-files/index-1.html">Index</a></li>
|
|
<li><a href="../../../../../help-doc.html">Help</a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="subNav">
|
|
<ul class="navList" id="allclasses_navbar_top">
|
|
<li><a href="../../../../../allclasses.html">All Classes</a></li>
|
|
</ul>
|
|
<ul class="navListSearch">
|
|
<li><label for="search">SEARCH:</label>
|
|
<input type="text" id="search" value="search" disabled="disabled">
|
|
<input type="reset" id="reset" value="reset" disabled="disabled">
|
|
</li>
|
|
</ul>
|
|
<div>
|
|
<script type="text/javascript"><!--
|
|
allClassesLink = document.getElementById("allclasses_navbar_top");
|
|
if(window==top) {
|
|
allClassesLink.style.display = "block";
|
|
}
|
|
else {
|
|
allClassesLink.style.display = "none";
|
|
}
|
|
//-->
|
|
</script>
|
|
<noscript>
|
|
<div>JavaScript is disabled on your browser.</div>
|
|
</noscript>
|
|
</div>
|
|
<div>
|
|
<ul class="subNavList">
|
|
<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="subNavList">
|
|
<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>
|
|
<a id="skip.navbar.top">
|
|
<!-- -->
|
|
</a></div>
|
|
<!-- ========= END OF TOP NAVBAR ========= -->
|
|
</div>
|
|
<div class="navPadding"> </div>
|
|
<script type="text/javascript"><!--
|
|
$('.navPadding').css('padding-top', $('.fixedNav').css("height"));
|
|
//-->
|
|
</script>
|
|
</nav>
|
|
</header>
|
|
<!-- ======== START OF CLASS DATA ======== -->
|
|
<main role="main">
|
|
<div class="header">
|
|
<div class="subTitle"><span class="packageLabelInType">Package</span> <a href="package-summary.html">frc.robot.subsystems.swervedrive2.swervelib</a></div>
|
|
<h2 title="Class SwerveDrive" class="title">Class SwerveDrive</h2>
|
|
</div>
|
|
<div class="contentContainer">
|
|
<ul class="inheritance">
|
|
<li><a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true" title="class or interface in java.lang" class="externalLink">java.lang.Object</a></li>
|
|
<li>
|
|
<ul class="inheritance">
|
|
<li>frc.robot.subsystems.swervedrive2.swervelib.SwerveDrive</li>
|
|
</ul>
|
|
</li>
|
|
</ul>
|
|
<div class="description">
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<hr>
|
|
<pre>public class <span class="typeNameLabel">SwerveDrive</span>
|
|
extends <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true" title="class or interface in java.lang" class="externalLink">Object</a></pre>
|
|
<div class="block">Swerve Drive class representing and controlling the swerve drive.</div>
|
|
</li>
|
|
</ul>
|
|
</div>
|
|
<div class="summary">
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<!-- =========== FIELD SUMMARY =========== -->
|
|
<section>
|
|
<ul class="blockList">
|
|
<li class="blockList"><a id="field.summary">
|
|
<!-- -->
|
|
</a>
|
|
<h3>Field Summary</h3>
|
|
<table class="memberSummary">
|
|
<caption><span>Fields</span><span class="tabEnd"> </span></caption>
|
|
<tr>
|
|
<th class="colFirst" scope="col">Modifier and Type</th>
|
|
<th class="colSecond" scope="col">Field</th>
|
|
<th class="colLast" scope="col">Description</th>
|
|
</tr>
|
|
<tr class="altColor">
|
|
<td class="colFirst"><code>private double</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#angle">angle</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">The current angle of the robot and last time odometry during simulations.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="rowColor">
|
|
<td class="colFirst"><code>edu.wpi.first.wpilibj.smartdashboard.Field2d</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#field">field</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Field object.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="altColor">
|
|
<td class="colFirst"><code>private <a href="imu/SwerveIMU.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.imu">SwerveIMU</a></code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#imu">imu</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Swerve IMU device for sensing the heading of the robot.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="rowColor">
|
|
<td class="colFirst"><code><a href="math/SwerveKinematics2.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.math">SwerveKinematics2</a></code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#kinematics">kinematics</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Swerve Kinematics object utilizing second order kinematics.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="altColor">
|
|
<td class="colFirst"><code>private double</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#lastTime">lastTime</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">The current angle of the robot and last time odometry during simulations.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="rowColor">
|
|
<td class="colFirst"><code><a href="SwerveController.html" title="class in frc.robot.subsystems.swervedrive2.swervelib">SwerveController</a></code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#swerveController">swerveController</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Swerve controller for controlling heading of the robot.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="altColor">
|
|
<td class="colFirst"><code><a href="parser/SwerveDriveConfiguration.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.parser">SwerveDriveConfiguration</a></code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#swerveDriveConfiguration">swerveDriveConfiguration</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Swerve drive configuration.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="rowColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.estimator.SwerveDrivePoseEstimator</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#swerveDrivePoseEstimator">swerveDrivePoseEstimator</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Swerve odometry.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="altColor">
|
|
<td class="colFirst"><code>private <a href="SwerveModule.html" title="class in frc.robot.subsystems.swervedrive2.swervelib">SwerveModule</a>[]</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#swerveModules">swerveModules</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Swerve modules.</div>
|
|
</td>
|
|
</tr>
|
|
<tr class="rowColor">
|
|
<td class="colFirst"><code>private edu.wpi.first.wpilibj.Timer</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#timer">timer</a></span></code></th>
|
|
<td class="colLast">
|
|
<div class="block">Time during simulations.</div>
|
|
</td>
|
|
</tr>
|
|
</table>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
<!-- ======== CONSTRUCTOR SUMMARY ======== -->
|
|
<section>
|
|
<ul class="blockList">
|
|
<li class="blockList"><a id="constructor.summary">
|
|
<!-- -->
|
|
</a>
|
|
<h3>Constructor Summary</h3>
|
|
<table class="memberSummary">
|
|
<caption><span>Constructors</span><span class="tabEnd"> </span></caption>
|
|
<tr>
|
|
<th class="colFirst" scope="col">Constructor</th>
|
|
<th class="colLast" scope="col">Description</th>
|
|
</tr>
|
|
<tr class="altColor">
|
|
<th class="colConstructorName" scope="row"><code><span class="memberNameLink"><a href="#%3Cinit%3E(frc.robot.subsystems.swervedrive2.swervelib.parser.SwerveDriveConfiguration,frc.robot.subsystems.swervedrive2.swervelib.parser.SwerveControllerConfiguration)">SwerveDrive</a></span>​(<a href="parser/SwerveDriveConfiguration.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.parser">SwerveDriveConfiguration</a> config,
|
|
<a href="parser/SwerveControllerConfiguration.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.parser">SwerveControllerConfiguration</a> controllerConfig)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Creates a new swerve drivebase subsystem.</div>
|
|
</td>
|
|
</tr>
|
|
</table>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
<!-- ========== METHOD SUMMARY =========== -->
|
|
<section>
|
|
<ul class="blockList">
|
|
<li class="blockList"><a id="method.summary">
|
|
<!-- -->
|
|
</a>
|
|
<h3>Method Summary</h3>
|
|
<table class="memberSummary">
|
|
<caption><span id="t0" class="activeTableTab"><span>All Methods</span><span class="tabEnd"> </span></span><span id="t2" class="tableTab"><span><a href="javascript:show(2);">Instance Methods</a></span><span class="tabEnd"> </span></span><span id="t4" class="tableTab"><span><a href="javascript:show(8);">Concrete Methods</a></span><span class="tabEnd"> </span></span></caption>
|
|
<tr>
|
|
<th class="colFirst" scope="col">Modifier and Type</th>
|
|
<th class="colSecond" scope="col">Method</th>
|
|
<th class="colLast" scope="col">Description</th>
|
|
</tr>
|
|
<tr id="i0" class="altColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#drive(edu.wpi.first.math.geometry.Translation2d,double,boolean,boolean)">drive</a></span>​(edu.wpi.first.math.geometry.Translation2d translation,
|
|
double rotation,
|
|
boolean fieldRelative,
|
|
boolean isOpenLoop)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">The primary method for controlling the drivebase.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i1" class="rowColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.kinematics.ChassisSpeeds</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getFieldVelocity()">getFieldVelocity</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Gets the current field-relative velocity (x, y and omega) of the robot</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i2" class="altColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.kinematics.SwerveModulePosition[]</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getModulePositions()">getModulePositions</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Gets the current module positions (azimuth and wheel position (meters))</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i3" class="rowColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.geometry.Rotation2d</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getPitch()">getPitch</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Gets the current yaw angle of the robot, as reported by the imu.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i4" class="altColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.geometry.Pose2d</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getPose()">getPose</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Gets the current pose (position and rotation) of the robot, as reported by odometry.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i5" class="rowColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.kinematics.ChassisSpeeds</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getRobotVelocity()">getRobotVelocity</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Gets the current robot-relative velocity (x, y and omega) of the robot</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i6" class="altColor">
|
|
<td class="colFirst"><code><a href="math/SwerveModuleState2.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.math">SwerveModuleState2</a>[]</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getStates()">getStates</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Gets the current module states (azimuth and velocity)</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i7" class="rowColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.geometry.Pose2d[]</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getSwerveModulePoses(edu.wpi.first.math.geometry.Pose2d)">getSwerveModulePoses</a></span>​(edu.wpi.first.math.geometry.Pose2d robotPose)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Get the swerve module poses and on the field relative to the robot.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i8" class="altColor">
|
|
<td class="colFirst"><code>edu.wpi.first.math.geometry.Rotation2d</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#getYaw()">getYaw</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Gets the current yaw angle of the robot, as reported by the imu.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i9" class="rowColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#replaceSwerveModuleFeedforward(edu.wpi.first.math.controller.SimpleMotorFeedforward)">replaceSwerveModuleFeedforward</a></span>​(edu.wpi.first.math.controller.SimpleMotorFeedforward feedforward)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Setup the swerve module feedforward.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i10" class="altColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#resetOdometry(edu.wpi.first.math.geometry.Pose2d)">resetOdometry</a></span>​(edu.wpi.first.math.geometry.Pose2d pose)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Resets odometry to the given pose.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i11" class="rowColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#setChassisSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds)">setChassisSpeeds</a></span>​(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Set field-relative chassis speeds with closed-loop velocity control.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i12" class="altColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#setDriveBrake()">setDriveBrake</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Point all modules toward the robot center, thus making the robot very difficult to move.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i13" class="rowColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#setModuleStates(frc.robot.subsystems.swervedrive2.swervelib.math.SwerveModuleState2%5B%5D,boolean)">setModuleStates</a></span>​(<a href="math/SwerveModuleState2.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.math">SwerveModuleState2</a>[] desiredStates,
|
|
boolean isOpenLoop)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Set the module states (azimuth and velocity) directly.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i14" class="altColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#setMotorBrake(boolean)">setMotorBrake</a></span>​(boolean brake)</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Sets the drive motors to brake/coast mode.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i15" class="rowColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#updateOdometry()">updateOdometry</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Update odometry should be run every loop.</div>
|
|
</td>
|
|
</tr>
|
|
<tr id="i16" class="altColor">
|
|
<td class="colFirst"><code>void</code></td>
|
|
<th class="colSecond" scope="row"><code><span class="memberNameLink"><a href="#zeroGyro()">zeroGyro</a></span>()</code></th>
|
|
<td class="colLast">
|
|
<div class="block">Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.</div>
|
|
</td>
|
|
</tr>
|
|
</table>
|
|
<ul class="blockList">
|
|
<li class="blockList"><a id="methods.inherited.from.class.java.lang.Object">
|
|
<!-- -->
|
|
</a>
|
|
<h3>Methods inherited from class java.lang.<a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true" title="class or interface in java.lang" class="externalLink">Object</a></h3>
|
|
<code><a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#clone()" title="class or interface in java.lang" class="externalLink">clone</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#equals(java.lang.Object)" title="class or interface in java.lang" class="externalLink">equals</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#finalize()" title="class or interface in java.lang" class="externalLink">finalize</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#getClass()" title="class or interface in java.lang" class="externalLink">getClass</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#hashCode()" title="class or interface in java.lang" class="externalLink">hashCode</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#notify()" title="class or interface in java.lang" class="externalLink">notify</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#notifyAll()" title="class or interface in java.lang" class="externalLink">notifyAll</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#toString()" title="class or interface in java.lang" class="externalLink">toString</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#wait()" title="class or interface in java.lang" class="externalLink">wait</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#wait(long)" title="class or interface in java.lang" class="externalLink">wait</a>, <a href="https://docs.oracle.com/en/java/javase/11/docs/api/java.base/java/lang/Object.html?is-external=true#wait(long,int)" title="class or interface in java.lang" class="externalLink">wait</a></code></li>
|
|
</ul>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</div>
|
|
<div class="details">
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<!-- ============ FIELD DETAIL =========== -->
|
|
<section>
|
|
<ul class="blockList">
|
|
<li class="blockList"><a id="field.detail">
|
|
<!-- -->
|
|
</a>
|
|
<h3>Field Detail</h3>
|
|
<a id="kinematics">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>kinematics</h4>
|
|
<pre>public final <a href="math/SwerveKinematics2.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.math">SwerveKinematics2</a> kinematics</pre>
|
|
<div class="block">Swerve Kinematics object utilizing second order kinematics.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="swerveDriveConfiguration">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>swerveDriveConfiguration</h4>
|
|
<pre>public final <a href="parser/SwerveDriveConfiguration.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.parser">SwerveDriveConfiguration</a> swerveDriveConfiguration</pre>
|
|
<div class="block">Swerve drive configuration.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="swerveDrivePoseEstimator">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>swerveDrivePoseEstimator</h4>
|
|
<pre>public final edu.wpi.first.math.estimator.SwerveDrivePoseEstimator swerveDrivePoseEstimator</pre>
|
|
<div class="block">Swerve odometry.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="swerveModules">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>swerveModules</h4>
|
|
<pre>private final <a href="SwerveModule.html" title="class in frc.robot.subsystems.swervedrive2.swervelib">SwerveModule</a>[] swerveModules</pre>
|
|
<div class="block">Swerve modules.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="field">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>field</h4>
|
|
<pre>public edu.wpi.first.wpilibj.smartdashboard.Field2d field</pre>
|
|
<div class="block">Field object.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="swerveController">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>swerveController</h4>
|
|
<pre>public <a href="SwerveController.html" title="class in frc.robot.subsystems.swervedrive2.swervelib">SwerveController</a> swerveController</pre>
|
|
<div class="block">Swerve controller for controlling heading of the robot.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="imu">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>imu</h4>
|
|
<pre>private <a href="imu/SwerveIMU.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.imu">SwerveIMU</a> imu</pre>
|
|
<div class="block">Swerve IMU device for sensing the heading of the robot.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="angle">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>angle</h4>
|
|
<pre>private double angle</pre>
|
|
<div class="block">The current angle of the robot and last time odometry during simulations.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="lastTime">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>lastTime</h4>
|
|
<pre>private double lastTime</pre>
|
|
<div class="block">The current angle of the robot and last time odometry during simulations.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="timer">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockListLast">
|
|
<li class="blockList">
|
|
<h4>timer</h4>
|
|
<pre>private edu.wpi.first.wpilibj.Timer timer</pre>
|
|
<div class="block">Time during simulations.</div>
|
|
</li>
|
|
</ul>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
<!-- ========= CONSTRUCTOR DETAIL ======== -->
|
|
<section>
|
|
<ul class="blockList">
|
|
<li class="blockList"><a id="constructor.detail">
|
|
<!-- -->
|
|
</a>
|
|
<h3>Constructor Detail</h3>
|
|
<a id="<init>(frc.robot.subsystems.swervedrive2.swervelib.parser.SwerveDriveConfiguration,frc.robot.subsystems.swervedrive2.swervelib.parser.SwerveControllerConfiguration)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockListLast">
|
|
<li class="blockList">
|
|
<h4>SwerveDrive</h4>
|
|
<pre>public SwerveDrive​(<a href="parser/SwerveDriveConfiguration.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.parser">SwerveDriveConfiguration</a> config,
|
|
<a href="parser/SwerveControllerConfiguration.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.parser">SwerveControllerConfiguration</a> controllerConfig)</pre>
|
|
<div class="block">Creates a new swerve drivebase subsystem. Robot is controlled via the drive() method, or via the setModuleStates()
|
|
method. The drive() method incorporates kinematics— it takes a translation and rotation, as well as parameters for
|
|
field-centric and closed-loop velocity control. setModuleStates() takes a list of SwerveModuleStates and directly
|
|
passes them to the modules. This subsystem also handles odometry.</div>
|
|
</li>
|
|
</ul>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
<!-- ============ METHOD DETAIL ========== -->
|
|
<section>
|
|
<ul class="blockList">
|
|
<li class="blockList"><a id="method.detail">
|
|
<!-- -->
|
|
</a>
|
|
<h3>Method Detail</h3>
|
|
<a id="drive(edu.wpi.first.math.geometry.Translation2d,double,boolean,boolean)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>drive</h4>
|
|
<pre class="methodSignature">public void drive​(edu.wpi.first.math.geometry.Translation2d translation,
|
|
double rotation,
|
|
boolean fieldRelative,
|
|
boolean isOpenLoop)</pre>
|
|
<div class="block">The primary method for controlling the drivebase. Takes a Translation2d 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>
|
|
<dt><span class="paramLabel">Parameters:</span></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>
|
|
<dd><code>isOpenLoop</code> - Whether to use closed-loop velocity control. Set to true to disable closed-loop.</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="setModuleStates(frc.robot.subsystems.swervedrive2.swervelib.math.SwerveModuleState2[],boolean)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>setModuleStates</h4>
|
|
<pre class="methodSignature">public void setModuleStates​(<a href="math/SwerveModuleState2.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.math">SwerveModuleState2</a>[] desiredStates,
|
|
boolean isOpenLoop)</pre>
|
|
<div class="block">Set the module states (azimuth and velocity) directly. Used primarily for auto pathing.</div>
|
|
<dl>
|
|
<dt><span class="paramLabel">Parameters:</span></dt>
|
|
<dd><code>desiredStates</code> - A list of SwerveModuleStates to send to the modules.</dd>
|
|
<dd><code>isOpenLoop</code> - Whether to use closed-loop velocity control. Set to true to disable closed-loop.</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="setChassisSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>setChassisSpeeds</h4>
|
|
<pre class="methodSignature">public void setChassisSpeeds​(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds)</pre>
|
|
<div class="block">Set field-relative chassis speeds with closed-loop velocity control.</div>
|
|
<dl>
|
|
<dt><span class="paramLabel">Parameters:</span></dt>
|
|
<dd><code>chassisSpeeds</code> - Field-relative.</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="getPose()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getPose</h4>
|
|
<pre class="methodSignature">public edu.wpi.first.math.geometry.Pose2d getPose()</pre>
|
|
<div class="block">Gets the current pose (position and rotation) of the robot, as reported by odometry.</div>
|
|
<dl>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>The robot's pose</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="getFieldVelocity()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getFieldVelocity</h4>
|
|
<pre class="methodSignature">public edu.wpi.first.math.kinematics.ChassisSpeeds getFieldVelocity()</pre>
|
|
<div class="block">Gets the current field-relative velocity (x, y and omega) of the robot</div>
|
|
<dl>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>A ChassisSpeeds object of the current field-relative velocity</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="getRobotVelocity()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getRobotVelocity</h4>
|
|
<pre class="methodSignature">public edu.wpi.first.math.kinematics.ChassisSpeeds getRobotVelocity()</pre>
|
|
<div class="block">Gets the current robot-relative velocity (x, y and omega) of the robot</div>
|
|
<dl>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>A ChassisSpeeds object of the current robot-relative velocity</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="resetOdometry(edu.wpi.first.math.geometry.Pose2d)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>resetOdometry</h4>
|
|
<pre class="methodSignature">public void resetOdometry​(edu.wpi.first.math.geometry.Pose2d pose)</pre>
|
|
<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>
|
|
<dt><span class="paramLabel">Parameters:</span></dt>
|
|
<dd><code>pose</code> - The pose to set the odometry to</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="getStates()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getStates</h4>
|
|
<pre class="methodSignature">public <a href="math/SwerveModuleState2.html" title="class in frc.robot.subsystems.swervedrive2.swervelib.math">SwerveModuleState2</a>[] getStates()</pre>
|
|
<div class="block">Gets the current module states (azimuth and velocity)</div>
|
|
<dl>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>A list of SwerveModuleStates containing the current module states</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="getModulePositions()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getModulePositions</h4>
|
|
<pre class="methodSignature">public edu.wpi.first.math.kinematics.SwerveModulePosition[] getModulePositions()</pre>
|
|
<div class="block">Gets the current module positions (azimuth and wheel position (meters))</div>
|
|
<dl>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>A list of SwerveModulePositions containg the current module positions</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="zeroGyro()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>zeroGyro</h4>
|
|
<pre class="methodSignature">public void zeroGyro()</pre>
|
|
<div class="block">Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="getYaw()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getYaw</h4>
|
|
<pre class="methodSignature">public edu.wpi.first.math.geometry.Rotation2d getYaw()</pre>
|
|
<div class="block">Gets the current yaw angle of the robot, as reported by the imu. CCW positive, not wrapped.</div>
|
|
<dl>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>The yaw as a <code>Rotation2d</code> angle</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="getPitch()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getPitch</h4>
|
|
<pre class="methodSignature">public edu.wpi.first.math.geometry.Rotation2d getPitch()</pre>
|
|
<div class="block">Gets the current yaw angle of the robot, as reported by the imu. CCW positive, not wrapped.</div>
|
|
<dl>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>The heading as a <code>Rotation2d</code> angle</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="setMotorBrake(boolean)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>setMotorBrake</h4>
|
|
<pre class="methodSignature">public void setMotorBrake​(boolean brake)</pre>
|
|
<div class="block">Sets the drive motors to brake/coast mode.</div>
|
|
<dl>
|
|
<dt><span class="paramLabel">Parameters:</span></dt>
|
|
<dd><code>brake</code> - True to set motors to brake mode, false for coast.</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="setDriveBrake()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>setDriveBrake</h4>
|
|
<pre class="methodSignature">public void setDriveBrake()</pre>
|
|
<div class="block">Point all modules toward the robot center, thus making the robot very difficult to move.</div>
|
|
</li>
|
|
</ul>
|
|
<a id="getSwerveModulePoses(edu.wpi.first.math.geometry.Pose2d)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>getSwerveModulePoses</h4>
|
|
<pre class="methodSignature">public edu.wpi.first.math.geometry.Pose2d[] getSwerveModulePoses​(edu.wpi.first.math.geometry.Pose2d robotPose)</pre>
|
|
<div class="block">Get the swerve module poses and on the field relative to the robot.</div>
|
|
<dl>
|
|
<dt><span class="paramLabel">Parameters:</span></dt>
|
|
<dd><code>robotPose</code> - Robot pose.</dd>
|
|
<dt><span class="returnLabel">Returns:</span></dt>
|
|
<dd>Swerve module poses.</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="replaceSwerveModuleFeedforward(edu.wpi.first.math.controller.SimpleMotorFeedforward)">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockList">
|
|
<li class="blockList">
|
|
<h4>replaceSwerveModuleFeedforward</h4>
|
|
<pre class="methodSignature">public void replaceSwerveModuleFeedforward​(edu.wpi.first.math.controller.SimpleMotorFeedforward feedforward)</pre>
|
|
<div class="block">Setup the swerve module feedforward.</div>
|
|
<dl>
|
|
<dt><span class="paramLabel">Parameters:</span></dt>
|
|
<dd><code>feedforward</code> - Feedforward for the drive motor on swerve modules.</dd>
|
|
</dl>
|
|
</li>
|
|
</ul>
|
|
<a id="updateOdometry()">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="blockListLast">
|
|
<li class="blockList">
|
|
<h4>updateOdometry</h4>
|
|
<pre class="methodSignature">public void updateOdometry()</pre>
|
|
<div class="block">Update odometry should be run every loop.</div>
|
|
</li>
|
|
</ul>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</div>
|
|
</div>
|
|
</main>
|
|
<!-- ========= END OF CLASS DATA ========= -->
|
|
<footer role="contentinfo">
|
|
<nav role="navigation">
|
|
<!-- ======= START OF BOTTOM NAVBAR ====== -->
|
|
<div class="bottomNav"><a id="navbar.bottom">
|
|
<!-- -->
|
|
</a>
|
|
<div class="skipNav"><a href="#skip.navbar.bottom" title="Skip navigation links">Skip navigation links</a></div>
|
|
<a id="navbar.bottom.firstrow">
|
|
<!-- -->
|
|
</a>
|
|
<ul class="navList" title="Navigation">
|
|
<li><a href="../../../../../index.html">Overview</a></li>
|
|
<li><a href="package-summary.html">Package</a></li>
|
|
<li class="navBarCell1Rev">Class</li>
|
|
<li><a href="package-tree.html">Tree</a></li>
|
|
<li><a href="../../../../../deprecated-list.html">Deprecated</a></li>
|
|
<li><a href="../../../../../index-files/index-1.html">Index</a></li>
|
|
<li><a href="../../../../../help-doc.html">Help</a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="subNav">
|
|
<ul class="navList" id="allclasses_navbar_bottom">
|
|
<li><a href="../../../../../allclasses.html">All Classes</a></li>
|
|
</ul>
|
|
<div>
|
|
<script type="text/javascript"><!--
|
|
allClassesLink = document.getElementById("allclasses_navbar_bottom");
|
|
if(window==top) {
|
|
allClassesLink.style.display = "block";
|
|
}
|
|
else {
|
|
allClassesLink.style.display = "none";
|
|
}
|
|
//-->
|
|
</script>
|
|
<noscript>
|
|
<div>JavaScript is disabled on your browser.</div>
|
|
</noscript>
|
|
</div>
|
|
<div>
|
|
<ul class="subNavList">
|
|
<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="subNavList">
|
|
<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>
|
|
<a id="skip.navbar.bottom">
|
|
<!-- -->
|
|
</a></div>
|
|
<!-- ======== END OF BOTTOM NAVBAR ======= -->
|
|
</nav>
|
|
</footer>
|
|
</body>
|
|
</html>
|