mirror of
https://github.com/BroncBotz3481/YAGSL
synced 2026-06-19 06:21:40 +00:00
464 lines
31 KiB
HTML
464 lines
31 KiB
HTML
<!DOCTYPE HTML>
|
|
<html lang="en">
|
|
<head>
|
|
<!-- Generated by javadoc (17) on Sat Apr 08 13:12:34 CDT 2023 -->
|
|
<title>SwerveKinematics2</title>
|
|
<meta name="viewport" content="width=device-width, initial-scale=1">
|
|
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
|
|
<meta name="dc.created" content="2023-04-08">
|
|
<meta name="description" content="declaration: package: swervelib.math, class: SwerveKinematics2">
|
|
<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.5.1.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-files/index-1.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">swervelib.math</a></div>
|
|
<h1 title="Class SwerveKinematics2" class="title">Class SwerveKinematics2</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.math.kinematics.SwerveDriveKinematics
|
|
<div class="inheritance">swervelib.math.SwerveKinematics2</div>
|
|
</div>
|
|
</div>
|
|
<section class="class-description" id="class-description">
|
|
<hr>
|
|
<div class="type-signature"><span class="modifiers">public class </span><span class="element-name type-name-label">SwerveKinematics2</span>
|
|
<span class="extends-implements">extends edu.wpi.first.math.kinematics.SwerveDriveKinematics</span></div>
|
|
<div class="block">Clone of WPI SwerveKinematics, which implements second order kinematics when calculating modules states from chassis
|
|
speed. Makes use of <a href="SwerveModuleState2.html" title="class in swervelib.math"><code>SwerveModuleState2</code></a> to add the angular velocity that is required of the module as an
|
|
output.</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>private final org.ejml.simple.SimpleMatrix</code></div>
|
|
<div class="col-second even-row-color"><code><a href="#bigInverseKinematics" class="member-name-link">bigInverseKinematics</a></code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Second order kinematics inverse matrix.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color"><code>private final org.ejml.simple.SimpleMatrix</code></div>
|
|
<div class="col-second odd-row-color"><code><a href="#m_forwardKinematics" class="member-name-link">m_forwardKinematics</a></code></div>
|
|
<div class="col-last odd-row-color">
|
|
<div class="block">Forward kinematics matrix.</div>
|
|
</div>
|
|
<div class="col-first even-row-color"><code>private final org.ejml.simple.SimpleMatrix</code></div>
|
|
<div class="col-second even-row-color"><code><a href="#m_inverseKinematics" class="member-name-link">m_inverseKinematics</a></code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Inverse kinematics matrix.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color"><code>private final edu.wpi.first.wpilibj.Timer</code></div>
|
|
<div class="col-second odd-row-color"><code><a href="#m_moduleAccelTimer" class="member-name-link">m_moduleAccelTimer</a></code></div>
|
|
<div class="col-last odd-row-color"> </div>
|
|
<div class="col-first even-row-color"><code>private final edu.wpi.first.math.geometry.Translation2d[]</code></div>
|
|
<div class="col-second even-row-color"><code><a href="#m_modules" class="member-name-link">m_modules</a></code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Location of each swerve module in meters.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color"><code>private final <a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[]</code></div>
|
|
<div class="col-second odd-row-color"><code><a href="#m_moduleStates" class="member-name-link">m_moduleStates</a></code></div>
|
|
<div class="col-last odd-row-color">
|
|
<div class="block">Swerve module states.</div>
|
|
</div>
|
|
<div class="col-first even-row-color"><code>private final int</code></div>
|
|
<div class="col-second even-row-color"><code><a href="#m_numModules" class="member-name-link">m_numModules</a></code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Number of swerve modules.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color"><code>private edu.wpi.first.math.kinematics.ChassisSpeeds</code></div>
|
|
<div class="col-second odd-row-color"><code><a href="#m_prevChassisSpeeds" class="member-name-link">m_prevChassisSpeeds</a></code></div>
|
|
<div class="col-last odd-row-color"> </div>
|
|
<div class="col-first even-row-color"><code>private edu.wpi.first.math.geometry.Translation2d</code></div>
|
|
<div class="col-second even-row-color"><code><a href="#m_prevCoR" class="member-name-link">m_prevCoR</a></code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Previous CoR</div>
|
|
</div>
|
|
<div class="col-first odd-row-color"><code>private double</code></div>
|
|
<div class="col-second odd-row-color"><code><a href="#m_prevModuleAccelTime" class="member-name-link">m_prevModuleAccelTime</a></code></div>
|
|
<div class="col-last odd-row-color"> </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(edu.wpi.first.math.geometry.Translation2d...)" class="member-name-link">SwerveKinematics2</a><wbr>(edu.wpi.first.math.geometry.Translation2d... wheelsMeters)</code></div>
|
|
<div class="col-last even-row-color">
|
|
<div class="block">Constructs a swerve drive kinematics object.</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-tab1" role="tab" aria-selected="false" aria-controls="method-summary-table.tabpanel" tabindex="-1" onkeydown="switchTab(event)" onclick="show('method-summary-table', 'method-summary-table-tab1', 3)" class="table-tab">Static 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-tab1 method-summary-table-tab4"><code>static void</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab1 method-summary-table-tab4"><code><a href="#desaturateWheelSpeeds(swervelib.math.SwerveModuleState2%5B%5D,double)" class="member-name-link">desaturateWheelSpeeds</a><wbr>(<a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[] moduleStates,
|
|
double attainableMaxSpeedMetersPerSecond)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab1 method-summary-table-tab4">
|
|
<div class="block">Renormalizes the wheel speeds if any individual speed is above the specified maximum.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab1 method-summary-table-tab4"><code>static void</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab1 method-summary-table-tab4"><code><a href="#desaturateWheelSpeeds(swervelib.math.SwerveModuleState2%5B%5D,edu.wpi.first.math.kinematics.ChassisSpeeds,double,double,double)" class="member-name-link">desaturateWheelSpeeds</a><wbr>(<a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[] moduleStates,
|
|
edu.wpi.first.math.kinematics.ChassisSpeeds currentChassisSpeed,
|
|
double attainableMaxModuleSpeedMetersPerSecond,
|
|
double attainableMaxTranslationalSpeedMetersPerSecond,
|
|
double attainableMaxRotationalVelocityRadiansPerSecond)</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab1 method-summary-table-tab4">
|
|
<div class="block">Renormalizes the wheel speeds if any individual speed is above the specified maximum, as well as getting rid of
|
|
joystick saturation at edges of joystick.</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="#toChassisSpeeds(swervelib.math.SwerveModuleState2...)" class="member-name-link">toChassisSpeeds</a><wbr>(<a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>... wheelStates)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Performs forward kinematics to return the resulting chassis state from the given module states.</div>
|
|
</div>
|
|
<div class="col-first odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[]</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#toSwerveModuleStates(edu.wpi.first.math.kinematics.ChassisSpeeds)" class="member-name-link">toSwerveModuleStates</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">Performs inverse kinematics.</div>
|
|
</div>
|
|
<div class="col-first even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[]</code></div>
|
|
<div class="col-second even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#toSwerveModuleStates(edu.wpi.first.math.kinematics.ChassisSpeeds,edu.wpi.first.math.geometry.Translation2d)" class="member-name-link">toSwerveModuleStates</a><wbr>(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds,
|
|
edu.wpi.first.math.geometry.Translation2d centerOfRotationMeters)</code></div>
|
|
<div class="col-last even-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Performs inverse kinematics to return the module states from a desired chassis velocity.</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.Twist2d</code></div>
|
|
<div class="col-second odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4"><code><a href="#toTwist2d(edu.wpi.first.math.kinematics.SwerveModulePosition...)" class="member-name-link">toTwist2d</a><wbr>(edu.wpi.first.math.kinematics.SwerveModulePosition... wheelDeltas)</code></div>
|
|
<div class="col-last odd-row-color method-summary-table method-summary-table-tab2 method-summary-table-tab4">
|
|
<div class="block">Performs forward kinematics to return the resulting chassis state from the given module states.</div>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
<div class="inherited-list">
|
|
<h3 id="methods-inherited-from-class-edu.wpi.first.math.kinematics.SwerveDriveKinematics">Methods inherited from class edu.wpi.first.math.kinematics.SwerveDriveKinematics</h3>
|
|
<code>desaturateWheelSpeeds, desaturateWheelSpeeds, toChassisSpeeds</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>
|
|
</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="m_inverseKinematics">
|
|
<h3>m_inverseKinematics</h3>
|
|
<div class="member-signature"><span class="modifiers">private final</span> <span class="return-type">org.ejml.simple.SimpleMatrix</span> <span class="element-name">m_inverseKinematics</span></div>
|
|
<div class="block">Inverse kinematics matrix.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_forwardKinematics">
|
|
<h3>m_forwardKinematics</h3>
|
|
<div class="member-signature"><span class="modifiers">private final</span> <span class="return-type">org.ejml.simple.SimpleMatrix</span> <span class="element-name">m_forwardKinematics</span></div>
|
|
<div class="block">Forward kinematics matrix.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="bigInverseKinematics">
|
|
<h3>bigInverseKinematics</h3>
|
|
<div class="member-signature"><span class="modifiers">private final</span> <span class="return-type">org.ejml.simple.SimpleMatrix</span> <span class="element-name">bigInverseKinematics</span></div>
|
|
<div class="block">Second order kinematics inverse matrix.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_numModules">
|
|
<h3>m_numModules</h3>
|
|
<div class="member-signature"><span class="modifiers">private final</span> <span class="return-type">int</span> <span class="element-name">m_numModules</span></div>
|
|
<div class="block">Number of swerve modules.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_modules">
|
|
<h3>m_modules</h3>
|
|
<div class="member-signature"><span class="modifiers">private final</span> <span class="return-type">edu.wpi.first.math.geometry.Translation2d[]</span> <span class="element-name">m_modules</span></div>
|
|
<div class="block">Location of each swerve module in meters.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_moduleStates">
|
|
<h3>m_moduleStates</h3>
|
|
<div class="member-signature"><span class="modifiers">private final</span> <span class="return-type"><a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[]</span> <span class="element-name">m_moduleStates</span></div>
|
|
<div class="block">Swerve module states.</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_moduleAccelTimer">
|
|
<h3>m_moduleAccelTimer</h3>
|
|
<div class="member-signature"><span class="modifiers">private final</span> <span class="return-type">edu.wpi.first.wpilibj.Timer</span> <span class="element-name">m_moduleAccelTimer</span></div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_prevCoR">
|
|
<h3>m_prevCoR</h3>
|
|
<div class="member-signature"><span class="modifiers">private</span> <span class="return-type">edu.wpi.first.math.geometry.Translation2d</span> <span class="element-name">m_prevCoR</span></div>
|
|
<div class="block">Previous CoR</div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_prevChassisSpeeds">
|
|
<h3>m_prevChassisSpeeds</h3>
|
|
<div class="member-signature"><span class="modifiers">private</span> <span class="return-type">edu.wpi.first.math.kinematics.ChassisSpeeds</span> <span class="element-name">m_prevChassisSpeeds</span></div>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="m_prevModuleAccelTime">
|
|
<h3>m_prevModuleAccelTime</h3>
|
|
<div class="member-signature"><span class="modifiers">private</span> <span class="return-type">double</span> <span class="element-name">m_prevModuleAccelTime</span></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>(edu.wpi.first.math.geometry.Translation2d...)">
|
|
<h3>SwerveKinematics2</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="element-name">SwerveKinematics2</span><wbr><span class="parameters">(edu.wpi.first.math.geometry.Translation2d... wheelsMeters)</span></div>
|
|
<div class="block">Constructs a swerve drive kinematics object. This takes in a variable number of wheel locations as Translation2ds.
|
|
The order in which you pass in the wheel locations is the same order that you will receive the module states when
|
|
performing inverse kinematics. It is also expected that you pass in the module states in the same order when
|
|
calling the forward kinematics methods.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>wheelsMeters</code> - The locations of the wheels relative to the physical center of the robot.</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="desaturateWheelSpeeds(swervelib.math.SwerveModuleState2[],double)">
|
|
<h3>desaturateWheelSpeeds</h3>
|
|
<div class="member-signature"><span class="modifiers">public static</span> <span class="return-type">void</span> <span class="element-name">desaturateWheelSpeeds</span><wbr><span class="parameters">(<a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[] moduleStates,
|
|
double attainableMaxSpeedMetersPerSecond)</span></div>
|
|
<div class="block">Renormalizes the wheel speeds if any individual speed is above the specified maximum.
|
|
|
|
<p>Sometimes, after inverse kinematics, the requested speed from one or more modules may be
|
|
above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the
|
|
wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while
|
|
maintaining the ratio of speeds between modules.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>moduleStates</code> - Reference to array of module states. The array will be mutated with the
|
|
normalized speeds!</dd>
|
|
<dd><code>attainableMaxSpeedMetersPerSecond</code> - The absolute max speed that a module can reach.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="desaturateWheelSpeeds(swervelib.math.SwerveModuleState2[],edu.wpi.first.math.kinematics.ChassisSpeeds,double,double,double)">
|
|
<h3>desaturateWheelSpeeds</h3>
|
|
<div class="member-signature"><span class="modifiers">public static</span> <span class="return-type">void</span> <span class="element-name">desaturateWheelSpeeds</span><wbr><span class="parameters">(<a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[] moduleStates,
|
|
edu.wpi.first.math.kinematics.ChassisSpeeds currentChassisSpeed,
|
|
double attainableMaxModuleSpeedMetersPerSecond,
|
|
double attainableMaxTranslationalSpeedMetersPerSecond,
|
|
double attainableMaxRotationalVelocityRadiansPerSecond)</span></div>
|
|
<div class="block">Renormalizes the wheel speeds if any individual speed is above the specified maximum, as well as getting rid of
|
|
joystick saturation at edges of joystick.
|
|
|
|
<p>Sometimes, after inverse kinematics, the requested speed from one or more modules may be
|
|
above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the
|
|
wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while
|
|
maintaining the ratio of speeds between modules.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>moduleStates</code> - Reference to array of module states. The array will be
|
|
mutated with the normalized speeds!</dd>
|
|
<dd><code>currentChassisSpeed</code> - The current speed of the robot</dd>
|
|
<dd><code>attainableMaxModuleSpeedMetersPerSecond</code> - The absolute max speed that a module can reach</dd>
|
|
<dd><code>attainableMaxTranslationalSpeedMetersPerSecond</code> - The absolute max speed that your robot can reach while
|
|
translating</dd>
|
|
<dd><code>attainableMaxRotationalVelocityRadiansPerSecond</code> - The absolute max speed the robot can reach while rotating</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="toSwerveModuleStates(edu.wpi.first.math.kinematics.ChassisSpeeds,edu.wpi.first.math.geometry.Translation2d)">
|
|
<h3>toSwerveModuleStates</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type"><a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[]</span> <span class="element-name">toSwerveModuleStates</span><wbr><span class="parameters">(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds,
|
|
edu.wpi.first.math.geometry.Translation2d centerOfRotationMeters)</span></div>
|
|
<div class="block">Performs inverse kinematics to return the module states from a desired chassis velocity. This method is often used
|
|
to convert joystick values into module speeds and angles.
|
|
|
|
<p>This function also supports variable centers of rotation. During normal operations, the
|
|
center of rotation is usually the same as the physical center of the robot; therefore, the argument is defaulted to
|
|
that use case. However, if you wish to change the center of rotation for evasive maneuvers, vision alignment, or
|
|
for any other use case, you can do so.
|
|
|
|
<p>In the case that the desired chassis speeds are zero (i.e. the robot will be stationary),
|
|
the previously calculated module angle will be maintained.</div>
|
|
<dl class="notes">
|
|
<dt>Overrides:</dt>
|
|
<dd><code>toSwerveModuleStates</code> in class <code>edu.wpi.first.math.kinematics.SwerveDriveKinematics</code></dd>
|
|
<dt>Parameters:</dt>
|
|
<dd><code>chassisSpeeds</code> - The desired chassis speed.</dd>
|
|
<dd><code>centerOfRotationMeters</code> - The center of rotation. For example, if you set the center of rotation at one corner
|
|
of the robot and provide a chassis speed that only has a dtheta component, the robot
|
|
will rotate around that corner.</dd>
|
|
<dt>Returns:</dt>
|
|
<dd>An array containing the module states. Use caution because these module states are not normalized.
|
|
Sometimes, a user input may cause one of the module speeds to go above the attainable max velocity. Use the
|
|
<a href="#desaturateWheelSpeeds(swervelib.math.SwerveModuleState2%5B%5D,double)"><code>DesaturateWheelSpeeds</code></a> function to rectify this issue.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="toSwerveModuleStates(edu.wpi.first.math.kinematics.ChassisSpeeds)">
|
|
<h3>toSwerveModuleStates</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type"><a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>[]</span> <span class="element-name">toSwerveModuleStates</span><wbr><span class="parameters">(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds)</span></div>
|
|
<div class="block">Performs inverse kinematics. See <a href="#toSwerveModuleStates(edu.wpi.first.math.kinematics.ChassisSpeeds,edu.wpi.first.math.geometry.Translation2d)"><code>toSwerveModuleStates(ChassisSpeeds, Translation2d)</code></a> toSwerveModuleStates
|
|
for more information.</div>
|
|
<dl class="notes">
|
|
<dt>Overrides:</dt>
|
|
<dd><code>toSwerveModuleStates</code> in class <code>edu.wpi.first.math.kinematics.SwerveDriveKinematics</code></dd>
|
|
<dt>Parameters:</dt>
|
|
<dd><code>chassisSpeeds</code> - The desired chassis speed.</dd>
|
|
<dt>Returns:</dt>
|
|
<dd>An array containing the module states.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="toChassisSpeeds(swervelib.math.SwerveModuleState2...)">
|
|
<h3>toChassisSpeeds</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">toChassisSpeeds</span><wbr><span class="parameters">(<a href="SwerveModuleState2.html" title="class in swervelib.math">SwerveModuleState2</a>... wheelStates)</span></div>
|
|
<div class="block">Performs forward kinematics to return the resulting chassis state from the given module states. This method is
|
|
often used for odometry -- determining the robot's position on the field using data from the real-world speed and
|
|
angle of each module on the robot.</div>
|
|
<dl class="notes">
|
|
<dt>Parameters:</dt>
|
|
<dd><code>wheelStates</code> - The state of the modules (as a SwerveModuleState type) as measured from respective encoders and
|
|
gyros. The order of the swerve module states should be same as passed into the constructor of
|
|
this class.</dd>
|
|
<dt>Returns:</dt>
|
|
<dd>The resulting chassis speed.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
<li>
|
|
<section class="detail" id="toTwist2d(edu.wpi.first.math.kinematics.SwerveModulePosition...)">
|
|
<h3>toTwist2d</h3>
|
|
<div class="member-signature"><span class="modifiers">public</span> <span class="return-type">edu.wpi.first.math.geometry.Twist2d</span> <span class="element-name">toTwist2d</span><wbr><span class="parameters">(edu.wpi.first.math.kinematics.SwerveModulePosition... wheelDeltas)</span></div>
|
|
<div class="block">Performs forward kinematics to return the resulting chassis state from the given module states. This method is
|
|
often used for odometry -- determining the robot's position on the field using data from the real-world speed and
|
|
angle of each module on the robot.</div>
|
|
<dl class="notes">
|
|
<dt>Overrides:</dt>
|
|
<dd><code>toTwist2d</code> in class <code>edu.wpi.first.math.kinematics.SwerveDriveKinematics</code></dd>
|
|
<dt>Parameters:</dt>
|
|
<dd><code>wheelDeltas</code> - The latest change in position of the modules (as a SwerveModulePosition type) as measured from
|
|
respective encoders and gyros. The order of the swerve module states should be same as passed
|
|
into the constructor of this class.</dd>
|
|
<dt>Returns:</dt>
|
|
<dd>The resulting Twist2d.</dd>
|
|
</dl>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
</li>
|
|
</ul>
|
|
</section>
|
|
<!-- ========= END OF CLASS DATA ========= -->
|
|
</main>
|
|
</div>
|
|
</div>
|
|
</body>
|
|
</html>
|