2023-02-13 14:37:05 -06:00
<!DOCTYPE HTML>
<!-- NewPage -->
< html lang = "en" >
< head >
2023-02-13 17:21:24 -06:00
<!-- Generated by javadoc (11.0.17) on Mon Feb 13 17:20:01 CST 2023 -->
2023-02-13 14:37:05 -06:00
< title > SwerveMath< / title >
< meta http-equiv = "Content-Type" content = "text/html; charset=utf-8" >
< meta name = "dc.created" content = "2023-02-13" >
2023-02-13 15:03:55 -06:00
< 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 >
2023-02-13 14:37:05 -06:00
<!-- [if IE]>
2023-02-13 15:03:55 -06:00
< script type = "text/javascript" src = "../../jquery/jszip-utils/dist/jszip-utils-ie.min.js" > < / script >
2023-02-13 14:37:05 -06:00
<![endif]-->
2023-02-13 15:03:55 -06:00
< script type = "text/javascript" src = "../../jquery/jquery-3.6.0.min.js" > < / script >
< script type = "text/javascript" src = "../../jquery/jquery-ui.min.js" > < / script >
2023-02-13 14:37:05 -06:00
< / head >
< body >
< script type = "text/javascript" > < ! - -
try {
if (location.href.indexOf('is-external=true') == -1) {
parent.document.title="SwerveMath";
}
}
catch(err) {
}
//-->
var data = {"i0":9,"i1":9,"i2":9,"i3":9,"i4":9,"i5":9,"i6":9,"i7":9,"i8":9};
var tabs = {65535:["t0","All Methods"],1:["t1","Static Methods"],8:["t4","Concrete Methods"]};
var altColor = "altColor";
var rowColor = "rowColor";
var tableTab = "tableTab";
var activeTableTab = "activeTableTab";
2023-02-13 15:03:55 -06:00
var pathtoroot = "../../";
2023-02-13 14:37:05 -06:00
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" >
2023-02-13 15:03:55 -06:00
< li > < a href = "../../index.html" > Overview< / a > < / li >
2023-02-13 14:37:05 -06:00
< li > < a href = "package-summary.html" > Package< / a > < / li >
< li class = "navBarCell1Rev" > Class< / li >
< li > < a href = "package-tree.html" > Tree< / a > < / li >
2023-02-13 15:03:55 -06:00
< 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 >
2023-02-13 14:37:05 -06:00
< / ul >
< / div >
< div class = "subNav" >
< ul class = "navList" id = "allclasses_navbar_top" >
2023-02-13 15:03:55 -06:00
< li > < a href = "../../allclasses.html" > All Classes< / a > < / li >
2023-02-13 14:37:05 -06:00
< / 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 > Field | < / 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 > Field | < / 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" >
2023-02-13 15:03:55 -06:00
< div class = "subTitle" > < span class = "packageLabelInType" > Package< / span > < a href = "package-summary.html" > swervelib.math< / a > < / div >
2023-02-13 14:37:05 -06:00
< h2 title = "Class SwerveMath" class = "title" > Class SwerveMath< / 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" >
2023-02-13 15:03:55 -06:00
< li > swervelib.math.SwerveMath< / li >
2023-02-13 14:37:05 -06:00
< / ul >
< / li >
< / ul >
< div class = "description" >
< ul class = "blockList" >
< li class = "blockList" >
< hr >
< pre > public class < span class = "typeNameLabel" > SwerveMath< / 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" > Mathematical functions which pertain to swerve drive.< / div >
< / li >
< / ul >
< / div >
< div class = "summary" >
< ul class = "blockList" >
< li class = "blockList" >
<!-- ======== 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()" > SwerveMath< / a > < / span > ()< / code > < / th >
< td class = "colLast" > < / 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 = "t1" class = "tableTab" > < span > < a href = "javascript:show(1);" > Static 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 > static double< / code > < / td >
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#applyDeadband(double,boolean,double)" > applyDeadband< / a > < / span > ​ (double value,
boolean scaled,
double deadband)< / code > < / th >
< td class = "colLast" >
< div class = "block" > Algebraically apply a deadband using a piece wise function.< / div >
< / td >
< / tr >
< tr id = "i1" class = "rowColor" >
< td class = "colFirst" > < code > private static double< / code > < / td >
2023-02-13 15:03:55 -06:00
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#calcMaxAccel(edu.wpi.first.math.geometry.Rotation2d,double,double,edu.wpi.first.math.geometry.Translation3d,swervelib.parser.SwerveDriveConfiguration)" > calcMaxAccel< / a > < / span > ​ (edu.wpi.first.math.geometry.Rotation2d angle,
2023-02-13 14:37:05 -06:00
double chassisMass,
double robotMass,
edu.wpi.first.math.geometry.Translation3d chassisCenterOfGravity,
2023-02-13 15:03:55 -06:00
< a href = "../parser/SwerveDriveConfiguration.html" title = "class in swervelib.parser" > SwerveDriveConfiguration< / a > config)< / code > < / th >
2023-02-13 14:37:05 -06:00
< td class = "colLast" >
< div class = "block" > Calculates the maximum acceleration allowed in a direction without tipping the robot.< / div >
< / td >
< / tr >
< tr id = "i2" class = "altColor" >
< td class = "colFirst" > < code > static double< / code > < / td >
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#calculateAngleKV(double,double,double)" > calculateAngleKV< / a > < / span > ​ (double optimalVoltage,
double motorFreeSpeedRPM,
double angleGearRatio)< / code > < / th >
< td class = "colLast" >
< div class = "block" > Calculate the angle kV which will be multiplied by the radians per second for the feedforward.< / div >
< / td >
< / tr >
< tr id = "i3" class = "rowColor" >
< td class = "colFirst" > < code > static double< / code > < / td >
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#calculateDegreesPerSteeringRotation(double,double)" > calculateDegreesPerSteeringRotation< / a > < / span > ​ (double angleGearRatio,
double pulsePerRotation)< / code > < / th >
< td class = "colLast" >
< div class = "block" > Calculate the degrees per steering rotation for the integrated encoder.< / div >
< / td >
< / tr >
< tr id = "i4" class = "altColor" >
< td class = "colFirst" > < code > static double< / code > < / td >
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#calculateMaxAcceleration(double)" > calculateMaxAcceleration< / a > < / span > ​ (double cof)< / code > < / th >
< td class = "colLast" >
< div class = "block" > Calculate the practical maximum acceleration of the robot using the wheel coefficient of friction.< / div >
< / td >
< / tr >
< tr id = "i5" class = "rowColor" >
< td class = "colFirst" > < code > static double< / code > < / td >
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#calculateMaxAcceleration(double,double,double,double,double)" > calculateMaxAcceleration< / a > < / span > ​ (double stallTorqueNm,
double gearRatio,
double moduleCount,
double wheelDiameter,
double robotMass)< / code > < / th >
< td class = "colLast" >
< div class = "block" > Calculate the maximum theoretical acceleration without friction.< / div >
< / td >
< / tr >
< tr id = "i6" class = "altColor" >
< td class = "colFirst" > < code > static double< / code > < / td >
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#calculateMaxAngularVelocity(double,double,double)" > calculateMaxAngularVelocity< / a > < / span > ​ (double maxSpeed,
double furthestModuleX,
double furthestModuleY)< / code > < / th >
< td class = "colLast" >
< div class = "block" > Calculate the maximum angular velocity.< / div >
< / td >
< / tr >
< tr id = "i7" class = "rowColor" >
< td class = "colFirst" > < code > static double< / code > < / td >
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#calculateMetersPerRotation(double,double,double)" > calculateMetersPerRotation< / a > < / span > ​ (double wheelDiameter,
double driveGearRatio,
double pulsePerRotation)< / code > < / th >
< td class = "colLast" >
< div class = "block" > Calculate the meters per rotation for the integrated encoder.< / div >
< / td >
< / tr >
< tr id = "i8" class = "altColor" >
< td class = "colFirst" > < code > static edu.wpi.first.math.geometry.Translation2d< / code > < / td >
2023-02-13 15:03:55 -06:00
< th class = "colSecond" scope = "row" > < code > < span class = "memberNameLink" > < a href = "#limitVelocity(edu.wpi.first.math.geometry.Translation2d,edu.wpi.first.math.kinematics.ChassisSpeeds,edu.wpi.first.math.geometry.Pose2d,double,double,double,edu.wpi.first.math.geometry.Translation3d,swervelib.parser.SwerveDriveConfiguration)" > limitVelocity< / a > < / span > ​ (edu.wpi.first.math.geometry.Translation2d commandedVelocity,
2023-02-13 14:37:05 -06:00
edu.wpi.first.math.kinematics.ChassisSpeeds fieldVelocity,
edu.wpi.first.math.geometry.Pose2d robotPose,
double loopTime,
double chassisMass,
double robotMass,
edu.wpi.first.math.geometry.Translation3d chassisCenterOfGravity,
2023-02-13 15:03:55 -06:00
< a href = "../parser/SwerveDriveConfiguration.html" title = "class in swervelib.parser" > SwerveDriveConfiguration< / a > config)< / code > < / th >
2023-02-13 14:37:05 -06:00
< td class = "colLast" >
< div class = "block" > Limits a commanded velocity to prevent exceeding the maximum acceleration given by
2023-02-13 15:03:55 -06:00
< a href = "#calcMaxAccel(edu.wpi.first.math.geometry.Rotation2d,double,double,edu.wpi.first.math.geometry.Translation3d,swervelib.parser.SwerveDriveConfiguration)" > < code > calcMaxAccel(Rotation2d, double, double, Translation3d, SwerveDriveConfiguration)< / code > < / a > .< / div >
2023-02-13 14:37:05 -06:00
< / 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" >
<!-- ========= CONSTRUCTOR DETAIL ======== -->
< section >
< ul class = "blockList" >
< li class = "blockList" > < a id = "constructor.detail" >
<!-- -->
< / a >
< h3 > Constructor Detail< / h3 >
< a id = "<init>()" >
<!-- -->
< / a >
< ul class = "blockListLast" >
< li class = "blockList" >
< h4 > SwerveMath< / h4 >
< pre > public SwerveMath()< / pre >
< / 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 = "calculateAngleKV(double,double,double)" >
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > calculateAngleKV< / h4 >
< pre class = "methodSignature" > public static double calculateAngleKV​ (double optimalVoltage,
double motorFreeSpeedRPM,
double angleGearRatio)< / pre >
< div class = "block" > Calculate the angle kV which will be multiplied by the radians per second for the feedforward. Volt * seconds /
degree < => (maxVolts) / (maxSpeed)< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > optimalVoltage< / code > - Optimal voltage to use when calculating the angle kV.< / dd >
< dd > < code > motorFreeSpeedRPM< / code > - Motor free speed in Rotations per Minute.< / dd >
< dd > < code > angleGearRatio< / code > - Angle gear ratio, the amount of times the motor as to turn for the wheel rotation.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > angle kV for feedforward.< / dd >
< / dl >
< / li >
< / ul >
< a id = "calculateMetersPerRotation(double,double,double)" >
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > calculateMetersPerRotation< / h4 >
< pre class = "methodSignature" > public static double calculateMetersPerRotation​ (double wheelDiameter,
double driveGearRatio,
double pulsePerRotation)< / pre >
< div class = "block" > Calculate the meters per rotation for the integrated encoder. Calculation: 4in diameter wheels * pi [circumfrence]
/ gear ratio.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > wheelDiameter< / code > - Wheel diameter in meters.< / dd >
< dd > < code > driveGearRatio< / code > - The gear ratio of the drive motor.< / dd >
< dd > < code > pulsePerRotation< / code > - The number of encoder pulses per rotation. 1 if using an integrated encoder.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > Meters per rotation for the drive motor.< / dd >
< / dl >
< / li >
< / ul >
< a id = "applyDeadband(double,boolean,double)" >
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > applyDeadband< / h4 >
< pre class = "methodSignature" > public static double applyDeadband​ (double value,
boolean scaled,
double deadband)< / pre >
< div class = "block" > Algebraically apply a deadband using a piece wise function.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > value< / code > - value to apply deadband to.< / dd >
< dd > < code > scaled< / code > - Use algebra to determine deadband by starting the value at 0 past deadband.< / dd >
< dd > < code > deadband< / code > - The deadbnad to apply.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > Value with deadband applied.< / dd >
< / dl >
< / li >
< / ul >
< a id = "calculateDegreesPerSteeringRotation(double,double)" >
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > calculateDegreesPerSteeringRotation< / h4 >
< pre class = "methodSignature" > public static double calculateDegreesPerSteeringRotation​ (double angleGearRatio,
double pulsePerRotation)< / pre >
< div class = "block" > Calculate the degrees per steering rotation for the integrated encoder. Encoder conversion values. Drive converts
motor rotations to linear wheel distance and steering converts motor rotations to module azimuth.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > angleGearRatio< / code > - The gear ratio of the steering motor.< / dd >
< dd > < code > pulsePerRotation< / code > - The number of pulses in a complete rotation for the encoder, 1 if integrated.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > Degrees per steering rotation for the angle motor.< / dd >
< / dl >
< / li >
< / ul >
< a id = "calculateMaxAngularVelocity(double,double,double)" >
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > calculateMaxAngularVelocity< / h4 >
< pre class = "methodSignature" > public static double calculateMaxAngularVelocity​ (double maxSpeed,
double furthestModuleX,
double furthestModuleY)< / pre >
< div class = "block" > Calculate the maximum angular velocity.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > maxSpeed< / code > - Max speed of the robot in meters per second.< / dd >
< dd > < code > furthestModuleX< / code > - X of the furthest module in meters.< / dd >
< dd > < code > furthestModuleY< / code > - Y of the furthest module in meters.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > Maximum angular velocity in rad/s.< / dd >
< / dl >
< / li >
< / ul >
< a id = "calculateMaxAcceleration(double)" >
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > calculateMaxAcceleration< / h4 >
< pre class = "methodSignature" > public static double calculateMaxAcceleration​ (double cof)< / pre >
< div class = "block" > Calculate the practical maximum acceleration of the robot using the wheel coefficient of friction.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > cof< / code > - Coefficient of Friction of the wheel grip tape.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > Practical maximum acceleration in m/s/s.< / dd >
< / dl >
< / li >
< / ul >
< a id = "calculateMaxAcceleration(double,double,double,double,double)" >
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > calculateMaxAcceleration< / h4 >
< pre class = "methodSignature" > public static double calculateMaxAcceleration​ (double stallTorqueNm,
double gearRatio,
double moduleCount,
double wheelDiameter,
double robotMass)< / pre >
< div class = "block" > Calculate the maximum theoretical acceleration without friction.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > stallTorqueNm< / code > - Stall torque of driving motor in nM.< / dd >
< dd > < code > gearRatio< / code > - Gear ratio for driving motor number of motor rotations until one wheel rotation.< / dd >
< dd > < code > moduleCount< / code > - Number of swerve modules.< / dd >
< dd > < code > wheelDiameter< / code > - Wheel diameter in meters.< / dd >
< dd > < code > robotMass< / code > - Mass of the robot in kg.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > Theoretical maximum acceleration in m/s/s.< / dd >
< / dl >
< / li >
< / ul >
2023-02-13 15:03:55 -06:00
< a id = "calcMaxAccel(edu.wpi.first.math.geometry.Rotation2d,double,double,edu.wpi.first.math.geometry.Translation3d,swervelib.parser.SwerveDriveConfiguration)" >
2023-02-13 14:37:05 -06:00
<!-- -->
< / a >
< ul class = "blockList" >
< li class = "blockList" >
< h4 > calcMaxAccel< / h4 >
< pre class = "methodSignature" > private static double calcMaxAccel​ (edu.wpi.first.math.geometry.Rotation2d angle,
double chassisMass,
double robotMass,
edu.wpi.first.math.geometry.Translation3d chassisCenterOfGravity,
2023-02-13 15:03:55 -06:00
< a href = "../parser/SwerveDriveConfiguration.html" title = "class in swervelib.parser" > SwerveDriveConfiguration< / a > config)< / pre >
2023-02-13 14:37:05 -06:00
< div class = "block" > Calculates the maximum acceleration allowed in a direction without tipping the robot. Reads arm position from
NetworkTables and is passed the direction in question.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > angle< / code > - The direction in which to calculate max acceleration, as a Rotation2d. Note that this
is robot-relative.< / dd >
< dd > < code > chassisMass< / code > - Chassis mass in kg. (The weight of just the chassis not anything else)< / dd >
< dd > < code > robotMass< / code > - The weight of the robot in kg. (Including manipulators, etc).< / dd >
< dd > < code > chassisCenterOfGravity< / code > - Chassis center of gravity.< / dd >
< dd > < code > config< / code > - The swerve drive configuration.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > Maximum acceleration allowed in the robot direction.< / dd >
< / dl >
< / li >
< / ul >
2023-02-13 15:03:55 -06:00
< a id = "limitVelocity(edu.wpi.first.math.geometry.Translation2d,edu.wpi.first.math.kinematics.ChassisSpeeds,edu.wpi.first.math.geometry.Pose2d,double,double,double,edu.wpi.first.math.geometry.Translation3d,swervelib.parser.SwerveDriveConfiguration)" >
2023-02-13 14:37:05 -06:00
<!-- -->
< / a >
< ul class = "blockListLast" >
< li class = "blockList" >
< h4 > limitVelocity< / h4 >
< pre class = "methodSignature" > public static edu.wpi.first.math.geometry.Translation2d limitVelocity​ (edu.wpi.first.math.geometry.Translation2d commandedVelocity,
edu.wpi.first.math.kinematics.ChassisSpeeds fieldVelocity,
edu.wpi.first.math.geometry.Pose2d robotPose,
double loopTime,
double chassisMass,
double robotMass,
edu.wpi.first.math.geometry.Translation3d chassisCenterOfGravity,
2023-02-13 15:03:55 -06:00
< a href = "../parser/SwerveDriveConfiguration.html" title = "class in swervelib.parser" > SwerveDriveConfiguration< / a > config)< / pre >
2023-02-13 14:37:05 -06:00
< div class = "block" > Limits a commanded velocity to prevent exceeding the maximum acceleration given by
2023-02-13 15:03:55 -06:00
< a href = "#calcMaxAccel(edu.wpi.first.math.geometry.Rotation2d,double,double,edu.wpi.first.math.geometry.Translation3d,swervelib.parser.SwerveDriveConfiguration)" > < code > calcMaxAccel(Rotation2d, double, double, Translation3d, SwerveDriveConfiguration)< / code > < / a > . Note that
2023-02-13 14:37:05 -06:00
this takes and returns field-relative velocities.< / div >
< dl >
< dt > < span class = "paramLabel" > Parameters:< / span > < / dt >
< dd > < code > commandedVelocity< / code > - The desired velocity< / dd >
< dd > < code > fieldVelocity< / code > - The velocity of the robot within a field relative state.< / dd >
< dd > < code > robotPose< / code > - The current pose of the robot.< / dd >
< dd > < code > loopTime< / code > - The time it takes to update the velocity in seconds. < b > Note: this should include the
100ms that it takes for a SparkMax velocity to update.< / b > < / dd >
< dd > < code > chassisMass< / code > - Chassis mass in kg. (The weight of just the chassis not anything else)< / dd >
< dd > < code > robotMass< / code > - The weight of the robot in kg. (Including manipulators, etc).< / dd >
< dd > < code > chassisCenterOfGravity< / code > - Chassis center of gravity.< / dd >
< dd > < code > config< / code > - The swerve drive configuration.< / dd >
< dt > < span class = "returnLabel" > Returns:< / span > < / dt >
< dd > The limited velocity. This is either the commanded velocity, if attainable, or the closest attainable
velocity.< / dd >
< / dl >
< / 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" >
2023-02-13 15:03:55 -06:00
< li > < a href = "../../index.html" > Overview< / a > < / li >
2023-02-13 14:37:05 -06:00
< li > < a href = "package-summary.html" > Package< / a > < / li >
< li class = "navBarCell1Rev" > Class< / li >
< li > < a href = "package-tree.html" > Tree< / a > < / li >
2023-02-13 15:03:55 -06:00
< 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 >
2023-02-13 14:37:05 -06:00
< / ul >
< / div >
< div class = "subNav" >
< ul class = "navList" id = "allclasses_navbar_bottom" >
2023-02-13 15:03:55 -06:00
< li > < a href = "../../allclasses.html" > All Classes< / a > < / li >
2023-02-13 14:37:05 -06:00
< / 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 > Field | < / 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 > Field | < / 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 >