To make the tests reliable, the synchronization in simulation Notifiers
had to be reworked. StepTiming() now waits for all Notifiers to reach
HAL_WaitForNotifierAlarm(), then steps the time, then lets any expired
Notifiers run.
While there, we made some variable names more descriptive and added more
comments.
There were three bugs:
1. The input range variables used in ProfiledPIDController::Calculate()
weren't being updated
2. The modulus error calculation was incorrect.
3. The setpoint wasn't being wrapped like the goal, so the invariant
that the error remains less than half the input range was violated.
(Thanks to @CptJJ for pointing this out and suggesting a fix.)
Old behavior is available via StepTimingAsync.
This makes it significantly easier to use simulation timing with notifiers.
Also update tests to use simulation framework. This also speeds up the
timing-dependent tests by using simulation timing. ResourceLock is used
in the Java tests to prevent parallel execution.
While we're here, tweak HAL Notifier implementation:
- Use wait_for instead of wait_until in WaitForNotifierAlarm
- Check for triggerTime = UINT64_MAX in UpdateNotifierAlarm
If the model is unstable, it will almost always diverge within 10
seconds, and the results are rather dramatic. We're also reducing the
threshold to 100 meters because the drivetrain is moving in a small
circle. The translation norm is also used for this reason; the X
component alone regularly crosses zero since the drivetrain moves in a
circle.
Some vestigial functions were never removed, and C++ single-jointed arm
sim was missing a flag for disabling gravity simulation. This is useful
for mechanisms like turrets.
Fixes#2738.
This includes physics simulation support for arms/elevator models, as well as differential drivetrains.
Swerve might be added at a later date.
Co-authored-by: Claudius Tewari <cttewari@gmail.com>
Co-authored-by: Prateek Machiraju <prateek.machiraju@gmail.com>
Co-authored-by: Tyler Veness <calcmogul@gmail.com>
The wpimath library is a new library designed to separate the reusable math functionality
from the common utility library (wpiutil) and the hardware-dependent library (wpilibc/j).
Package names / include file names were NOT changed to minimize breakage. In a future year
it would be good to revamp these for a more uniform user experience and to reduce the risk
of accidental naming conflicts.
While theoretically all of this functionality could be placed into wpiutil, several pieces
of this library (e.g. DARE) are very time-consuming to compile, so it's nice to avoid this
expense for users who only want cscore or ntcore. It also allows for easy future separation
of build tasks vs number of workers on memory-constrained machines.
This moves the following functionality from wpiutil into wpimath:
- Eigen
- ejml
- Drake
- DARE
- wpiutil.math package (Matrix etc)
- units
And the following functionality from wpilibc/j into wpimath:
- Geometry
- Kinematics
- Spline
- Trajectory
- LinearFilter
- MedianFilter
- Feed-forward controllers
When not direct mapped, make index constructors private and add factory
functions for channel and index.
Co-authored-by: GabrielDeml <gabrielddeml@gmail.com>
pose.Translation().X() and pose.Translation.Y() are common operations,
so shortening them to pose.X() and pose.Y() would be convenient.
Java uses the getX() convention so that is used instead of X() for Java.
Also move some things in HAL for consistency.
WAS:
C++:
- C APIs: #include "mockdata/AccelerometerData.h"
- User side class: #include "simulation/AccelerometerSim.h"
Java:
- JNI APIs: hal.sim.mockdata.AccelerometerData (and a few classes in hal.sim)
- User side classes: hal.sim.AccelerometerSim
IS:
C++:
- C APIs: #include "hal/simulation/AccelerometerData.h"
- C++ class: #include "frc/simulation/AccelerometerSim.h"
Java:
- JNI APIs: hal.simulation.AccelerometerData
- User side class: wpilibj.simulation.AccelerometerSim
Previously, it could take the long way around. This recomputes the
profile goal with the shortest error, thus taking the shortest path.
Also removed the setpoint clamping from PIDController::SetSetpoint()
because it's unnecessary to make PIDController behave correctly for
a modular arithmetic input, and it breaks the setpoint calculation in
ProfiledPIDController otherwise.
Fixes#2277.
This is useful for undoing transformations. One application my FRC team
found was converting perspective n-point data from a "camera to target"
coordinate frame transformation to a "target to camera" coordinate frame
transformation.
This PR changes the spline parameterizer to use an explicit stack instead of recursion. This is motivated by the fact that splines with adjacent waypoints with approximately opposite headings will never parameterize. In this case the parameterizer subdivides these malformed splines fine for a while, and then gets stuck parameterizing infinitely on some interval. In the recursive approach, this would lead to a stack overflow. We could implement a recursion depth counter (this is what my team did on our similar trajectory code last season), but it's hard to choose a good number for max depth because the initial amount of stack used varies based on how the user calls Parameterize.
A good solution for this is converting the recursion to an "explicit stack," which basically simulates recursion, but allows us to have a much larger maximum stack size. Because we avoid the stack overflow, we can instead throws a more informative MalformedSplineException. If the user is using the TrajectoryGenerator instead of the SplineParameterizer directly then the TrajectoryGenerator will go ahead and catch the exception, return a harmless empty trajectory, and report and error to the driver station.
This is extremely useful for implementing various "ramping" functions
(such as voltage ramps, setpoint ramps, etc). Usage is straightforward;
it behaves like all of our other filter classes. C++ version is unit-safe.
It doesn't make sense to continue to provide a less accurate method of performing odometry
when a more accurate method using distances exists.
This also removes the need to pass DifferentialDriveKinematics to the constructor.
This kind of filter is extremely useful for signals that are susceptible to sudden
outliers - ultrasonics, 1-D LIDAR, and results from vision processing are all
good use-cases.
This also modifies the existing ultrasonic examples accordingly.
The odometry classes previously took in the robot angle as an argument, meaning that users had to take care of offsetting the gyro themselves to accurately report the robot angle. This change will make it so that users will not have to worry about resetting gyros and adding offsets themselves, as this will be handled by the odometry classes.
The current index would be set to -1 by the execute method of ParallelRaceGroup,
and then an index out of bounds exception would be thrown by the end() method of
SequentialCommandGroup. This change bound checks the current command index as well
as only calls end at the end of parallel race group rather than during execute.
This removes the name and subsystem from individual objects, and instead
puts this data into a new singleton class, SendableRegistry. Much of
LiveWindow has been refactored into SendableRegistry.
In C++, a new CRTP helper class, SendableHelper, has been added to provide
move and destruction functionality.
Shims for GetName, SetName, GetSubsystem, and SetSubsystem have been added
to Command and Subsystem (both old and new), and also to SendableHelper to
prevent code breakage.
This deprecates SendableBase in preparation for future removal.