Squashed 'third_party/allwpilib/' changes from e473a00f97..e4b91005cf
e4b91005cf [examples] Update SwerveModule constructor doc (NFC) (#4042)
a260bfd83b [examples] Remove "this" keyword from SwerveModule (#4043)
18e262a100 [examples] Fix multiple doc typos in SwerveControllerCommand example (NFC) (#4044)
4bd1f526ab [wpilibc] Prevent StopMotor from terminating robot during MotorSafety check (#4038)
27847d7eb2 [sim] Expose GUI control functions via HAL_RegisterExtension (#4034)
b2a8d3f0f3 [wpilibc] Add mechanism to reset MotorSafety list (#4037)
49adac9564 [wpilib] Check for signedness in ArcadeDriveIK() (#4028)
a19d1133b1 [wpiutil] libuv: Fix sign compare warnings in gcc 11.2 (#4031)
dde91717e4 [build] cmake: Add ability to customize target warnings (#4032)
e9050afd67 [sim] Update sim match time to match real robot (#4024)
165d2837cf [wpilib] Preferences: Set Persistent in Init methods (#4025)
ac7549edca [glass] Fix snprintf truncation warning (#4029)
4d96bc72e0 [wpilibj] Fix typos in error messages for non-null assertions (#4014)
3411eee20f [hal] Replace hardcoded sim array sizes with constants (#4015)
74de97eeca [wpilibc] Add mechanism to reset various global structures (#4007)
4e3cc25012 [examples] Fix periodic function rate comment (NFC) (#4013)
90c1db393e [sim] Add exported functions to control the sim GUI (#3995)
2f43274aa4 [wpilibj] MechanismRoot2d: Add flush to setPosition (#4011)
aeca09db09 [glass] Support remapping of Enter key (#3994)
c107f22c67 [sim] Sim GUI: don't force-show Timing and Other Devices (#4001)
68fe51e8da [wpigui] Update PFD to latest, fix kdialog multiselect (#4005)
8d08d67cf1 [wpigui] PFD: Add console warning if file chooser unavailable (#4003)
4f1782f66e [wpilibc] Only call HAL_Report when initializing SmartDashboard (#4006)
3f77725cd3 Remove uses of iostream (#4004)
5635f33a32 [glass] Increase plot depth to 20K points (#3993)
bca4b7111b [glass] Fix PlotSeries::SetSource() (#3991)
6a6366b0d6 [commands] Add until() as alias for withInterrupt() (#3981)
16bf2c70c5 [wpilib] Fix joystick out of range error messages (#3988)
4b3edb742c [wpilib] Fix ADIS16448 IMU default constructor not working in Java (#3989)
fcf23fc9e9 [hal] Fix potential gamedata out of bounds read (#3983)
af5ef510c5 [wpilibc] Fix REV PH pulse duration units (#3982)
05401e2b81 [wpilib] Write REV PH firmware version to roboRIO to display on driver station (#3977)
9fde0110b6 Update to 2022 v4.0 image (#3944)
b03f8ddb2e [examples] fix incorrect variable in Arm Simulation Pref (#3980)
a26df2a022 [examples] Update ArmSimulation example to use Preferences (#3976)
d68d6674e8 [examples] Armbot: rename kCos to kG (#3975)
a8f0f6bb90 [wpilibj] Fix ADIS16448 getRate to return rate instead of angle (#3974)
dd9c92d5bf [build] Remove debug info from examples (#3971)
84df14dd70 [rtns] Fix icons (#3972)
560094ad92 [examples] Correct Mecanum example axes (#3955)
7ea1be9c01 [wpilibc] Fix typo in hardware version for REV PDH (#3969)
700f13bffd [wpilibj] Make methods public for Java REV PDH (#3970)
b6aa7c1aa9 [wpilibj] Make methods public for Java REVPH (#3968)
eb4d183e48 [wpimath] Fix clang-tidy bugprone-integer-division warning (#3966)
77e4e81e1e [wpilib] Add Field widget to BuiltInWidgets in shuffleboard (#3961)
88f5cb6eb0 [build] Publish PDBs with C++ tools (#3960)
efae552f3e [wpimath] Remove DifferentialDriveKinematics include from odometry (#3958)
46b277421a [glass] Update Speed Controller Type name for 2022 WPILib (#3952)
42908126b9 [wpilib] Add DCMotorSim (#3910)
a467392cbd [wpiutil] StackTrace: Add ability to override default implementation (#3951)
78d0bcf49d [templates] Add SimulationInit()/SimulationPeriodic() to robot templates (#3943)
02a0ced9b0 [wpilib] MecanumDrive: update docs for axis to match implementation (NFC) (#3942)
4ccfe1c9f2 [wpilib] Added docs clarification on units for drive class WheelSpeeds (NFC) (#3939)
830c0c5c2f [wpilib] MechanismLigament2d: Add getters for color and line weight (#3947)
5548a37465 [wpilib] PowerDistribution: Add module type getter (#3948)
2f9a600de2 [hal] Fix PCM one shot (#3949)
559db11a20 [myRobot] Skip deploying debug libraries for myRobot deploys (#3950)
76c78e295b [examples] Reorder SwerveModules in SwerveControllerCommand example odometry update (#3934)
debbd5ff4b [wpilib] Improve PowerDistribution docs (NFC) (#3925)
841174f302 [commands] Change command vendordep JSON version number to 1.0.0 (#3938)
8c55844f91 [wpilib] Remove comment about Mecanum right side inverted (NFC) (#3929)
0b990bf0f5 [hal] Fix PCM sticky faults clear function crashing (#3932)
104d7e2abc [hal] Don't throw exceptions in PCM JNI (#3933)
5ba69e1af1 [examples] Updated type in Java SwerveModule (#3928)
f3a0b5c7d7 [wpimath] Fix Java SimpleMotorFeedforward Docs (NFC) (#3926)
7f4265facc [wpimath] Add LinearFilter::FiniteDifference() (#3900)
63d1fb3bed [wpiutil] Modify fmt to not throw on write failure (#3919)
36af6d25a5 [wpimath] Fix input vector in pose estimator docs (NFC) (#3923)
8f387f7255 [wpilibj] Switch ControlWord mutex to actual reentrant mutex (#3922)
792e735e08 [wpimath] Move TrajectoryGenerator::SetErrorHandler definition to .cpp (#3920)
3b76de83eb [commands] Fix ProfiledPIDCommand use-after-free (#3904)
ad9f738cfa [fieldimages] Fix maven publishing (#3897)
49455199e5 [examples] Use left/rightGroup.Get() for simulator inputs to fix inversions (#3908)
64426502ea [wpimath] Fix arm -> flywheel typo (NFC) (#3911)
8cc112d196 [wpiutil] Fix wpi::array for move-only types (#3917)
e78cd49861 [build] Upgrade Java formatter plugins (#3894)
cfb4f756d6 [build] Upgrade to shadow 7.1.2 (#3893)
ba0908216c [wpimath] Fix crash in KF latency compensator (#3888)
a3a0334fad [build] cmake: Move fieldImages to WITH_GUI (#3885)
cf7460c3a8 [fieldImages] Add 2022 field (#3883)
db0fbb6448 [wpimath] Fix LQR matrix constructor overload for Q, R, and N (#3884)
8ac45f20bb [commands] Update Command documentation (NFC) (#3881)
b3707cca0b [wpiutil] Upgrade to fmt 8.1.1 (#3879)
a69ee3ece9 [wpimath] Const-qualify Twist2d scalar multiply (#3882)
750d9a30c9 [examples] Fix Eigen out of range error when running example (#3877)
41c5b2b5ac [rtns] Add cmake build (#3866)
6cf3f9b28e [build] Upgrade to Gradle 7.3.3 (#3878)
269cf03472 [examples] Add communication examples (e.g. arduino) (#2500)
5ccfc4adbd [oldcommands] Deprecate PIDWrappers, since they use deprecated interfaces (#3868)
b6f44f98be [hal] Add warning about onboard I2C (#3871)
0dca57e9ec [templates] romieducational: Invert drivetrain and disable motor safety (#3869)
22c4da152e [wpilib] Add GetRate() to ADIS classes (#3864)
05d66f862d [templates] Change the template ordering to put command based first (#3863)
b09f5b2cf2 [wpilibc] Add virtual dtor for LinearSystemSim (#3861)
a2510aaa0e [wpilib] Make ADIS IMU classes unit-safe (#3860)
947f589916 [wpilibc] Rename ADIS_16470_IMU.cpp to match class name (#3859)
bbd8980a20 [myRobot] Fix cameraserver library order (#3858)
831052f118 [wpilib] Add simulation support to ADIS classes (#3857)
c137569f91 [wpilib] Throw exception if the REV Pneumatic Hub firmware version is older than 22.0.0 (#3853)
dae61226fa Fix Maven Artifacts readme (#3856)
3ad4594a88 Update Maven artifacts readme for 2022 (#3855)
112acb9a62 [wpilibc] Move ADIS IMU constants to inside class (#3852)
ecee224e81 [wpilib] Allow SendableCameraWrappers to take arbitrary URLs (#3850)
a3645dea34 LICENSE: Bump year range to include 2022 (#3854)
7c09f44898 [wpilib] Use PSI for compressor config and sensor reading (#3847)
f401ea9aae [wpigui] Remove wpiutil linkage (#3851)
bf8517f1e6 [wpimath] TimeInterpolatableBufferTest: Fix lint warnings (#3849)
528087e308 [hal] Use enums with fixed underlying type in clang C (#3297)
1f59ff72f9 [wpilib] Add ADIS IMUs (#3777)
315be873c4 [wpimath] Add TimeInterpolatableBuffer (#2695)
b8d019cdb4 [wpilib] Rename NormalizeWheelSpeeds to DesaturateWheelSpeeds (#3791)
102f23bbdb [wpilibj] DriverStation: Set thread interrupted state (#3846)
b85c24a79c [wpilib] Add warning about onboard I2C (#3842)
eee29daaf9 [newCommands] Trigger: Allow override of debounce type (#3845)
aa9dfabde2 [wpimath] Move debouncer to filters (#3838)
5999a26fba [wpiutil] Add GetSystemTime() (#3840)
1e82595ffb [examples] Fix arcade inversions (#3841)
e373fa476b [wpiutil] Add disableMockTime to JNI (#3839)
dceb5364f4 [examples] Ensure right side motors are inverted (#3836)
baacbc8e24 [wpilib] Tachometer: Add function to return RPS (#3833)
84b15f0883 [templates] Add Java Romi Educational template (#3837)
c0da9d2d35 [examples] Invert Right Motor in Romi Java examples (#3828)
0fe0be2733 [build] Change project year to intellisense (#3835)
eafa947338 [wpimath] Make copies of trajectory constraint arguments (#3832)
9d13ae8d01 [wpilib] Add notes for Servo get that it only returns cmd (NFC) (#3820)
2a64e4bae5 [wpimath] Give drivetrain a more realistic width in TrajectoryJsonTest.java (#3822)
c3fd20db59 [wpilib] Fix trajectory sampling in DifferentialDriveSim test (#3821)
6f91f37cd0 [examples] Fix SwerveControllerCommand order of Module States (#3815)
5158730b81 [wpigui] Upgrade to imgui 1.86, GLFW 3.3.6 (#3817)
2ad2d2ca96 [wpiutil] MulticastServiceResolver: Fix C array returning functions (#3816)
b5fd29774f [wpilibj] Trigger: implement BooleanSupplier interface (#3811)
9f8f330e96 [wpilib] Fix Mecanum and SwerveControllerCommand when desired rotation passed (#3808)
1ad3b1b333 [hal] Don't copy byte to where null terminator goes (#3807)
dfc24425c3 [build] Fix gazebo gradle IDE warnings (#3806)
c02577bb51 [glass] Configure delay loading for windows camera server support (#3803)
c9e6a96a61 [wpilib] Document range of Servo angle (NFC) (#3796)
9778626f34 [wpilib, hal] Add support for getting faults and versions from power distribution (#3794)
34b2d0dae1 [wpilib, hal] High Level REV PH changes (#3792)
59a7528fd6 [cscore] Fix crash when usbcamera is deleted before message pump thread fully starts (#3804)
11d9859ef1 [build] Update plugins to remove log4j vulnerabilities (#3805)
e44ed752ad [glass] Fix CollapsingHeader in Encoder, PCM, and DeviceTree (#3797)
52b2dd5b89 [build] Bump native utils to remove log4j (#3802)
c46636f218 [wpilib] Improve new counter classes documentation (NFC) (#3801)
dc531462e1 [build] Update to gradle 7.3.2 (#3800)
92ba98621c [wpimath] Add helper variable templates for units type traits (#3790)
d41d051f1b [wpilibc] Fix Mecanum & Swerve ControllerCommand lambda capture (#3795)
c5ae0effac OtherVersions.md: Add one missing case of useLocal (#3788)
b3974c6ed3 [wpimath] Upgrade to Drake v0.37.0 (#3786)
589a00e379 [wpilibc] Start DriverStation thread from RobotBase (#3785)
8d9836ca02 [wpilib] Improve curvature drive documentation (NFC) (#3783)
8b5bf8632e [myRobot] Add wpimath and wpiutil JNI (#3784)
1846114491 [examples] Update references from characterization to SysId (NFC) (#3782)
2c461c794e [build] Update to gradle 7.3 (#3778)
109363daa4 [hal] Add remaining driver functions for REVPH (#3776)
41d26bee8d [hal] Refactor REV PDH (#3775)
7269a170fb Upgrade maven deps to latest versions and fix new linter errors (#3772)
441f2ed9b0 [build] actions: use fixed image versions instead latest (#3761)
15275433d4 [examples] Fix duplicate port allocations in C++ SwerveBot/SwerveDrivePoseEstimator/RomiReference (#3773)
1ac02d2f58 [examples] Fix drive Joystick axes in several examples (#3769)
8ee6257e92 [wpilib] DifferentialDrivetrainSim.KitbotMotor: Add NEO and Falcon 500 (#3762)
d81ef2bc5c [wpilib] Fix deadlocks in Mechanism2d et al. (#3770)
acb64dff97 [wpimath] Make RamseteController::Calculate() more concise (#3763)
3f6cf76a8c [hal] Refactor REV PH CAN frames (#3756)
3ef2dab465 [wpilib] DutyCycleEncoder: add setting of duty cycle range (#3759)
a5a56dd067 Readme: Add Visual Studio 2022 (#3760)
04957a6d30 [wpimath] Fix units of RamseteController's b and zeta (#3757)
5da54888f8 [glass] Upgrade imgui to 0.85, implot to HEAD, glfw to 3.3.5 (#3754)
6c93365b0f [wpiutil] MulticastService cleanup (#3750)
1c4a8bfb66 [cscore] Cleanup Windows USB camera impl (#3751)
d51a1d3b3d [rtns] Fix icon (#3749)
aced2e7da6 Add roboRIO Team Number Setter tool (#3744)
fa1ceca83a [wpilibj] Use DS cache for iterative robot control word cache (#3748)
0ea05d34e6 [build] Update to gradle 7.2 (#3746)
09db4f672b [build] Update to native utils 2022.6.1 (#3745)
4ba80a3a8c [wpigui] Don't recursively render frames in size callback (#3743)
ae208d2b17 [wpiutil] StringExtras: Add substr() (#3742)
6f51cb3b98 [wpiutil] MulticastResolver: make event manual reset, change to multiple read (#3736)
f6159ee1a2 [glass] Fix Drive widget handling of negative rotation (#3739)
7f401ae895 [build] Update NI libraries to 2022.2.3 (#3738)
0587b7043a [glass] Use JSON files for storage instead of imgui ini
0bbf51d566 [wpigui] Change maximized to bool
92c6eae6b0 [wpigui] PFD: Add explicit to constructors
141354cd79 [wpigui] Add hooks for custom load/save settings
f6e9fc7d71 [wpiutil] Handle multicast service collision on linux (#3734)
d8418be7d1 [glass, outlineviewer] Return 0 from WinMain (#3735)
82066946e5 [wpiutil] Add mDNS resolver and announcer (#3733)
4b1defc8d8 [wpilib] Remove automatic PD type from module type enum (#3732)
da90c1cd2c [wpilib] Add bang-bang controller (#3676)
3aa54fa027 [wpilib] Add new counter implementations (#2447)
b156db400d [hal, wpilib] Incorporate pneumatic control type into wpilibc/j (#3728)
9aba2b7583 [oldCommands] Add wrappers for WPILib objects to work with old PID Controller (#3710)
a9931223f0 [hal] Add REV PH faults (#3729)
aacf9442e4 [wpimath] Fix units typo in LinearSystemId source comment (#3730)
7db10ecf00 [wpilibc] Make SPI destructor virtual since SPI contains virtual functions (#3727)
a0a5b2aea5 [wpimath] Upgrade to EJML 0.41 (#3726)
eb835598a4 [hal] Add HAL functions for compressor config modes on REV PH (#3724)
f0ab6df5b6 [wpimath] Upgrade to Drake v0.36.0 (#3722)
075144faa3 [docs] Parse files without extensions with Doxygen (#3721)
32468a40cb [hal] Remove use of getDmaDescriptor from autospi (#3717)
38611e9dd7 [hal] Fix REVPH Analog Pressure channel selection (#3716)
4d78def31e [wpilib] Add DeadbandElimination forwarding to PWMMotorController (#3714)
3be0c1217a [wpilibcExamples] Make GearsBot use idiomatic C++ (#3711)
42d3a50aa2 [hal] Check error codes during serial port initialization (#3712)
52f1464029 Add project with field images and their json config files (#3668)
68ce62e2e9 [hal] Add autodetect for power modules (#3706)
3dd41c0d37 [wpilib] Don't print PD errors for LiveWindow reads (#3708)
7699a1f827 [hal] Fix sim not working with automatic PD type and default module (#3707)
Change-Id: I6b0b8fa8b2d2a24071240f624db9ec6d127f6648
git-subtree-dir: third_party/allwpilib
git-subtree-split: e4b91005cf69161f1cb3d934f6526232e6b9169e
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/hal/src/main/native/sim/Notifier.cpp b/hal/src/main/native/sim/Notifier.cpp
index 49f1c80..c686eea 100644
--- a/hal/src/main/native/sim/Notifier.cpp
+++ b/hal/src/main/native/sim/Notifier.cpp
@@ -320,7 +320,7 @@
static_cast<int>(getHandleIndex(handle)));
} else {
std::strncpy(arr[num].name, notifier->name.c_str(),
- sizeof(arr[num].name));
+ sizeof(arr[num].name) - 1);
arr[num].name[sizeof(arr[num].name) - 1] = '\0';
}
arr[num].timeout = notifier->waitTime;
diff --git a/hal/src/main/native/sim/PortsInternal.h b/hal/src/main/native/sim/PortsInternal.h
index 2d1a205..190573b 100644
--- a/hal/src/main/native/sim/PortsInternal.h
+++ b/hal/src/main/native/sim/PortsInternal.h
@@ -7,6 +7,7 @@
#include <stdint.h>
namespace hal {
+constexpr int32_t kAccelerometers = 1;
constexpr int32_t kNumAccumulators = 2;
constexpr int32_t kNumAnalogTriggers = 8;
constexpr int32_t kNumAnalogInputs = 8;
@@ -18,6 +19,7 @@
constexpr int32_t kNumPWMChannels = 20;
constexpr int32_t kNumDigitalPWMOutputs = 6;
constexpr int32_t kNumEncoders = 8;
+constexpr int32_t kI2CPorts = 2;
constexpr int32_t kNumInterrupts = 8;
constexpr int32_t kNumRelayChannels = 8;
constexpr int32_t kNumRelayHeaders = kNumRelayChannels / 2;
@@ -27,8 +29,13 @@
constexpr int32_t kNumCTREPDPChannels = 16;
constexpr int32_t kNumREVPDHModules = 63;
constexpr int32_t kNumREVPDHChannels = 24;
+constexpr int32_t kNumPDSimModules = kNumREVPDHModules;
+constexpr int32_t kNumPDSimChannels = kNumREVPDHChannels;
constexpr int32_t kNumDutyCycles = 8;
constexpr int32_t kNumAddressableLEDs = 1;
constexpr int32_t kNumREVPHModules = 63;
constexpr int32_t kNumREVPHChannels = 16;
+constexpr int32_t kSPIAccelerometers = 5;
+constexpr int32_t kSPIPorts = 5;
+
} // namespace hal
diff --git a/hal/src/main/native/sim/PowerDistribution.cpp b/hal/src/main/native/sim/PowerDistribution.cpp
index 85646cf..ddda420 100644
--- a/hal/src/main/native/sim/PowerDistribution.cpp
+++ b/hal/src/main/native/sim/PowerDistribution.cpp
@@ -30,6 +30,19 @@
HAL_PowerDistributionHandle HAL_InitializePowerDistribution(
int32_t module, HAL_PowerDistributionType type,
const char* allocationLocation, int32_t* status) {
+ if (type == HAL_PowerDistributionType_kAutomatic) {
+ if (module != HAL_DEFAULT_POWER_DISTRIBUTION_MODULE) {
+ *status = PARAMETER_OUT_OF_RANGE;
+ hal::SetLastError(
+ status, "Automatic PowerDistributionType must have default module");
+ return HAL_kInvalidHandle;
+ }
+
+ // TODO Make this not matter
+ type = HAL_PowerDistributionType_kCTRE;
+ module = 0;
+ }
+
if (!HAL_CheckPowerDistributionModule(module, type)) {
*status = PARAMETER_OUT_OF_RANGE;
hal::SetLastError(status, fmt::format("Invalid pdp module {}", module));
@@ -155,4 +168,16 @@
HAL_PowerDistributionHandle handle, int32_t* status) {
return false;
}
+
+void HAL_GetPowerDistributionVersion(HAL_PowerDistributionHandle handle,
+ HAL_PowerDistributionVersion* version,
+ int32_t* status) {}
+
+void HAL_GetPowerDistributionFaults(HAL_PowerDistributionHandle handle,
+ HAL_PowerDistributionFaults* faults,
+ int32_t* status) {}
+
+void HAL_GetPowerDistributionStickyFaults(
+ HAL_PowerDistributionHandle handle,
+ HAL_PowerDistributionStickyFaults* stickyFaults, int32_t* status) {}
} // extern "C"
diff --git a/hal/src/main/native/sim/REVPH.cpp b/hal/src/main/native/sim/REVPH.cpp
index 9ddb655..163ca9c 100644
--- a/hal/src/main/native/sim/REVPH.cpp
+++ b/hal/src/main/native/sim/REVPH.cpp
@@ -64,7 +64,8 @@
SimREVPHData[module].initialized = true;
// Enable closed loop
- SimREVPHData[module].closedLoopEnabled = true;
+ SimREVPHData[module].compressorConfigType =
+ HAL_REVPHCompressorConfigType_kDigital;
return handle;
}
@@ -97,26 +98,73 @@
return SimREVPHData[pcm->module].compressorOn;
}
-void HAL_SetREVPHClosedLoopControl(HAL_REVPHHandle handle, HAL_Bool enabled,
- int32_t* status) {
+void HAL_SetREVPHCompressorConfig(HAL_REVPHHandle handle,
+ const HAL_REVPHCompressorConfig* config,
+ int32_t* status) {
auto pcm = pcmHandles->Get(handle);
if (pcm == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
-
- SimREVPHData[pcm->module].closedLoopEnabled = enabled;
+ // TODO
+ // SimREVPHData[pcm->module].compressorConfigType = config.
}
-
-HAL_Bool HAL_GetREVPHClosedLoopControl(HAL_REVPHHandle handle,
- int32_t* status) {
+void HAL_SetREVPHClosedLoopControlDisabled(HAL_REVPHHandle handle,
+ int32_t* status) {
auto pcm = pcmHandles->Get(handle);
if (pcm == nullptr) {
*status = HAL_HANDLE_ERROR;
- return false;
+ return;
}
+ SimREVPHData[pcm->module].compressorConfigType =
+ HAL_REVPHCompressorConfigType_kDisabled;
+}
- return SimREVPHData[pcm->module].closedLoopEnabled;
+void HAL_SetREVPHClosedLoopControlDigital(HAL_REVPHHandle handle,
+ int32_t* status) {
+ auto pcm = pcmHandles->Get(handle);
+ if (pcm == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+ SimREVPHData[pcm->module].compressorConfigType =
+ HAL_REVPHCompressorConfigType_kDigital;
+}
+
+void HAL_SetREVPHClosedLoopControlAnalog(HAL_REVPHHandle handle,
+ double minAnalogVoltage,
+ double maxAnalogVoltage,
+ int32_t* status) {
+ auto pcm = pcmHandles->Get(handle);
+ if (pcm == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+ SimREVPHData[pcm->module].compressorConfigType =
+ HAL_REVPHCompressorConfigType_kAnalog;
+}
+
+void HAL_SetREVPHClosedLoopControlHybrid(HAL_REVPHHandle handle,
+ double minAnalogVoltage,
+ double maxAnalogVoltage,
+ int32_t* status) {
+ auto pcm = pcmHandles->Get(handle);
+ if (pcm == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+ SimREVPHData[pcm->module].compressorConfigType =
+ HAL_REVPHCompressorConfigType_kHybrid;
+}
+
+HAL_REVPHCompressorConfigType HAL_GetREVPHCompressorConfig(
+ HAL_REVPHHandle handle, int32_t* status) {
+ auto pcm = pcmHandles->Get(handle);
+ if (pcm == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return HAL_REVPHCompressorConfigType_kDisabled;
+ }
+ return SimREVPHData[pcm->module].compressorConfigType;
}
HAL_Bool HAL_GetREVPHPressureSwitch(HAL_REVPHHandle handle, int32_t* status) {
@@ -129,8 +177,8 @@
return SimREVPHData[pcm->module].pressureSwitch;
}
-double HAL_GetREVPHAnalogPressure(HAL_REVPHHandle handle, int32_t channel,
- int32_t* status) {
+double HAL_GetREVPHAnalogVoltage(HAL_REVPHHandle handle, int32_t channel,
+ int32_t* status) {
return 0;
}
@@ -179,3 +227,31 @@
void HAL_FireREVPHOneShot(HAL_REVPHHandle handle, int32_t index, int32_t durMs,
int32_t* status) {}
+
+double HAL_GetREVPHVoltage(HAL_REVPHHandle handle, int32_t* status) {
+ return 0;
+}
+
+double HAL_GetREVPH5VVoltage(HAL_REVPHHandle handle, int32_t* status) {
+ return 0;
+}
+
+double HAL_GetREVPHSolenoidCurrent(HAL_REVPHHandle handle, int32_t* status) {
+ return 0;
+}
+
+double HAL_GetREVPHSolenoidVoltage(HAL_REVPHHandle handle, int32_t* status) {
+ return 0;
+}
+
+void HAL_GetREVPHVersion(HAL_REVPHHandle handle, HAL_REVPHVersion* version,
+ int32_t* status) {}
+
+void HAL_GetREVPHFaults(HAL_REVPHHandle handle, HAL_REVPHFaults* faults,
+ int32_t* status) {}
+
+void HAL_GetREVPHStickyFaults(HAL_REVPHHandle handle,
+ HAL_REVPHStickyFaults* stickyFaults,
+ int32_t* status) {}
+
+void HAL_ClearREVPHStickyFaults(HAL_REVPHHandle handle, int32_t* status) {}
diff --git a/hal/src/main/native/sim/mockdata/AccelerometerData.cpp b/hal/src/main/native/sim/mockdata/AccelerometerData.cpp
index 8ed4d78..9284830 100644
--- a/hal/src/main/native/sim/mockdata/AccelerometerData.cpp
+++ b/hal/src/main/native/sim/mockdata/AccelerometerData.cpp
@@ -9,7 +9,7 @@
namespace hal::init {
void InitializeAccelerometerData() {
- static AccelerometerData sad[1];
+ static AccelerometerData sad[kAccelerometers];
::hal::SimAccelerometerData = sad;
}
} // namespace hal::init
diff --git a/hal/src/main/native/sim/mockdata/DriverStationData.cpp b/hal/src/main/native/sim/mockdata/DriverStationData.cpp
index c704f2b..1c76a7a 100644
--- a/hal/src/main/native/sim/mockdata/DriverStationData.cpp
+++ b/hal/src/main/native/sim/mockdata/DriverStationData.cpp
@@ -30,7 +30,7 @@
fmsAttached.Reset(false);
dsAttached.Reset(true);
allianceStationId.Reset(static_cast<HAL_AllianceStationID>(0));
- matchTime.Reset(0.0);
+ matchTime.Reset(-1.0);
{
std::scoped_lock lock(m_joystickDataMutex);
diff --git a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
index e0f545e..2470b04 100644
--- a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
@@ -126,7 +126,7 @@
SimDataValue<HAL_AllianceStationID, MakeAllianceStationIdValue,
GetAllianceStationIdName>
allianceStationId{static_cast<HAL_AllianceStationID>(0)};
- SimDataValue<double, HAL_MakeDouble, GetMatchTimeName> matchTime{0.0};
+ SimDataValue<double, HAL_MakeDouble, GetMatchTimeName> matchTime{-1.0};
private:
SimCallbackRegistry<HAL_JoystickAxesCallback, GetJoystickAxesName>
diff --git a/hal/src/main/native/sim/mockdata/I2CData.cpp b/hal/src/main/native/sim/mockdata/I2CData.cpp
index 0ac813d..d3b7db6 100644
--- a/hal/src/main/native/sim/mockdata/I2CData.cpp
+++ b/hal/src/main/native/sim/mockdata/I2CData.cpp
@@ -9,7 +9,7 @@
namespace hal::init {
void InitializeI2CData() {
- static I2CData sid[2];
+ static I2CData sid[kI2CPorts];
::hal::SimI2CData = sid;
}
} // namespace hal::init
diff --git a/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h b/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h
index 4876dbd..cb3e4b3 100644
--- a/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h
@@ -9,8 +9,6 @@
#include "hal/simulation/SimDataValue.h"
namespace hal {
-constexpr int32_t kNumPDSimModules = hal::kNumREVPDHModules;
-constexpr int32_t kNumPDSimChannels = hal::kNumREVPDHChannels;
class PowerDistributionData {
HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
diff --git a/hal/src/main/native/sim/mockdata/REVPHData.cpp b/hal/src/main/native/sim/mockdata/REVPHData.cpp
index 6c0ed5a..cb1a3a8 100644
--- a/hal/src/main/native/sim/mockdata/REVPHData.cpp
+++ b/hal/src/main/native/sim/mockdata/REVPHData.cpp
@@ -21,7 +21,7 @@
}
initialized.Reset(false);
compressorOn.Reset(false);
- closedLoopEnabled.Reset(true);
+ compressorConfigType.Reset(HAL_REVPHCompressorConfigType_kDisabled);
pressureSwitch.Reset(false);
compressorCurrent.Reset(0.0);
}
@@ -39,7 +39,8 @@
SimREVPHData, solenoidOutput)
DEFINE_CAPI(HAL_Bool, Initialized, initialized)
DEFINE_CAPI(HAL_Bool, CompressorOn, compressorOn)
-DEFINE_CAPI(HAL_Bool, ClosedLoopEnabled, closedLoopEnabled)
+DEFINE_CAPI(HAL_REVPHCompressorConfigType, CompressorConfigType,
+ compressorConfigType)
DEFINE_CAPI(HAL_Bool, PressureSwitch, pressureSwitch)
DEFINE_CAPI(double, CompressorCurrent, compressorCurrent)
@@ -69,7 +70,7 @@
HAL_Bool initialNotify) {
REGISTER(initialized);
REGISTER(compressorOn);
- REGISTER(closedLoopEnabled);
+ REGISTER(compressorConfigType);
REGISTER(pressureSwitch);
REGISTER(compressorCurrent);
}
diff --git a/hal/src/main/native/sim/mockdata/REVPHDataInternal.h b/hal/src/main/native/sim/mockdata/REVPHDataInternal.h
index ebf4964..c41cbbe 100644
--- a/hal/src/main/native/sim/mockdata/REVPHDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/REVPHDataInternal.h
@@ -13,7 +13,7 @@
HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
HAL_SIMDATAVALUE_DEFINE_NAME(SolenoidOutput)
HAL_SIMDATAVALUE_DEFINE_NAME(CompressorOn)
- HAL_SIMDATAVALUE_DEFINE_NAME(ClosedLoopEnabled)
+ HAL_SIMDATAVALUE_DEFINE_NAME(CompressorConfigType)
HAL_SIMDATAVALUE_DEFINE_NAME(PressureSwitch)
HAL_SIMDATAVALUE_DEFINE_NAME(CompressorCurrent)
@@ -22,6 +22,11 @@
return false;
}
+ static inline HAL_Value MakeCompressorConfigTypeValue(
+ HAL_REVPHCompressorConfigType value) {
+ return HAL_MakeEnum(value);
+ }
+
public:
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
false};
@@ -30,8 +35,10 @@
solenoidOutput[kNumREVPHChannels];
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetCompressorOnName> compressorOn{
false};
- SimDataValue<HAL_Bool, HAL_MakeBoolean, GetClosedLoopEnabledName>
- closedLoopEnabled{true};
+ SimDataValue<HAL_REVPHCompressorConfigType, MakeCompressorConfigTypeValue,
+ GetCompressorConfigTypeName>
+ compressorConfigType{HAL_REVPHCompressorConfigType::
+ HAL_REVPHCompressorConfigType_kDisabled};
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetPressureSwitchName> pressureSwitch{
false};
SimDataValue<double, HAL_MakeDouble, GetCompressorCurrentName>
diff --git a/hal/src/main/native/sim/mockdata/SPIAccelerometerData.cpp b/hal/src/main/native/sim/mockdata/SPIAccelerometerData.cpp
index 6c5f341..0ec10cf 100644
--- a/hal/src/main/native/sim/mockdata/SPIAccelerometerData.cpp
+++ b/hal/src/main/native/sim/mockdata/SPIAccelerometerData.cpp
@@ -9,7 +9,7 @@
namespace hal::init {
void InitializeSPIAccelerometerData() {
- static SPIAccelerometerData ssad[5];
+ static SPIAccelerometerData ssad[kSPIAccelerometers];
::hal::SimSPIAccelerometerData = ssad;
}
} // namespace hal::init
diff --git a/hal/src/main/native/sim/mockdata/SPIData.cpp b/hal/src/main/native/sim/mockdata/SPIData.cpp
index 9499b9b..82f7650 100644
--- a/hal/src/main/native/sim/mockdata/SPIData.cpp
+++ b/hal/src/main/native/sim/mockdata/SPIData.cpp
@@ -9,7 +9,7 @@
namespace hal::init {
void InitializeSPIData() {
- static SPIData ssd[5];
+ static SPIData ssd[kSPIPorts];
::hal::SimSPIData = ssd;
}
} // namespace hal::init