();
+}
+#endif
diff --git a/wpilibcExamples/src/main/cpp/snippets/snippets.json b/wpilibcExamples/src/main/cpp/snippets/snippets.json
index c38c0587e7..1fa789b2c7 100644
--- a/wpilibcExamples/src/main/cpp/snippets/snippets.json
+++ b/wpilibcExamples/src/main/cpp/snippets/snippets.json
@@ -146,5 +146,15 @@
],
"foldername": "OnboardIMU",
"gradlebase": "cpp"
+ },
+ {
+ "name": "ProfiledPIDFeedforward",
+ "description": "Snippets of ProfiledPIDController with feedforward for frc-docs.",
+ "tags": [
+ "PID",
+ "Profiled PID"
+ ],
+ "foldername": "ProfiledPIDFeedforward",
+ "gradlebase": "cpp"
}
]
diff --git a/wpilibj/src/generate/pwm_motor_controllers.json b/wpilibj/src/generate/pwm_motor_controllers.json
index ee7433617e..cb324973aa 100644
--- a/wpilibj/src/generate/pwm_motor_controllers.json
+++ b/wpilibj/src/generate/pwm_motor_controllers.json
@@ -1,30 +1,4 @@
[
- {
- "name": "DMC60",
- "Manufacturer": "Digilent",
- "DisplayName": "DMC 60",
- "ResourceName": "DigilentDMC60",
- "pulse_width_ms": {
- "max": 2.004,
- "deadbandMax": 1.520,
- "center": 1.500,
- "deadbandMin": 1.480,
- "min": 0.997
- }
- },
- {
- "name": "Jaguar",
- "Manufacturer": "Luminary Micro / Vex Robotics",
- "DisplayName": "Jaguar",
- "ResourceName": "Jaguar",
- "pulse_width_ms": {
- "max": 2.310,
- "deadbandMax": 1.550,
- "center": 1.507,
- "deadbandMin": 1.454,
- "min": 0.697
- }
- },
{
"name": "PWMSparkFlex",
"Manufacturer": "REV Robotics",
@@ -103,19 +77,6 @@
"min": 0.997
}
},
- {
- "name": "SD540",
- "Manufacturer": "Mindsensors",
- "DisplayName": "SD540",
- "ResourceName": "MindsensorsSD540",
- "pulse_width_ms": {
- "max": 2.05,
- "deadbandMax": 1.55,
- "center": 1.50,
- "deadbandMin": 1.44,
- "min": 0.94
- }
- },
{
"name": "Spark",
"Manufacturer": "REV Robotics",
@@ -142,20 +103,6 @@
"min": 0.989
}
},
- {
- "name": "Victor",
- "Manufacturer": "Vex Robotics",
- "DisplayName": "Victor 888",
- "ResourceName": "Victor",
- "OutputPeriod": 10,
- "pulse_width_ms": {
- "max": 2.027,
- "deadbandMax": 1.525,
- "center": 1.507,
- "deadbandMin": 1.490,
- "min": 1.026
- }
- },
{
"name": "VictorSP",
"Manufacturer": "Vex Robotics",
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java
deleted file mode 100644
index d105848017..0000000000
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
-
-package edu.wpi.first.wpilibj.motorcontrol;
-
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.wpilibj.PWM;
-
-/**
- * Digilent DMC 60 Motor Controller.
- *
- * Note that the DMC 60 uses the following bounds for PWM values. These values should work
- * reasonably well for most controllers, but if users experience issues such as asymmetric behavior
- * around the deadband or inability to saturate the controller in either direction, calibration is
- * recommended. The calibration procedure can be found in the DMC 60 User Manual available from
- * Digilent.
- *
- *
- * - 2.004ms = full "forward"
- *
- 1.520ms = the "high end" of the deadband range
- *
- 1.500ms = center of the deadband range (off)
- *
- 1.480ms = the "low end" of the deadband range
- *
- 0.997ms = full "reverse"
- *
- */
-public class DMC60 extends PWMMotorController {
- /**
- * Constructor.
- *
- * @param channel The PWM channel that the DMC 60 is attached to. 0-9 are on-board, 10-19
- * are on the MXP port
- */
- @SuppressWarnings("this-escape")
- public DMC60(final int channel) {
- super("DMC60", channel);
-
- setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
- m_pwm.setOutputPeriod(PWM.OutputPeriod.k5Ms);
- setSpeed(0.0);
-
- HAL.reportUsage("IO", getChannel(), "DigilentDMC60");
- }
-}
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java
deleted file mode 100644
index 48b5fc50f7..0000000000
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
-
-package edu.wpi.first.wpilibj.motorcontrol;
-
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.wpilibj.PWM;
-
-/**
- * Luminary Micro / Vex Robotics Jaguar Motor Controller.
- *
- * Note that the Jaguar uses the following bounds for PWM values. These values should work
- * reasonably well for most controllers, but if users experience issues such as asymmetric behavior
- * around the deadband or inability to saturate the controller in either direction, calibration is
- * recommended. The calibration procedure can be found in the Jaguar User Manual available from
- * Luminary Micro / Vex Robotics.
- *
- *
- * - 2.310ms = full "forward"
- *
- 1.550ms = the "high end" of the deadband range
- *
- 1.507ms = center of the deadband range (off)
- *
- 1.454ms = the "low end" of the deadband range
- *
- 0.697ms = full "reverse"
- *
- */
-public class Jaguar extends PWMMotorController {
- /**
- * Constructor.
- *
- * @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19
- * are on the MXP port
- */
- @SuppressWarnings("this-escape")
- public Jaguar(final int channel) {
- super("Jaguar", channel);
-
- setBoundsMicroseconds(2310, 1550, 1507, 1454, 697);
- m_pwm.setOutputPeriod(PWM.OutputPeriod.k5Ms);
- setSpeed(0.0);
-
- HAL.reportUsage("IO", getChannel(), "Jaguar");
- }
-}
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java
deleted file mode 100644
index 927edfd46f..0000000000
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
-
-package edu.wpi.first.wpilibj.motorcontrol;
-
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.wpilibj.PWM;
-
-/**
- * Mindsensors SD540 Motor Controller.
- *
- * Note that the SD540 uses the following bounds for PWM values. These values should work
- * reasonably well for most controllers, but if users experience issues such as asymmetric behavior
- * around the deadband or inability to saturate the controller in either direction, calibration is
- * recommended. The calibration procedure can be found in the SD540 User Manual available from
- * Mindsensors.
- *
- *
- * - 2.050ms = full "forward"
- *
- 1.550ms = the "high end" of the deadband range
- *
- 1.500ms = center of the deadband range (off)
- *
- 1.440ms = the "low end" of the deadband range
- *
- 0.940ms = full "reverse"
- *
- */
-public class SD540 extends PWMMotorController {
- /**
- * Constructor.
- *
- * @param channel The PWM channel that the SD540 is attached to. 0-9 are on-board, 10-19
- * are on the MXP port
- */
- @SuppressWarnings("this-escape")
- public SD540(final int channel) {
- super("SD540", channel);
-
- setBoundsMicroseconds(2050, 1550, 1500, 1440, 940);
- m_pwm.setOutputPeriod(PWM.OutputPeriod.k5Ms);
- setSpeed(0.0);
-
- HAL.reportUsage("IO", getChannel(), "MindsensorsSD540");
- }
-}
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java
deleted file mode 100644
index 3e9911982c..0000000000
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
-
-package edu.wpi.first.wpilibj.motorcontrol;
-
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.wpilibj.PWM;
-
-/**
- * Vex Robotics Victor 888 Motor Controller.
- *
- * Note that the Victor 888 uses the following bounds for PWM values. These values should work
- * reasonably well for most controllers, but if users experience issues such as asymmetric behavior
- * around the deadband or inability to saturate the controller in either direction, calibration is
- * recommended. The calibration procedure can be found in the Victor 888 User Manual available from
- * Vex Robotics.
- *
- *
- * - 2.027ms = full "forward"
- *
- 1.525ms = the "high end" of the deadband range
- *
- 1.507ms = center of the deadband range (off)
- *
- 1.490ms = the "low end" of the deadband range
- *
- 1.026ms = full "reverse"
- *
- */
-public class Victor extends PWMMotorController {
- /**
- * Constructor.
- *
- * @param channel The PWM channel that the Victor 888 is attached to. 0-9 are on-board, 10-19
- * are on the MXP port
- */
- @SuppressWarnings("this-escape")
- public Victor(final int channel) {
- super("Victor", channel);
-
- setBoundsMicroseconds(2027, 1525, 1507, 1490, 1026);
- m_pwm.setOutputPeriod(PWM.OutputPeriod.k10Ms);
- setSpeed(0.0);
-
- HAL.reportUsage("IO", getChannel(), "Victor");
- }
-}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
index e077440d7e..663611d3f2 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
@@ -4,9 +4,12 @@
package edu.wpi.first.wpilibj;
+import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
import edu.wpi.first.hal.NotifierJNI;
+import edu.wpi.first.units.measure.Frequency;
+import edu.wpi.first.units.measure.Time;
import java.util.concurrent.atomic.AtomicInteger;
import java.util.concurrent.locks.ReentrantLock;
@@ -186,6 +189,15 @@ public class Notifier implements AutoCloseable {
}
}
+ /**
+ * Run the callback once after the given delay.
+ *
+ * @param delay Time to wait before the callback is called.
+ */
+ public void startSingle(Time delay) {
+ startSingle(delay.in(Seconds));
+ }
+
/**
* Run the callback periodically with the given period.
*
@@ -207,6 +219,32 @@ public class Notifier implements AutoCloseable {
}
}
+ /**
+ * Run the callback periodically with the given period.
+ *
+ * The user-provided callback should be written so that it completes before the next time it's
+ * scheduled to run.
+ *
+ * @param period Period after which to call the callback starting one period after the call to
+ * this method.
+ */
+ public void startPeriodic(Time period) {
+ startPeriodic(period.in(Seconds));
+ }
+
+ /**
+ * Run the callback periodically with the given frequency.
+ *
+ *
The user-provided callback should be written so that it completes before the next time it's
+ * scheduled to run.
+ *
+ * @param frequency Frequency at which to call the callback, starting one period after the call to
+ * this method.
+ */
+ public void startPeriodic(Frequency frequency) {
+ startPeriodic(frequency.asPeriod());
+ }
+
/**
* Stop further callback invocations.
*
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
index 685bcfc982..494a6d4371 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
@@ -9,6 +9,7 @@ import static edu.wpi.first.units.Units.Seconds;
import edu.wpi.first.hal.DriverStationJNI;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.hal.NotifierJNI;
+import edu.wpi.first.units.measure.Frequency;
import edu.wpi.first.units.measure.Time;
import java.util.PriorityQueue;
@@ -82,7 +83,7 @@ public class TimedRobot extends IterativeRobotBase {
/**
* Constructor for TimedRobot.
*
- * @param period Period in seconds.
+ * @param period The period of the robot loop function.
*/
protected TimedRobot(double period) {
super(period);
@@ -93,6 +94,24 @@ public class TimedRobot extends IterativeRobotBase {
HAL.reportUsage("Framework", "TimedRobot");
}
+ /**
+ * Constructor for TimedRobot.
+ *
+ * @param period The period of the robot loop function.
+ */
+ protected TimedRobot(Time period) {
+ this(period.in(Seconds));
+ }
+
+ /**
+ * Constructor for TimedRobot.
+ *
+ * @param frequency The frequency of the robot loop function.
+ */
+ protected TimedRobot(Frequency frequency) {
+ this(frequency.asPeriod());
+ }
+
@Override
public void close() {
NotifierJNI.stopNotifier(m_notifier);
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
index fb92dc52a8..af55a43208 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
@@ -4,6 +4,10 @@
package edu.wpi.first.wpilibj;
+import static edu.wpi.first.units.Units.Seconds;
+
+import edu.wpi.first.units.measure.Time;
+
/**
* A timer class.
*
@@ -46,10 +50,20 @@ public class Timer {
}
/**
- * Pause the thread for a specified time. Pause the execution of the thread for a specified period
- * of time given in seconds. Motors will continue to run at their last assigned values, and
- * sensors will continue to update. Only the task containing the wait will pause until the wait
- * time is expired.
+ * Pause the execution of the thread for a specified period of time. Motors will continue to run
+ * at their last assigned values, and sensors will continue to update. Only the task containing
+ * the wait will pause until the wait time is expired.
+ *
+ * @param period Length of time to pause
+ */
+ public static void delay(final Time period) {
+ delay(period.in(Seconds));
+ }
+
+ /**
+ * Pause the execution of the thread for a specified period of time given in seconds. Motors will
+ * continue to run at their last assigned values, and sensors will continue to update. Only the
+ * task containing the wait will pause until the wait time is expired.
*
* @param seconds Length of time to pause
*/
@@ -137,7 +151,17 @@ public class Timer {
/**
* Check if the period specified has passed.
*
- * @param seconds The period to check.
+ * @param period The period to check.
+ * @return Whether the period has passed.
+ */
+ public boolean hasElapsed(Time period) {
+ return hasElapsed(period.in(Seconds));
+ }
+
+ /**
+ * Check if the period specified has passed.
+ *
+ * @param seconds The period to check in seconds.
* @return Whether the period has passed.
*/
public boolean hasElapsed(double seconds) {
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
index 2023f040fa..00b9085331 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
@@ -4,7 +4,10 @@
package edu.wpi.first.wpilibj;
+import static edu.wpi.first.units.Units.Seconds;
+
import edu.wpi.first.hal.NotifierJNI;
+import edu.wpi.first.units.measure.Time;
import java.io.Closeable;
import java.util.PriorityQueue;
import java.util.concurrent.locks.ReentrantLock;
@@ -55,6 +58,16 @@ public class Watchdog implements Closeable, Comparable {
m_tracer = new Tracer();
}
+ /**
+ * Watchdog constructor.
+ *
+ * @param timeout The watchdog's timeout with microsecond resolution.
+ * @param callback This function is called when the timeout expires.
+ */
+ public Watchdog(Time timeout, Runnable callback) {
+ this(timeout.in(Seconds), callback);
+ }
+
@Override
public void close() {
disable();
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
index 9369b7811a..01c0b8ee3b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
@@ -4,9 +4,11 @@
package edu.wpi.first.wpilibj.event;
+import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
import edu.wpi.first.math.filter.Debouncer;
+import edu.wpi.first.units.measure.Time;
import java.util.concurrent.atomic.AtomicBoolean;
import java.util.function.BiFunction;
import java.util.function.BooleanSupplier;
@@ -167,7 +169,18 @@ public class BooleanEvent implements BooleanSupplier {
* Creates a new debounced event from this event - it will become active when this event has been
* active for longer than the specified period.
*
- * @param seconds The debounce period.
+ * @param period The debounce period.
+ * @return The debounced event (rising edges debounced only).
+ */
+ public BooleanEvent debounce(Time period) {
+ return debounce(period.in(Seconds));
+ }
+
+ /**
+ * Creates a new debounced event from this event - it will become active when this event has been
+ * active for longer than the specified period.
+ *
+ * @param seconds The debounce period in seconds.
* @return The debounced event (rising edges debounced only).
*/
public BooleanEvent debounce(double seconds) {
@@ -178,7 +191,19 @@ public class BooleanEvent implements BooleanSupplier {
* Creates a new debounced event from this event - it will become active when this event has been
* active for longer than the specified period.
*
- * @param seconds The debounce period.
+ * @param period The debounce period.
+ * @param type The debounce type.
+ * @return The debounced event.
+ */
+ public BooleanEvent debounce(Time period, Debouncer.DebounceType type) {
+ return debounce(period.in(Seconds), type);
+ }
+
+ /**
+ * Creates a new debounced event from this event - it will become active when this event has been
+ * active for longer than the specified period.
+ *
+ * @param seconds The debounce period in seconds.
* @param type The debounce type.
* @return The debounced event.
*/
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
index 749e2f843e..4a056c0fd4 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
@@ -4,11 +4,14 @@
package edu.wpi.first.wpilibj.smartdashboard;
+import static edu.wpi.first.units.Units.Meters;
+
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.networktables.NTSendable;
import edu.wpi.first.networktables.NTSendableBuilder;
import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.units.measure.Distance;
import edu.wpi.first.util.sendable.SendableRegistry;
import java.util.ArrayList;
import java.util.List;
@@ -66,6 +69,17 @@ public class Field2d implements NTSendable, AutoCloseable {
m_objects.get(0).setPose(x, y, rotation);
}
+ /**
+ * Set the robot pose from x, y, and rotation.
+ *
+ * @param x X location
+ * @param y Y location
+ * @param rotation rotation
+ */
+ public synchronized void setRobotPose(Distance x, Distance y, Rotation2d rotation) {
+ m_objects.get(0).setPose(x.in(Meters), y.in(Meters), rotation);
+ }
+
/**
* Get the robot pose.
*
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
index c943a1d317..d508afed2c 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
@@ -4,11 +4,14 @@
package edu.wpi.first.wpilibj.smartdashboard;
+import static edu.wpi.first.units.Units.Meters;
+
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.networktables.DoubleArrayEntry;
+import edu.wpi.first.units.measure.Distance;
import java.util.ArrayList;
import java.util.Collections;
import java.util.List;
@@ -51,6 +54,17 @@ public class FieldObject2d implements AutoCloseable {
setPose(new Pose2d(x, y, rotation));
}
+ /**
+ * Set the pose from x, y, and rotation.
+ *
+ * @param x X location
+ * @param y Y location
+ * @param rotation rotation
+ */
+ public synchronized void setPose(Distance x, Distance y, Rotation2d rotation) {
+ setPose(new Pose2d(x.in(Meters), y.in(Meters), rotation));
+ }
+
/**
* Get the pose.
*
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Main.java
new file mode 100644
index 0000000000..1fc6c2ec2b
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Main.java
@@ -0,0 +1,25 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.snippets.profiledpidfeedforward;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
+public final class Main {
+ private Main() {}
+
+ /**
+ * Main initialization function. Do not perform any initialization here.
+ *
+ * If you change your main robot class, change the parameter type.
+ */
+ public static void main(String... args) {
+ RobotBase.startRobot(Robot::new);
+ }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java
new file mode 100644
index 0000000000..9f30e73e5f
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java
@@ -0,0 +1,51 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj.snippets.profiledpidfeedforward;
+
+import edu.wpi.first.math.controller.ProfiledPIDController;
+import edu.wpi.first.math.controller.SimpleMotorFeedforward;
+import edu.wpi.first.math.trajectory.TrapezoidProfile;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
+
+/**
+ * ProfiledPIDController with feedforward snippets for frc-docs.
+ * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/controllers/profiled-pidcontroller.html
+ */
+public class Robot extends TimedRobot {
+ private final ProfiledPIDController m_controller =
+ new ProfiledPIDController(1.0, 0.0, 0.0, new TrapezoidProfile.Constraints(5.0, 10.0));
+ private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(0.5, 1.5, 0.3);
+ private final Encoder m_encoder = new Encoder(0, 1);
+ private final PWMSparkMax m_motor = new PWMSparkMax(0);
+
+ double m_lastSpeed;
+
+ /** Called once at the beginning of the robot program. */
+ public Robot() {
+ m_encoder.setDistancePerPulse(1.0 / 256.0);
+ }
+
+ /**
+ * Controls a simple motor's position using a SimpleMotorFeedforward and a ProfiledPIDController.
+ *
+ * @param goalPosition the desired position
+ */
+ public void goToPosition(double goalPosition) {
+ double pidVal = m_controller.calculate(m_encoder.getDistance(), goalPosition);
+ m_motor.setVoltage(
+ pidVal
+ + m_feedforward.calculateWithVelocities(
+ m_lastSpeed, m_controller.getSetpoint().velocity));
+ m_lastSpeed = m_controller.getSetpoint().velocity;
+ }
+
+ @Override
+ public void teleopPeriodic() {
+ // Example usage: move to position 10.0
+ goToPosition(10.0);
+ }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json
index 3c5054f5a2..556af19525 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json
@@ -160,5 +160,16 @@
"foldername": "onboardimu",
"gradlebase": "java",
"mainclass": "Main"
+ },
+ {
+ "name": "ProfiledPIDFeedforward",
+ "description": "Snippets of ProfiledPIDController with feedforward for frc-docs.",
+ "tags": [
+ "PID",
+ "Profiled PID"
+ ],
+ "foldername": "profiledpidfeedforward",
+ "gradlebase": "java",
+ "mainclass": "Robot"
}
]
diff --git a/wpimath/.styleguide b/wpimath/.styleguide
index 7f3f80be8f..1ef7b426ef 100644
--- a/wpimath/.styleguide
+++ b/wpimath/.styleguide
@@ -19,8 +19,6 @@ generatedFileExclude {
src/main/native/include/unsupported/
src/main/native/thirdparty/
src/test/native/cpp/UnitsTest\.cpp$
- src/test/native/cpp/drake/
- src/test/native/include/drake/
src/generated/main/java/edu/wpi/first/math/proto
src/generated/main/native/cpp
@@ -43,6 +41,7 @@ includeOtherLibs {
^fmt/
^gcem/
^gtest/
+ ^sleipnir/
^unsupported/
^wpi/
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java
index 9fb001221c..6de79523a0 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java
@@ -308,6 +308,42 @@ public class DCMotor implements ProtobufSerializable, StructSerializable {
12, 9.37, 483, 2, Units.rotationsPerMinuteToRadiansPerSecond(5800), numMotors);
}
+ /**
+ * Return a gearbox of Kraken X44 brushless motors.
+ *
+ * @param numMotors Number of motors in the gearbox.
+ * @return a gearbox of Kraken X44 motors.
+ */
+ public static DCMotor getKrakenX44(int numMotors) {
+ // From https://motors.ctr-electronics.com/dyno/dynometer-testing/
+ return new DCMotor(
+ 12, 4.11, 279, 2, Units.rotationsPerMinuteToRadiansPerSecond(7758), numMotors);
+ }
+
+ /**
+ * Return a gearbox of Kraken X44 brushless motors with FOC (Field-Oriented Control) enabled.
+ *
+ * @param numMotors Number of motors in the gearbox.
+ * @return A gearbox of Kraken X44 FOC enabled motors.
+ */
+ public static DCMotor getKrakenX44Foc(int numMotors) {
+ // From https://motors.ctr-electronics.com/dyno/dynometer-testing/
+ return new DCMotor(
+ 12, 5.01, 329, 2, Units.rotationsPerMinuteToRadiansPerSecond(7368), numMotors);
+ }
+
+ /**
+ * Return a gearbox of Minion brushless motors.
+ *
+ * @param numMotors Number of motors in the gearbox.
+ * @return A gearbox of Minion motors.
+ */
+ public static DCMotor getMinion(int numMotors) {
+ // From https://motors.ctr-electronics.com/dyno/dynometer-testing/
+ return new DCMotor(
+ 12, 3.17, 211, 2, Units.rotationsPerMinuteToRadiansPerSecond(7704), numMotors);
+ }
+
/**
* Return a gearbox of Neo Vortex brushless motors.
*
diff --git a/wpimath/src/main/native/include/frc/StateSpaceUtil.h b/wpimath/src/main/native/include/frc/StateSpaceUtil.h
index 6c58485d45..b04aea48ce 100644
--- a/wpimath/src/main/native/include/frc/StateSpaceUtil.h
+++ b/wpimath/src/main/native/include/frc/StateSpaceUtil.h
@@ -260,7 +260,7 @@ WPILIB_DLLEXPORT constexpr Eigen::Vector3d PoseTo3dVector(const Pose2d& pose) {
}
/**
- * Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
+ * Converts a Pose2d into a vector of [x, y, cos(theta), sin(theta)].
*
* @param pose The pose that is being represented.
*
diff --git a/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h b/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h
index 629faf5922..1c3a8382af 100644
--- a/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h
+++ b/wpimath/src/main/native/include/frc/geometry/Ellipse2d.h
@@ -91,7 +91,7 @@ class WPILIB_DLLEXPORT Ellipse2d {
auto a = units::math::max(m_xSemiAxis, m_ySemiAxis);
// Minor semi-axis
- auto b = units::math::min(m_xSemiAxis, m_ySemiAxis); // NOLINT
+ auto b = units::math::min(m_xSemiAxis, m_ySemiAxis);
auto c = units::math::sqrt(a * a - b * b);
@@ -203,7 +203,9 @@ class WPILIB_DLLEXPORT Ellipse2d {
auto x = rotPoint.X() - m_center.X();
auto y = rotPoint.Y() - m_center.Y();
+ // NOLINTNEXTLINE (bugprone-integer-division)
return (x * x) / (m_xSemiAxis * m_xSemiAxis) +
+ // NOLINTNEXTLINE (bugprone-integer-division)
(y * y) / (m_ySemiAxis * m_ySemiAxis);
}
};
diff --git a/wpimath/src/main/native/include/frc/geometry/Quaternion.h b/wpimath/src/main/native/include/frc/geometry/Quaternion.h
index 65c6a8265e..09d21e38f2 100644
--- a/wpimath/src/main/native/include/frc/geometry/Quaternion.h
+++ b/wpimath/src/main/native/include/frc/geometry/Quaternion.h
@@ -296,8 +296,8 @@ class WPILIB_DLLEXPORT Quaternion {
// 𝑣⃗ = θ * v̂
// v̂ = 𝑣⃗ / θ
- // 𝑞 = std::cos(θ/2) + std::sin(θ/2) * v̂
- // 𝑞 = std::cos(θ/2) + std::sin(θ/2) / θ * 𝑣⃗
+ // 𝑞 = cos(θ/2) + sin(θ/2) * v̂
+ // 𝑞 = cos(θ/2) + sin(θ/2) / θ * 𝑣⃗
double theta = gcem::hypot(rvec(0), rvec(1), rvec(2));
double cos = gcem::cos(theta / 2);
diff --git a/wpimath/src/main/native/include/frc/system/plant/DCMotor.h b/wpimath/src/main/native/include/frc/system/plant/DCMotor.h
index 90dc8299ea..145cf02bfd 100644
--- a/wpimath/src/main/native/include/frc/system/plant/DCMotor.h
+++ b/wpimath/src/main/native/include/frc/system/plant/DCMotor.h
@@ -247,6 +247,31 @@ class WPILIB_DLLEXPORT DCMotor {
return DCMotor(12_V, 9.37_Nm, 483_A, 2_A, 5800_rpm, numMotors);
}
+ /**
+ * Return a gearbox of Kraken X44 brushless motors.
+ */
+ static constexpr DCMotor KrakenX44(int numMotors = 1) {
+ // From https://motors.ctr-electronics.com/dyno/dynometer-testing/
+ return DCMotor(12_V, 4.11_Nm, 279_A, 2_A, 7758_rpm, numMotors);
+ }
+
+ /**
+ * Return a gearbox of Kraken X44 brushless motors with FOC (Field-Oriented
+ * Control) enabled.
+ */
+ static constexpr DCMotor KrakenX44FOC(int numMotors = 1) {
+ // From https://motors.ctr-electronics.com/dyno/dynometer-testing/
+ return DCMotor(12_V, 5.01_Nm, 329_A, 2_A, 7368_rpm, numMotors);
+ }
+
+ /**
+ * Return a gearbox of Minion brushless motors.
+ */
+ static constexpr DCMotor Minion(int numMotors = 1) {
+ // From https://motors.ctr-electronics.com/dyno/dynometer-testing/
+ return DCMotor(12_V, 3.17_Nm, 211_A, 2_A, 7704_rpm, numMotors);
+ }
+
/**
* Return a gearbox of Neo Vortex brushless motors.
*/
diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.clang-format b/wpimath/src/main/native/thirdparty/sleipnir/.clang-format
deleted file mode 100644
index 5e5e1773c3..0000000000
--- a/wpimath/src/main/native/thirdparty/sleipnir/.clang-format
+++ /dev/null
@@ -1,249 +0,0 @@
----
-Language: Cpp
-BasedOnStyle: Google
-AccessModifierOffset: -1
-AlignAfterOpenBracket: Align
-AlignArrayOfStructures: None
-AlignConsecutiveAssignments:
- Enabled: false
- AcrossEmptyLines: false
- AcrossComments: false
- AlignCompound: false
- PadOperators: true
-AlignConsecutiveBitFields:
- Enabled: false
- AcrossEmptyLines: false
- AcrossComments: false
- AlignCompound: false
- PadOperators: false
-AlignConsecutiveDeclarations:
- Enabled: false
- AcrossEmptyLines: false
- AcrossComments: false
- AlignCompound: false
- PadOperators: false
-AlignConsecutiveMacros:
- Enabled: false
- AcrossEmptyLines: false
- AcrossComments: false
- AlignCompound: false
- PadOperators: false
-AlignConsecutiveShortCaseStatements:
- Enabled: false
- AcrossEmptyLines: false
- AcrossComments: false
- AlignCaseColons: false
-AlignEscapedNewlines: Left
-AlignOperands: Align
-AlignTrailingComments:
- Kind: Always
- OverEmptyLines: 0
-AllowAllArgumentsOnNextLine: true
-AllowAllParametersOfDeclarationOnNextLine: true
-AllowShortBlocksOnASingleLine: Never
-AllowShortCaseLabelsOnASingleLine: false
-AllowShortEnumsOnASingleLine: true
-AllowShortFunctionsOnASingleLine: Inline
-AllowShortIfStatementsOnASingleLine: Never
-AllowShortLambdasOnASingleLine: All
-AllowShortLoopsOnASingleLine: false
-AlwaysBreakAfterDefinitionReturnType: None
-AlwaysBreakAfterReturnType: None
-AlwaysBreakBeforeMultilineStrings: true
-AlwaysBreakTemplateDeclarations: Yes
-BinPackArguments: true
-BinPackParameters: true
-BitFieldColonSpacing: Both
-BraceWrapping:
- AfterCaseLabel: false
- AfterClass: false
- AfterControlStatement: Never
- AfterEnum: false
- AfterExternBlock: false
- AfterFunction: false
- AfterNamespace: false
- AfterObjCDeclaration: false
- AfterStruct: false
- AfterUnion: false
- BeforeCatch: false
- BeforeElse: false
- BeforeLambdaBody: false
- BeforeWhile: false
- IndentBraces: false
- SplitEmptyFunction: true
- SplitEmptyRecord: true
- SplitEmptyNamespace: true
-BreakAfterAttributes: Always
-BreakAfterJavaFieldAnnotations: false
-BreakArrays: true
-BreakBeforeBinaryOperators: None
-BreakBeforeConceptDeclarations: Always
-BreakBeforeBraces: Attach
-BreakBeforeInlineASMColon: OnlyMultiline
-BreakBeforeTernaryOperators: true
-BreakConstructorInitializers: BeforeColon
-BreakInheritanceList: BeforeColon
-BreakStringLiterals: true
-ColumnLimit: 80
-CommentPragmas: '^ IWYU pragma:'
-CompactNamespaces: false
-ConstructorInitializerIndentWidth: 4
-ContinuationIndentWidth: 4
-Cpp11BracedListStyle: true
-DerivePointerAlignment: false
-DisableFormat: false
-EmptyLineAfterAccessModifier: Never
-EmptyLineBeforeAccessModifier: LogicalBlock
-ExperimentalAutoDetectBinPacking: false
-FixNamespaceComments: true
-IncludeBlocks: Regroup
-IncludeCategories:
- - Regex: '^'
- Priority: 2
- SortPriority: 0
- CaseSensitive: false
- - Regex: '^<.*\.h>'
- Priority: 1
- SortPriority: 0
- CaseSensitive: false
- - Regex: '^<.*'
- Priority: 2
- SortPriority: 0
- CaseSensitive: false
- - Regex: '.*'
- Priority: 3
- SortPriority: 0
- CaseSensitive: false
-IncludeIsMainRegex: '([-_](test|unittest))?$'
-IncludeIsMainSourceRegex: ''
-IndentAccessModifiers: false
-IndentCaseBlocks: false
-IndentCaseLabels: true
-IndentExternBlock: AfterExternBlock
-IndentGotoLabels: true
-IndentPPDirectives: None
-IndentRequiresClause: true
-IndentWidth: 2
-IndentWrappedFunctionNames: false
-InsertBraces: false
-InsertNewlineAtEOF: false
-InsertTrailingCommas: None
-IntegerLiteralSeparator:
- Binary: 0
- BinaryMinDigits: 0
- Decimal: 0
- DecimalMinDigits: 0
- Hex: 0
- HexMinDigits: 0
-JavaScriptQuotes: Leave
-JavaScriptWrapImports: true
-KeepEmptyLinesAtTheStartOfBlocks: false
-KeepEmptyLinesAtEOF: false
-LambdaBodyIndentation: Signature
-LineEnding: DeriveLF
-MacroBlockBegin: ''
-MacroBlockEnd: ''
-MaxEmptyLinesToKeep: 1
-NamespaceIndentation: None
-ObjCBinPackProtocolList: Never
-ObjCBlockIndentWidth: 2
-ObjCBreakBeforeNestedBlockParam: true
-ObjCSpaceAfterProperty: false
-ObjCSpaceBeforeProtocolList: true
-PackConstructorInitializers: NextLine
-PenaltyBreakAssignment: 2
-PenaltyBreakBeforeFirstCallParameter: 1
-PenaltyBreakComment: 300
-PenaltyBreakFirstLessLess: 120
-PenaltyBreakOpenParenthesis: 0
-PenaltyBreakString: 1000
-PenaltyBreakTemplateDeclaration: 10
-PenaltyExcessCharacter: 1000000
-PenaltyIndentedWhitespace: 0
-PenaltyReturnTypeOnItsOwnLine: 200
-PointerAlignment: Left
-PPIndentWidth: -1
-QualifierAlignment: Leave
-RawStringFormats:
- - Language: Cpp
- Delimiters:
- - cc
- - CC
- - cpp
- - Cpp
- - CPP
- - 'c++'
- - 'C++'
- CanonicalDelimiter: ''
- BasedOnStyle: google
- - Language: TextProto
- Delimiters:
- - pb
- - PB
- - proto
- - PROTO
- EnclosingFunctions:
- - EqualsProto
- - EquivToProto
- - PARSE_PARTIAL_TEXT_PROTO
- - PARSE_TEST_PROTO
- - PARSE_TEXT_PROTO
- - ParseTextOrDie
- - ParseTextProtoOrDie
- - ParseTestProto
- - ParsePartialTestProto
- CanonicalDelimiter: pb
- BasedOnStyle: google
-ReferenceAlignment: Pointer
-ReflowComments: true
-RemoveBracesLLVM: false
-RemoveParentheses: Leave
-RemoveSemicolon: false
-RequiresClausePosition: OwnLine
-RequiresExpressionIndentation: OuterScope
-SeparateDefinitionBlocks: Leave
-ShortNamespaceLines: 1
-SortIncludes: false
-SortJavaStaticImport: Before
-SortUsingDeclarations: LexicographicNumeric
-SpaceAfterCStyleCast: false
-SpaceAfterLogicalNot: false
-SpaceAfterTemplateKeyword: true
-SpaceAroundPointerQualifiers: Default
-SpaceBeforeAssignmentOperators: true
-SpaceBeforeCaseColon: false
-SpaceBeforeCpp11BracedList: false
-SpaceBeforeCtorInitializerColon: true
-SpaceBeforeInheritanceColon: true
-SpaceBeforeJsonColon: false
-SpaceBeforeParens: ControlStatements
-SpaceBeforeParensOptions:
- AfterControlStatements: true
- AfterForeachMacros: true
- AfterFunctionDefinitionName: false
- AfterFunctionDeclarationName: false
- AfterIfMacros: true
- AfterOverloadedOperator: false
- AfterRequiresInClause: false
- AfterRequiresInExpression: false
- BeforeNonEmptyParentheses: false
-SpaceBeforeRangeBasedForLoopColon: true
-SpaceBeforeSquareBrackets: false
-SpaceInEmptyBlock: false
-SpacesBeforeTrailingComments: 2
-SpacesInAngles: Never
-SpacesInContainerLiterals: true
-SpacesInLineCommentPrefix:
- Minimum: 1
- Maximum: -1
-SpacesInParens: Never
-SpacesInParensOptions:
- InCStyleCasts: false
- InConditionalStatements: false
- InEmptyParentheses: false
- Other: false
-SpacesInSquareBrackets: false
-Standard: c++20
-TabWidth: 8
-UseTab: Never
-...
diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.clang-tidy b/wpimath/src/main/native/thirdparty/sleipnir/.clang-tidy
deleted file mode 100644
index cfb2b12f2a..0000000000
--- a/wpimath/src/main/native/thirdparty/sleipnir/.clang-tidy
+++ /dev/null
@@ -1,74 +0,0 @@
-Checks:
- 'bugprone-assert-side-effect,
- bugprone-bool-pointer-implicit-conversion,
- bugprone-copy-constructor-init,
- bugprone-dangling-handle,
- bugprone-dynamic-static-initializers,
- bugprone-forward-declaration-namespace,
- bugprone-forwarding-reference-overload,
- bugprone-inaccurate-erase,
- bugprone-incorrect-roundings,
- bugprone-integer-division,
- bugprone-lambda-function-name,
- bugprone-misplaced-operator-in-strlen-in-alloc,
- bugprone-misplaced-widening-cast,
- bugprone-move-forwarding-reference,
- bugprone-multiple-statement-macro,
- bugprone-parent-virtual-call,
- bugprone-posix-return,
- bugprone-sizeof-container,
- bugprone-sizeof-expression,
- bugprone-spuriously-wake-up-functions,
- bugprone-string-constructor,
- bugprone-string-integer-assignment,
- bugprone-string-literal-with-embedded-nul,
- bugprone-suspicious-enum-usage,
- bugprone-suspicious-include,
- bugprone-suspicious-memset-usage,
- bugprone-suspicious-missing-comma,
- bugprone-suspicious-semicolon,
- bugprone-suspicious-string-compare,
- bugprone-throw-keyword-missing,
- bugprone-too-small-loop-variable,
- bugprone-undefined-memory-manipulation,
- bugprone-undelegated-constructor,
- bugprone-unhandled-self-assignment,
- bugprone-unused-raii,
- bugprone-virtual-near-miss,
- cert-err52-cpp,
- cert-err60-cpp,
- cert-mem57-cpp,
- cert-oop57-cpp,
- cert-oop58-cpp,
- clang-diagnostic-*,
- -clang-diagnostic-deprecated-declarations,
- -clang-diagnostic-#warnings,
- -clang-diagnostic-pedantic,
- clang-analyzer-*,
- -clang-analyzer-core.uninitialized.UndefReturn,
- -clang-analyzer-optin.cplusplus.UninitializedObject,
- -clang-analyzer-optin.portability.UnixAPI,
- -clang-analyzer-unix.Malloc,
- -cppcoreguidelines-slicing,
- google-build-namespaces,
- google-explicit-constructor,
- google-global-names-in-headers,
- google-readability-avoid-underscore-in-googletest-name,
- google-readability-casting,
- google-runtime-operator,
- misc-definitions-in-headers,
- misc-misplaced-const,
- misc-new-delete-overloads,
- misc-non-copyable-objects,
- modernize-avoid-bind,
- modernize-concat-nested-namespaces,
- modernize-make-shared,
- modernize-make-unique,
- modernize-pass-by-value,
- modernize-use-default-member-init,
- modernize-use-noexcept,
- modernize-use-nullptr,
- modernize-use-override,
- modernize-use-using,
- readability-braces-around-statements'
-FormatStyle: file
diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide b/wpimath/src/main/native/thirdparty/sleipnir/.styleguide
deleted file mode 100644
index 054f5eb80e..0000000000
--- a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide
+++ /dev/null
@@ -1,23 +0,0 @@
-cppHeaderFileInclude {
- \.hpp$
-}
-
-cppSrcFileInclude {
- \.cpp$
-}
-
-modifiableFileExclude {
- \.patch$
- \.png$
- \.svg$
- jormungandr/cpp/docstrings\.hpp$
- jormungandr/py\.typed$
-}
-
-includeOtherLibs {
- ^Eigen/
- ^catch2/
- ^gch/
- ^nanobind/
- ^sleipnir/
-}
diff --git a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide-license b/wpimath/src/main/native/thirdparty/sleipnir/.styleguide-license
deleted file mode 100644
index d664772a55..0000000000
--- a/wpimath/src/main/native/thirdparty/sleipnir/.styleguide-license
+++ /dev/null
@@ -1 +0,0 @@
-// Copyright (c) Sleipnir contributors
diff --git a/wpimath/src/main/native/thirdparty/sleipnir/include/.styleguide b/wpimath/src/main/native/thirdparty/sleipnir/include/.styleguide
deleted file mode 100644
index 03938557c2..0000000000
--- a/wpimath/src/main/native/thirdparty/sleipnir/include/.styleguide
+++ /dev/null
@@ -1,14 +0,0 @@
-cppHeaderFileInclude {
- \.hpp$
-}
-
-cppSrcFileInclude {
- \.cpp$
-}
-
-includeOtherLibs {
- ^Eigen/
- ^fmt/
- ^gch/
- ^wpi/
-}
diff --git a/wpimath/src/main/native/thirdparty/sleipnir/src/.styleguide b/wpimath/src/main/native/thirdparty/sleipnir/src/.styleguide
deleted file mode 100644
index 4f4c762040..0000000000
--- a/wpimath/src/main/native/thirdparty/sleipnir/src/.styleguide
+++ /dev/null
@@ -1,13 +0,0 @@
-cppHeaderFileInclude {
- \.hpp$
-}
-
-cppSrcFileInclude {
- \.cpp$
-}
-
-includeOtherLibs {
- ^Eigen/
- ^fmt/
- ^gch/
-}
diff --git a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp
index 919552534d..c69e3f8f50 100644
--- a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp
+++ b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp
@@ -192,11 +192,11 @@ TEST(LinearFilterOutputTest, CentralFiniteDifference) {
AssertCentralResults<1, 3>(
[](double x) {
- // f(x) = std::sin(x)
+ // f(x) = sin(x)
return std::sin(x);
},
[](double x) {
- // df/dx = std::cos(x)
+ // df/dx = cos(x)
return std::cos(x);
},
h, -20.0, 20.0);
@@ -225,11 +225,11 @@ TEST(LinearFilterOutputTest, CentralFiniteDifference) {
AssertCentralResults<2, 5>(
[](double x) {
- // f(x) = std::sin(x)
+ // f(x) = sin(x)
return std::sin(x);
},
[](double x) {
- // d²f/dx² = -std::sin(x)
+ // d²f/dx² = -sin(x)
return -std::sin(x);
},
h, -20.0, 20.0);
@@ -265,11 +265,11 @@ TEST(LinearFilterOutputTest, BackwardFiniteDifference) {
AssertBackwardResults<1, 2>(
[](double x) {
- // f(x) = std::sin(x)
+ // f(x) = sin(x)
return std::sin(x);
},
[](double x) {
- // df/dx = std::cos(x)
+ // df/dx = cos(x)
return std::cos(x);
},
h, -20.0, 20.0);
@@ -298,11 +298,11 @@ TEST(LinearFilterOutputTest, BackwardFiniteDifference) {
AssertBackwardResults<2, 4>(
[](double x) {
- // f(x) = std::sin(x)
+ // f(x) = sin(x)
return std::sin(x);
},
[](double x) {
- // d²f/dx² = -std::sin(x)
+ // d²f/dx² = -sin(x)
return -std::sin(x);
},
h, -20.0, 20.0);
diff --git a/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h b/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h
index 739a95ee08..8b3f4b1b21 100644
--- a/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h
+++ b/wpiutil/src/main/native/include/wpi/sendable/SendableHelper.h
@@ -39,8 +39,7 @@ class SendableHelper {
// See https://bugzilla.mozilla.org/show_bug.cgi?id=1442819
__attribute__((no_sanitize("vptr")))
#endif
- constexpr SendableHelper&
- operator=(SendableHelper&& rhs) {
+ constexpr SendableHelper& operator=(SendableHelper&& rhs) {
if (!std::is_constant_evaluated()) {
// it is safe to call Move() multiple times with the same rhs
SendableRegistry::Move(static_cast(this),