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/athena/CTREPCM.cpp b/hal/src/main/native/athena/CTREPCM.cpp
index b000ace..37faf69 100644
--- a/hal/src/main/native/athena/CTREPCM.cpp
+++ b/hal/src/main/native/athena/CTREPCM.cpp
@@ -335,8 +335,13 @@
void HAL_ClearAllCTREPCMStickyFaults(HAL_CTREPCMHandle handle,
int32_t* status) {
+ auto pcm = pcmHandles->Get(handle);
+ if (pcm == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
uint8_t controlData[] = {0, 0, 0, 0x80};
- HAL_WriteCANPacket(handle, controlData, sizeof(controlData), Control2,
+ HAL_WriteCANPacket(pcm->canHandle, controlData, sizeof(controlData), Control2,
status);
}
@@ -393,7 +398,7 @@
(std::min)(static_cast<uint32_t>(durMs) / 10,
static_cast<uint32_t>(0xFF));
HAL_WriteCANPacketRepeating(pcm->canHandle, pcm->oneShot.sol10MsPerUnit, 8,
- Control2, SendPeriod, status);
+ Control3, SendPeriod, status);
}
} // extern "C"
diff --git a/hal/src/main/native/athena/FRCDriverStation.cpp b/hal/src/main/native/athena/FRCDriverStation.cpp
index 0f4b69b..e7ef194 100644
--- a/hal/src/main/native/athena/FRCDriverStation.cpp
+++ b/hal/src/main/native/athena/FRCDriverStation.cpp
@@ -110,10 +110,15 @@
static int32_t HAL_GetMatchInfoInternal(HAL_MatchInfo* info) {
MatchType_t matchType = MatchType_t::kMatchType_none;
+ info->gameSpecificMessageSize = sizeof(info->gameSpecificMessage);
int status = FRC_NetworkCommunication_getMatchInfo(
info->eventName, &matchType, &info->matchNumber, &info->replayNumber,
info->gameSpecificMessage, &info->gameSpecificMessageSize);
+ if (info->gameSpecificMessageSize > sizeof(info->gameSpecificMessage)) {
+ info->gameSpecificMessageSize = 0;
+ }
+
info->matchType = static_cast<HAL_MatchType>(matchType);
*(std::end(info->eventName) - 1) = '\0';
diff --git a/hal/src/main/native/athena/HAL.cpp b/hal/src/main/native/athena/HAL.cpp
index 0b6d05e..93e5c15 100644
--- a/hal/src/main/native/athena/HAL.cpp
+++ b/hal/src/main/native/athena/HAL.cpp
@@ -34,6 +34,7 @@
static std::unique_ptr<tGlobal> global;
static std::unique_ptr<tSysWatchdog> watchdog;
+static uint64_t dsStartTime;
using namespace hal;
@@ -86,6 +87,11 @@
&status);
global->strobeInterruptForceOnce(&status);
}
+
+uint64_t GetDSInitializeTime() {
+ return dsStartTime;
+}
+
} // namespace hal
extern "C" {
@@ -420,6 +426,11 @@
HAL_InitializeDriverStation();
+ dsStartTime = HAL_GetFPGATime(&status);
+ if (status != 0) {
+ return false;
+ }
+
// Set WPI_Now to use FPGA timestamp
wpi::SetNowImpl([]() -> uint64_t {
int32_t status = 0;
diff --git a/hal/src/main/native/athena/HALInternal.h b/hal/src/main/native/athena/HALInternal.h
index 64a0dca..52a818b 100644
--- a/hal/src/main/native/athena/HALInternal.h
+++ b/hal/src/main/native/athena/HALInternal.h
@@ -17,4 +17,5 @@
void SetLastErrorPreviouslyAllocated(int32_t* status, std::string_view message,
int32_t channel,
std::string_view previousAllocation);
+uint64_t GetDSInitializeTime();
} // namespace hal
diff --git a/hal/src/main/native/athena/I2C.cpp b/hal/src/main/native/athena/I2C.cpp
index 93e280e..479f646 100644
--- a/hal/src/main/native/athena/I2C.cpp
+++ b/hal/src/main/native/athena/I2C.cpp
@@ -54,6 +54,10 @@
}
if (port == HAL_I2C_kOnboard) {
+ HAL_SendError(0, 0, 0,
+ "Onboard I2C port is subject to system lockups. See Known "
+ "Issues page for details",
+ "", "", true);
std::scoped_lock lock(digitalI2COnBoardMutex);
i2COnboardObjCount++;
if (i2COnboardObjCount > 1) {
diff --git a/hal/src/main/native/athena/PowerDistribution.cpp b/hal/src/main/native/athena/PowerDistribution.cpp
index f7fe88f..0d2b963 100644
--- a/hal/src/main/native/athena/PowerDistribution.cpp
+++ b/hal/src/main/native/athena/PowerDistribution.cpp
@@ -4,11 +4,15 @@
#include "hal/PowerDistribution.h"
+#include <cstring>
+#include <thread>
+
#include "CTREPDP.h"
#include "HALInternal.h"
#include "PortsInternal.h"
#include "REVPDH.h"
#include "hal/Errors.h"
+#include "hal/HALBase.h"
#include "hal/handles/HandlesInternal.h"
using namespace hal;
@@ -19,7 +23,41 @@
int32_t moduleNumber, HAL_PowerDistributionType type,
const char* allocationLocation, int32_t* status) {
if (type == HAL_PowerDistributionType::HAL_PowerDistributionType_kAutomatic) {
- type = HAL_PowerDistributionType::HAL_PowerDistributionType_kCTRE;
+ if (moduleNumber != HAL_DEFAULT_POWER_DISTRIBUTION_MODULE) {
+ *status = PARAMETER_OUT_OF_RANGE;
+ hal::SetLastError(
+ status, "Automatic PowerDistributionType must have default module");
+ return HAL_kInvalidHandle;
+ }
+
+ uint64_t waitTime = hal::GetDSInitializeTime() + 400000;
+
+ // Ensure we have been alive for long enough to receive a few Power packets.
+ do {
+ uint64_t currentTime = HAL_GetFPGATime(status);
+ if (*status != 0) {
+ return HAL_kInvalidHandle;
+ }
+ if (currentTime >= waitTime) {
+ break;
+ }
+ std::this_thread::sleep_for(
+ std::chrono::microseconds(waitTime - currentTime));
+ } while (true);
+
+ // Try PDP first
+ auto pdpHandle = HAL_InitializePDP(0, allocationLocation, status);
+ if (pdpHandle != HAL_kInvalidHandle) {
+ *status = 0;
+ HAL_GetPDPVoltage(pdpHandle, status);
+ if (*status == 0 || *status == HAL_CAN_TIMEOUT) {
+ return static_cast<HAL_PowerDistributionHandle>(pdpHandle);
+ }
+ HAL_CleanPDP(pdpHandle);
+ }
+ *status = 0;
+ auto pdhHandle = HAL_InitializeREVPDH(1, allocationLocation, status);
+ return static_cast<HAL_PowerDistributionHandle>(pdhHandle);
}
if (type == HAL_PowerDistributionType::HAL_PowerDistributionType_kCTRE) {
@@ -27,13 +65,13 @@
moduleNumber = 0;
}
return static_cast<HAL_PowerDistributionHandle>(
- HAL_InitializePDP(moduleNumber, allocationLocation, status)); // TODO
+ HAL_InitializePDP(moduleNumber, allocationLocation, status));
} else {
if (moduleNumber == HAL_DEFAULT_POWER_DISTRIBUTION_MODULE) {
moduleNumber = 1;
}
return static_cast<HAL_PowerDistributionHandle>(
- HAL_REV_InitializePDH(moduleNumber, allocationLocation, status));
+ HAL_InitializeREVPDH(moduleNumber, allocationLocation, status));
}
}
@@ -43,7 +81,7 @@
if (IsCtre(handle)) {
HAL_CleanPDP(handle);
} else {
- HAL_REV_FreePDH(handle);
+ HAL_FreeREVPDH(handle);
}
}
@@ -52,7 +90,7 @@
if (IsCtre(handle)) {
return HAL_GetPDPModuleNumber(handle, status);
} else {
- return HAL_REV_GetPDHModuleNumber(handle, status);
+ return HAL_GetREVPDHModuleNumber(handle, status);
}
}
@@ -61,7 +99,7 @@
if (IsCtre(handle)) {
return HAL_CheckPDPChannel(channel);
} else {
- return HAL_REV_CheckPDHChannelNumber(channel);
+ return HAL_CheckREVPDHChannelNumber(channel);
}
}
@@ -70,7 +108,7 @@
if (type == HAL_PowerDistributionType::HAL_PowerDistributionType_kCTRE) {
return HAL_CheckPDPModule(module);
} else {
- return HAL_REV_CheckPDHModuleNumber(module);
+ return HAL_CheckREVPDHModuleNumber(module);
}
}
@@ -105,7 +143,7 @@
if (IsCtre(handle)) {
return HAL_GetPDPVoltage(handle, status);
} else {
- return HAL_REV_GetPDHSupplyVoltage(handle, status);
+ return HAL_GetREVPDHVoltage(handle, status);
}
}
@@ -114,7 +152,7 @@
if (IsCtre(handle)) {
return HAL_GetPDPChannelCurrent(handle, channel, status);
} else {
- return HAL_REV_GetPDHChannelCurrent(handle, channel, status);
+ return HAL_GetREVPDHChannelCurrent(handle, channel, status);
}
}
@@ -134,7 +172,7 @@
SetLastError(status, "Output array not large enough");
return;
}
- return HAL_REV_GetPDHAllChannelCurrents(handle, currents, status);
+ return HAL_GetREVPDHAllChannelCurrents(handle, currents, status);
}
}
@@ -143,7 +181,7 @@
if (IsCtre(handle)) {
return HAL_GetPDPTotalCurrent(handle, status);
} else {
- return HAL_REV_GetPDHTotalCurrent(handle, status);
+ return HAL_GetREVPDHTotalCurrent(handle, status);
}
}
@@ -181,7 +219,7 @@
if (IsCtre(handle)) {
HAL_ClearPDPStickyFaults(handle, status);
} else {
- HAL_REV_ClearPDHFaults(handle, status);
+ HAL_ClearREVPDHStickyFaults(handle, status);
}
}
@@ -191,7 +229,7 @@
// No-op on CTRE
return;
} else {
- HAL_REV_SetPDHSwitchableChannel(handle, enabled, status);
+ HAL_SetREVPDHSwitchableChannel(handle, enabled, status);
}
}
@@ -201,7 +239,37 @@
// No-op on CTRE
return false;
} else {
- return HAL_REV_GetPDHSwitchableChannelState(handle, status);
+ return HAL_GetREVPDHSwitchableChannelState(handle, status);
+ }
+}
+
+void HAL_GetPowerDistributionVersion(HAL_PowerDistributionHandle handle,
+ HAL_PowerDistributionVersion* version,
+ int32_t* status) {
+ if (IsCtre(handle)) {
+ std::memset(version, 0, sizeof(*version));
+ } else {
+ HAL_GetREVPDHVersion(handle, version, status);
+ }
+}
+
+void HAL_GetPowerDistributionFaults(HAL_PowerDistributionHandle handle,
+ HAL_PowerDistributionFaults* faults,
+ int32_t* status) {
+ if (IsCtre(handle)) {
+ std::memset(faults, 0, sizeof(*faults));
+ } else {
+ HAL_GetREVPDHFaults(handle, faults, status);
+ }
+}
+
+void HAL_GetPowerDistributionStickyFaults(
+ HAL_PowerDistributionHandle handle,
+ HAL_PowerDistributionStickyFaults* stickyFaults, int32_t* status) {
+ if (IsCtre(handle)) {
+ std::memset(stickyFaults, 0, sizeof(*stickyFaults));
+ } else {
+ HAL_GetREVPDHStickyFaults(handle, stickyFaults, status);
}
}
diff --git a/hal/src/main/native/athena/REVPDH.cpp b/hal/src/main/native/athena/REVPDH.cpp
index 9ad45b5..10c019d 100644
--- a/hal/src/main/native/athena/REVPDH.cpp
+++ b/hal/src/main/native/athena/REVPDH.cpp
@@ -11,6 +11,7 @@
#include <hal/handles/IndexedHandleResource.h>
#include <cstring>
+#include <thread>
#include <fmt/format.h>
@@ -35,6 +36,7 @@
int32_t controlPeriod;
HAL_CANHandle hcan;
std::string previousAllocation;
+ HAL_PowerDistributionVersion versionInfo;
};
} // namespace
@@ -43,32 +45,26 @@
return (extId >> 6) & 0x3FF;
}
-static constexpr uint32_t PDH_SWITCH_CHANNEL_SET_FRAME_API =
- APIFromExtId(PDH_SWITCH_CHANNEL_SET_FRAME_ID);
+static constexpr uint32_t PDH_SET_SWITCH_CHANNEL_FRAME_API =
+ APIFromExtId(PDH_SET_SWITCH_CHANNEL_FRAME_ID);
-static constexpr uint32_t PDH_STATUS0_FRAME_API =
- APIFromExtId(PDH_STATUS0_FRAME_ID);
-static constexpr uint32_t PDH_STATUS1_FRAME_API =
- APIFromExtId(PDH_STATUS1_FRAME_ID);
-static constexpr uint32_t PDH_STATUS2_FRAME_API =
- APIFromExtId(PDH_STATUS2_FRAME_ID);
-static constexpr uint32_t PDH_STATUS3_FRAME_API =
- APIFromExtId(PDH_STATUS3_FRAME_ID);
-static constexpr uint32_t PDH_STATUS4_FRAME_API =
- APIFromExtId(PDH_STATUS4_FRAME_ID);
+static constexpr uint32_t PDH_STATUS_0_FRAME_API =
+ APIFromExtId(PDH_STATUS_0_FRAME_ID);
+static constexpr uint32_t PDH_STATUS_1_FRAME_API =
+ APIFromExtId(PDH_STATUS_1_FRAME_ID);
+static constexpr uint32_t PDH_STATUS_2_FRAME_API =
+ APIFromExtId(PDH_STATUS_2_FRAME_ID);
+static constexpr uint32_t PDH_STATUS_3_FRAME_API =
+ APIFromExtId(PDH_STATUS_3_FRAME_ID);
+static constexpr uint32_t PDH_STATUS_4_FRAME_API =
+ APIFromExtId(PDH_STATUS_4_FRAME_ID);
static constexpr uint32_t PDH_CLEAR_FAULTS_FRAME_API =
APIFromExtId(PDH_CLEAR_FAULTS_FRAME_ID);
-static constexpr uint32_t PDH_IDENTIFY_FRAME_API =
- APIFromExtId(PDH_IDENTIFY_FRAME_ID);
-
static constexpr uint32_t PDH_VERSION_FRAME_API =
APIFromExtId(PDH_VERSION_FRAME_ID);
-static constexpr uint32_t PDH_CONFIGURE_HR_CHANNEL_FRAME_API =
- APIFromExtId(PDH_CONFIGURE_HR_CHANNEL_FRAME_ID);
-
static constexpr int32_t kPDHFrameStatus0Timeout = 20;
static constexpr int32_t kPDHFrameStatus1Timeout = 20;
static constexpr int32_t kPDHFrameStatus2Timeout = 20;
@@ -89,97 +85,97 @@
extern "C" {
-static PDH_status0_t HAL_REV_ReadPDHStatus0(HAL_CANHandle hcan,
+static PDH_status_0_t HAL_ReadREVPDHStatus0(HAL_CANHandle hcan,
int32_t* status) {
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
- PDH_status0_t result = {};
+ PDH_status_0_t result = {};
- HAL_ReadCANPacketTimeout(hcan, PDH_STATUS0_FRAME_API, packedData, &length,
+ HAL_ReadCANPacketTimeout(hcan, PDH_STATUS_0_FRAME_API, packedData, &length,
×tamp, kPDHFrameStatus0Timeout * 2, status);
if (*status != 0) {
return result;
}
- PDH_status0_unpack(&result, packedData, PDH_STATUS0_LENGTH);
+ PDH_status_0_unpack(&result, packedData, PDH_STATUS_0_LENGTH);
return result;
}
-static PDH_status1_t HAL_REV_ReadPDHStatus1(HAL_CANHandle hcan,
+static PDH_status_1_t HAL_ReadREVPDHStatus1(HAL_CANHandle hcan,
int32_t* status) {
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
- PDH_status1_t result = {};
+ PDH_status_1_t result = {};
- HAL_ReadCANPacketTimeout(hcan, PDH_STATUS1_FRAME_API, packedData, &length,
+ HAL_ReadCANPacketTimeout(hcan, PDH_STATUS_1_FRAME_API, packedData, &length,
×tamp, kPDHFrameStatus1Timeout * 2, status);
if (*status != 0) {
return result;
}
- PDH_status1_unpack(&result, packedData, PDH_STATUS1_LENGTH);
+ PDH_status_1_unpack(&result, packedData, PDH_STATUS_1_LENGTH);
return result;
}
-static PDH_status2_t HAL_REV_ReadPDHStatus2(HAL_CANHandle hcan,
+static PDH_status_2_t HAL_ReadREVPDHStatus2(HAL_CANHandle hcan,
int32_t* status) {
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
- PDH_status2_t result = {};
+ PDH_status_2_t result = {};
- HAL_ReadCANPacketTimeout(hcan, PDH_STATUS2_FRAME_API, packedData, &length,
+ HAL_ReadCANPacketTimeout(hcan, PDH_STATUS_2_FRAME_API, packedData, &length,
×tamp, kPDHFrameStatus2Timeout * 2, status);
if (*status != 0) {
return result;
}
- PDH_status2_unpack(&result, packedData, PDH_STATUS2_LENGTH);
+ PDH_status_2_unpack(&result, packedData, PDH_STATUS_2_LENGTH);
return result;
}
-static PDH_status3_t HAL_REV_ReadPDHStatus3(HAL_CANHandle hcan,
+static PDH_status_3_t HAL_ReadREVPDHStatus3(HAL_CANHandle hcan,
int32_t* status) {
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
- PDH_status3_t result = {};
+ PDH_status_3_t result = {};
- HAL_ReadCANPacketTimeout(hcan, PDH_STATUS3_FRAME_API, packedData, &length,
+ HAL_ReadCANPacketTimeout(hcan, PDH_STATUS_3_FRAME_API, packedData, &length,
×tamp, kPDHFrameStatus3Timeout * 2, status);
if (*status != 0) {
return result;
}
- PDH_status3_unpack(&result, packedData, PDH_STATUS3_LENGTH);
+ PDH_status_3_unpack(&result, packedData, PDH_STATUS_3_LENGTH);
return result;
}
-static PDH_status4_t HAL_REV_ReadPDHStatus4(HAL_CANHandle hcan,
+static PDH_status_4_t HAL_ReadREVPDHStatus4(HAL_CANHandle hcan,
int32_t* status) {
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
- PDH_status4_t result = {};
+ PDH_status_4_t result = {};
- HAL_ReadCANPacketTimeout(hcan, PDH_STATUS4_FRAME_API, packedData, &length,
+ HAL_ReadCANPacketTimeout(hcan, PDH_STATUS_4_FRAME_API, packedData, &length,
×tamp, kPDHFrameStatus4Timeout * 2, status);
if (*status != 0) {
return result;
}
- PDH_status4_unpack(&result, packedData, PDH_STATUS4_LENGTH);
+ PDH_status_4_unpack(&result, packedData, PDH_STATUS_4_LENGTH);
return result;
}
@@ -187,23 +183,23 @@
/**
* Helper function for the individual getter functions for status 4
*/
-PDH_status4_t HAL_REV_GetPDHStatus4(HAL_REVPDHHandle handle, int32_t* status) {
- PDH_status4_t statusFrame = {};
+PDH_status_4_t HAL_GetREVPDHStatus4(HAL_REVPDHHandle handle, int32_t* status) {
+ PDH_status_4_t statusFrame = {};
auto hpdh = REVPDHHandles->Get(handle);
if (hpdh == nullptr) {
*status = HAL_HANDLE_ERROR;
return statusFrame;
}
- statusFrame = HAL_REV_ReadPDHStatus4(hpdh->hcan, status);
+ statusFrame = HAL_ReadREVPDHStatus4(hpdh->hcan, status);
return statusFrame;
}
-HAL_REVPDHHandle HAL_REV_InitializePDH(int32_t module,
- const char* allocationLocation,
- int32_t* status) {
+HAL_REVPDHHandle HAL_InitializeREVPDH(int32_t module,
+ const char* allocationLocation,
+ int32_t* status) {
hal::init::CheckInit();
- if (!HAL_REV_CheckPDHModuleNumber(module)) {
+ if (!HAL_CheckREVPDHModuleNumber(module)) {
*status = RESOURCE_OUT_OF_RANGE;
return HAL_kInvalidHandle;
}
@@ -232,11 +228,12 @@
hpdh->previousAllocation = allocationLocation ? allocationLocation : "";
hpdh->hcan = hcan;
hpdh->controlPeriod = kDefaultControlPeriod;
+ std::memset(&hpdh->versionInfo, 0, sizeof(hpdh->versionInfo));
return handle;
}
-void HAL_REV_FreePDH(HAL_REVPDHHandle handle) {
+void HAL_FreeREVPDH(HAL_REVPDHHandle handle) {
auto hpdh = REVPDHHandles->Get(handle);
if (hpdh == nullptr) {
return;
@@ -247,27 +244,27 @@
REVPDHHandles->Free(handle);
}
-int32_t HAL_REV_GetPDHModuleNumber(HAL_REVPDHHandle handle, int32_t* status) {
+int32_t HAL_GetREVPDHModuleNumber(HAL_REVPDHHandle handle, int32_t* status) {
return hal::getHandleIndex(handle);
}
-HAL_Bool HAL_REV_CheckPDHModuleNumber(int32_t module) {
+HAL_Bool HAL_CheckREVPDHModuleNumber(int32_t module) {
return ((module >= 1) && (module < kNumREVPDHModules)) ? 1 : 0;
}
-HAL_Bool HAL_REV_CheckPDHChannelNumber(int32_t channel) {
+HAL_Bool HAL_CheckREVPDHChannelNumber(int32_t channel) {
return ((channel >= 0) && (channel < kNumREVPDHChannels)) ? 1 : 0;
}
-double HAL_REV_GetPDHChannelCurrent(HAL_REVPDHHandle handle, int32_t channel,
- int32_t* status) {
+double HAL_GetREVPDHChannelCurrent(HAL_REVPDHHandle handle, int32_t channel,
+ int32_t* status) {
auto hpdh = REVPDHHandles->Get(handle);
if (hpdh == nullptr) {
*status = HAL_HANDLE_ERROR;
return 0;
}
- if (!HAL_REV_CheckPDHChannelNumber(channel)) {
+ if (!HAL_CheckREVPDHChannelNumber(channel)) {
*status = RESOURCE_OUT_OF_RANGE;
return 0;
}
@@ -275,174 +272,101 @@
// Determine what periodic status the channel is in
if (channel < 6) {
// Periodic status 0
- PDH_status0_t statusFrame = HAL_REV_ReadPDHStatus0(hpdh->hcan, status);
+ PDH_status_0_t statusFrame = HAL_ReadREVPDHStatus0(hpdh->hcan, status);
switch (channel) {
case 0:
- return PDH_status0_channel_0_current_decode(
+ return PDH_status_0_channel_0_current_decode(
statusFrame.channel_0_current);
case 1:
- return PDH_status0_channel_1_current_decode(
+ return PDH_status_0_channel_1_current_decode(
statusFrame.channel_1_current);
case 2:
- return PDH_status0_channel_2_current_decode(
+ return PDH_status_0_channel_2_current_decode(
statusFrame.channel_2_current);
case 3:
- return PDH_status0_channel_3_current_decode(
+ return PDH_status_0_channel_3_current_decode(
statusFrame.channel_3_current);
case 4:
- return PDH_status0_channel_4_current_decode(
+ return PDH_status_0_channel_4_current_decode(
statusFrame.channel_4_current);
case 5:
- return PDH_status0_channel_5_current_decode(
+ return PDH_status_0_channel_5_current_decode(
statusFrame.channel_5_current);
}
} else if (channel < 12) {
// Periodic status 1
- PDH_status1_t statusFrame = HAL_REV_ReadPDHStatus1(hpdh->hcan, status);
+ PDH_status_1_t statusFrame = HAL_ReadREVPDHStatus1(hpdh->hcan, status);
switch (channel) {
case 6:
- return PDH_status1_channel_6_current_decode(
+ return PDH_status_1_channel_6_current_decode(
statusFrame.channel_6_current);
case 7:
- return PDH_status1_channel_7_current_decode(
+ return PDH_status_1_channel_7_current_decode(
statusFrame.channel_7_current);
case 8:
- return PDH_status1_channel_8_current_decode(
+ return PDH_status_1_channel_8_current_decode(
statusFrame.channel_8_current);
case 9:
- return PDH_status1_channel_9_current_decode(
+ return PDH_status_1_channel_9_current_decode(
statusFrame.channel_9_current);
case 10:
- return PDH_status1_channel_10_current_decode(
+ return PDH_status_1_channel_10_current_decode(
statusFrame.channel_10_current);
case 11:
- return PDH_status1_channel_11_current_decode(
+ return PDH_status_1_channel_11_current_decode(
statusFrame.channel_11_current);
}
} else if (channel < 18) {
// Periodic status 2
- PDH_status2_t statusFrame = HAL_REV_ReadPDHStatus2(hpdh->hcan, status);
+ PDH_status_2_t statusFrame = HAL_ReadREVPDHStatus2(hpdh->hcan, status);
switch (channel) {
case 12:
- return PDH_status2_channel_12_current_decode(
+ return PDH_status_2_channel_12_current_decode(
statusFrame.channel_12_current);
case 13:
- return PDH_status2_channel_13_current_decode(
+ return PDH_status_2_channel_13_current_decode(
statusFrame.channel_13_current);
case 14:
- return PDH_status2_channel_14_current_decode(
+ return PDH_status_2_channel_14_current_decode(
statusFrame.channel_14_current);
case 15:
- return PDH_status2_channel_15_current_decode(
+ return PDH_status_2_channel_15_current_decode(
statusFrame.channel_15_current);
case 16:
- return PDH_status2_channel_16_current_decode(
+ return PDH_status_2_channel_16_current_decode(
statusFrame.channel_16_current);
case 17:
- return PDH_status2_channel_17_current_decode(
+ return PDH_status_2_channel_17_current_decode(
statusFrame.channel_17_current);
}
} else if (channel < 24) {
// Periodic status 3
- PDH_status3_t statusFrame = HAL_REV_ReadPDHStatus3(hpdh->hcan, status);
+ PDH_status_3_t statusFrame = HAL_ReadREVPDHStatus3(hpdh->hcan, status);
switch (channel) {
case 18:
- return PDH_status3_channel_18_current_decode(
+ return PDH_status_3_channel_18_current_decode(
statusFrame.channel_18_current);
case 19:
- return PDH_status3_channel_19_current_decode(
+ return PDH_status_3_channel_19_current_decode(
statusFrame.channel_19_current);
case 20:
- return PDH_status3_channel_20_current_decode(
+ return PDH_status_3_channel_20_current_decode(
statusFrame.channel_20_current);
case 21:
- return PDH_status3_channel_21_current_decode(
+ return PDH_status_3_channel_21_current_decode(
statusFrame.channel_21_current);
case 22:
- return PDH_status3_channel_22_current_decode(
+ return PDH_status_3_channel_22_current_decode(
statusFrame.channel_22_current);
case 23:
- return PDH_status3_channel_23_current_decode(
+ return PDH_status_3_channel_23_current_decode(
statusFrame.channel_23_current);
}
}
return 0;
}
-void HAL_REV_GetPDHAllChannelCurrents(HAL_REVPDHHandle handle, double* currents,
- int32_t* status) {
- auto hpdh = REVPDHHandles->Get(handle);
- if (hpdh == nullptr) {
- *status = HAL_HANDLE_ERROR;
- return;
- }
-
- PDH_status0_t statusFrame0 = HAL_REV_ReadPDHStatus0(hpdh->hcan, status);
- PDH_status1_t statusFrame1 = HAL_REV_ReadPDHStatus1(hpdh->hcan, status);
- PDH_status2_t statusFrame2 = HAL_REV_ReadPDHStatus2(hpdh->hcan, status);
- PDH_status3_t statusFrame3 = HAL_REV_ReadPDHStatus3(hpdh->hcan, status);
-
- currents[0] =
- PDH_status0_channel_0_current_decode(statusFrame0.channel_0_current);
- currents[1] =
- PDH_status0_channel_1_current_decode(statusFrame0.channel_1_current);
- currents[2] =
- PDH_status0_channel_2_current_decode(statusFrame0.channel_2_current);
- currents[3] =
- PDH_status0_channel_3_current_decode(statusFrame0.channel_3_current);
- currents[4] =
- PDH_status0_channel_4_current_decode(statusFrame0.channel_4_current);
- currents[5] =
- PDH_status0_channel_5_current_decode(statusFrame0.channel_5_current);
- currents[6] =
- PDH_status1_channel_6_current_decode(statusFrame1.channel_6_current);
- currents[7] =
- PDH_status1_channel_7_current_decode(statusFrame1.channel_7_current);
- currents[8] =
- PDH_status1_channel_8_current_decode(statusFrame1.channel_8_current);
- currents[9] =
- PDH_status1_channel_9_current_decode(statusFrame1.channel_9_current);
- currents[10] =
- PDH_status1_channel_10_current_decode(statusFrame1.channel_10_current);
- currents[11] =
- PDH_status1_channel_11_current_decode(statusFrame1.channel_11_current);
- currents[12] =
- PDH_status2_channel_12_current_decode(statusFrame2.channel_12_current);
- currents[13] =
- PDH_status2_channel_13_current_decode(statusFrame2.channel_13_current);
- currents[14] =
- PDH_status2_channel_14_current_decode(statusFrame2.channel_14_current);
- currents[15] =
- PDH_status2_channel_15_current_decode(statusFrame2.channel_15_current);
- currents[16] =
- PDH_status2_channel_16_current_decode(statusFrame2.channel_16_current);
- currents[17] =
- PDH_status2_channel_17_current_decode(statusFrame2.channel_17_current);
- currents[18] =
- PDH_status3_channel_18_current_decode(statusFrame3.channel_18_current);
- currents[19] =
- PDH_status3_channel_19_current_decode(statusFrame3.channel_19_current);
- currents[20] =
- PDH_status3_channel_20_current_decode(statusFrame3.channel_20_current);
- currents[21] =
- PDH_status3_channel_21_current_decode(statusFrame3.channel_21_current);
- currents[22] =
- PDH_status3_channel_22_current_decode(statusFrame3.channel_22_current);
- currents[23] =
- PDH_status3_channel_23_current_decode(statusFrame3.channel_23_current);
-}
-
-uint16_t HAL_REV_GetPDHTotalCurrent(HAL_REVPDHHandle handle, int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0;
- }
-
- return PDH_status4_total_current_decode(statusFrame.total_current);
-}
-
-void HAL_REV_SetPDHSwitchableChannel(HAL_REVPDHHandle handle, HAL_Bool enabled,
+void HAL_GetREVPDHAllChannelCurrents(HAL_REVPDHHandle handle, double* currents,
int32_t* status) {
auto hpdh = REVPDHHandles->Get(handle);
if (hpdh == nullptr) {
@@ -450,291 +374,115 @@
return;
}
- uint8_t packedData[8] = {0};
- PDH_switch_channel_set_t frame;
- frame.output_set_value = enabled;
- frame.use_system_enable = false;
- PDH_switch_channel_set_pack(packedData, &frame, 1);
+ PDH_status_0_t statusFrame0 = HAL_ReadREVPDHStatus0(hpdh->hcan, status);
+ PDH_status_1_t statusFrame1 = HAL_ReadREVPDHStatus1(hpdh->hcan, status);
+ PDH_status_2_t statusFrame2 = HAL_ReadREVPDHStatus2(hpdh->hcan, status);
+ PDH_status_3_t statusFrame3 = HAL_ReadREVPDHStatus3(hpdh->hcan, status);
- HAL_WriteCANPacket(hpdh->hcan, packedData, PDH_SWITCH_CHANNEL_SET_LENGTH,
- PDH_SWITCH_CHANNEL_SET_FRAME_API, status);
+ currents[0] =
+ PDH_status_0_channel_0_current_decode(statusFrame0.channel_0_current);
+ currents[1] =
+ PDH_status_0_channel_1_current_decode(statusFrame0.channel_1_current);
+ currents[2] =
+ PDH_status_0_channel_2_current_decode(statusFrame0.channel_2_current);
+ currents[3] =
+ PDH_status_0_channel_3_current_decode(statusFrame0.channel_3_current);
+ currents[4] =
+ PDH_status_0_channel_4_current_decode(statusFrame0.channel_4_current);
+ currents[5] =
+ PDH_status_0_channel_5_current_decode(statusFrame0.channel_5_current);
+ currents[6] =
+ PDH_status_1_channel_6_current_decode(statusFrame1.channel_6_current);
+ currents[7] =
+ PDH_status_1_channel_7_current_decode(statusFrame1.channel_7_current);
+ currents[8] =
+ PDH_status_1_channel_8_current_decode(statusFrame1.channel_8_current);
+ currents[9] =
+ PDH_status_1_channel_9_current_decode(statusFrame1.channel_9_current);
+ currents[10] =
+ PDH_status_1_channel_10_current_decode(statusFrame1.channel_10_current);
+ currents[11] =
+ PDH_status_1_channel_11_current_decode(statusFrame1.channel_11_current);
+ currents[12] =
+ PDH_status_2_channel_12_current_decode(statusFrame2.channel_12_current);
+ currents[13] =
+ PDH_status_2_channel_13_current_decode(statusFrame2.channel_13_current);
+ currents[14] =
+ PDH_status_2_channel_14_current_decode(statusFrame2.channel_14_current);
+ currents[15] =
+ PDH_status_2_channel_15_current_decode(statusFrame2.channel_15_current);
+ currents[16] =
+ PDH_status_2_channel_16_current_decode(statusFrame2.channel_16_current);
+ currents[17] =
+ PDH_status_2_channel_17_current_decode(statusFrame2.channel_17_current);
+ currents[18] =
+ PDH_status_3_channel_18_current_decode(statusFrame3.channel_18_current);
+ currents[19] =
+ PDH_status_3_channel_19_current_decode(statusFrame3.channel_19_current);
+ currents[20] =
+ PDH_status_3_channel_20_current_decode(statusFrame3.channel_20_current);
+ currents[21] =
+ PDH_status_3_channel_21_current_decode(statusFrame3.channel_21_current);
+ currents[22] =
+ PDH_status_3_channel_22_current_decode(statusFrame3.channel_22_current);
+ currents[23] =
+ PDH_status_3_channel_23_current_decode(statusFrame3.channel_23_current);
}
-HAL_Bool HAL_REV_GetPDHSwitchableChannelState(HAL_REVPDHHandle handle,
- int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
+uint16_t HAL_GetREVPDHTotalCurrent(HAL_REVPDHHandle handle, int32_t* status) {
+ PDH_status_4_t statusFrame = HAL_GetREVPDHStatus4(handle, status);
if (*status != 0) {
- return 0.0;
+ return 0;
}
- return PDH_status4_sw_state_decode(statusFrame.sw_state);
+ return PDH_status_4_total_current_decode(statusFrame.total_current);
}
-HAL_Bool HAL_REV_CheckPDHChannelBrownout(HAL_REVPDHHandle handle,
- int32_t channel, int32_t* status) {
+void HAL_SetREVPDHSwitchableChannel(HAL_REVPDHHandle handle, HAL_Bool enabled,
+ int32_t* status) {
auto hpdh = REVPDHHandles->Get(handle);
if (hpdh == nullptr) {
*status = HAL_HANDLE_ERROR;
- return 0;
+ return;
}
- if (!HAL_REV_CheckPDHChannelNumber(channel)) {
- *status = RESOURCE_OUT_OF_RANGE;
- return 0;
- }
+ uint8_t packedData[8] = {0};
+ PDH_set_switch_channel_t frame;
+ frame.output_set_value = enabled;
+ PDH_set_switch_channel_pack(packedData, &frame,
+ PDH_SET_SWITCH_CHANNEL_LENGTH);
- // Determine what periodic status the channel is in
- if (channel < 4) {
- // Periodic status 0
- PDH_status0_t statusFrame = HAL_REV_ReadPDHStatus0(hpdh->hcan, status);
- switch (channel) {
- case 0:
- return PDH_status0_channel_0_brownout_decode(
- statusFrame.channel_0_brownout);
- case 1:
- return PDH_status0_channel_1_brownout_decode(
- statusFrame.channel_1_brownout);
- case 2:
- return PDH_status0_channel_2_brownout_decode(
- statusFrame.channel_2_brownout);
- case 3:
- return PDH_status0_channel_3_brownout_decode(
- statusFrame.channel_3_brownout);
- }
- } else if (channel < 8) {
- // Periodic status 1
- PDH_status1_t statusFrame = HAL_REV_ReadPDHStatus1(hpdh->hcan, status);
- switch (channel) {
- case 4:
- return PDH_status1_channel_4_brownout_decode(
- statusFrame.channel_4_brownout);
- case 5:
- return PDH_status1_channel_5_brownout_decode(
- statusFrame.channel_5_brownout);
- case 6:
- return PDH_status1_channel_6_brownout_decode(
- statusFrame.channel_6_brownout);
- case 7:
- return PDH_status1_channel_7_brownout_decode(
- statusFrame.channel_7_brownout);
- }
- } else if (channel < 12) {
- // Periodic status 2
- PDH_status2_t statusFrame = HAL_REV_ReadPDHStatus2(hpdh->hcan, status);
- switch (channel) {
- case 8:
- return PDH_status2_channel_8_brownout_decode(
- statusFrame.channel_8_brownout);
- case 9:
- return PDH_status2_channel_9_brownout_decode(
- statusFrame.channel_9_brownout);
- case 10:
- return PDH_status2_channel_10_brownout_decode(
- statusFrame.channel_10_brownout);
- case 11:
- return PDH_status2_channel_11_brownout_decode(
- statusFrame.channel_11_brownout);
- }
- } else if (channel < 24) {
- // Periodic status 3
- PDH_status3_t statusFrame = HAL_REV_ReadPDHStatus3(hpdh->hcan, status);
- switch (channel) {
- case 12:
- return PDH_status3_channel_12_brownout_decode(
- statusFrame.channel_12_brownout);
- case 13:
- return PDH_status3_channel_13_brownout_decode(
- statusFrame.channel_13_brownout);
- case 14:
- return PDH_status3_channel_14_brownout_decode(
- statusFrame.channel_14_brownout);
- case 15:
- return PDH_status3_channel_15_brownout_decode(
- statusFrame.channel_15_brownout);
- case 16:
- return PDH_status3_channel_16_brownout_decode(
- statusFrame.channel_16_brownout);
- case 17:
- return PDH_status3_channel_17_brownout_decode(
- statusFrame.channel_17_brownout);
- case 18:
- return PDH_status3_channel_18_brownout_decode(
- statusFrame.channel_18_brownout);
- case 19:
- return PDH_status3_channel_19_brownout_decode(
- statusFrame.channel_19_brownout);
- case 20:
- return PDH_status3_channel_20_brownout_decode(
- statusFrame.channel_20_brownout);
- case 21:
- return PDH_status3_channel_21_brownout_decode(
- statusFrame.channel_21_brownout);
- case 22:
- return PDH_status3_channel_22_brownout_decode(
- statusFrame.channel_22_brownout);
- case 23:
- return PDH_status3_channel_23_brownout_decode(
- statusFrame.channel_23_brownout);
- }
- }
- return 0;
+ HAL_WriteCANPacket(hpdh->hcan, packedData, PDH_SET_SWITCH_CHANNEL_LENGTH,
+ PDH_SET_SWITCH_CHANNEL_FRAME_API, status);
}
-double HAL_REV_GetPDHSupplyVoltage(HAL_REVPDHHandle handle, int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- return PDH_status4_v_bus_decode(statusFrame.v_bus);
-}
-
-HAL_Bool HAL_REV_IsPDHEnabled(HAL_REVPDHHandle handle, int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return false;
- }
-
- return PDH_status4_system_enable_decode(statusFrame.system_enable);
-}
-
-HAL_Bool HAL_REV_CheckPDHBrownout(HAL_REVPDHHandle handle, int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return false;
- }
-
- return PDH_status4_brownout_decode(statusFrame.brownout);
-}
-
-HAL_Bool HAL_REV_CheckPDHCANWarning(HAL_REVPDHHandle handle, int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- return PDH_status4_can_warning_decode(statusFrame.can_warning);
-}
-
-HAL_Bool HAL_REV_CheckPDHHardwareFault(HAL_REVPDHHandle handle,
- int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- return PDH_status4_hardware_fault_decode(statusFrame.hardware_fault);
-}
-
-HAL_Bool HAL_REV_CheckPDHStickyBrownout(HAL_REVPDHHandle handle,
- int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- return PDH_status4_sticky_brownout_decode(statusFrame.sticky_brownout);
-}
-
-HAL_Bool HAL_REV_CheckPDHStickyCANWarning(HAL_REVPDHHandle handle,
- int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- return PDH_status4_sticky_can_warning_decode(statusFrame.sticky_can_warning);
-}
-
-HAL_Bool HAL_REV_CheckPDHStickyCANBusOff(HAL_REVPDHHandle handle,
- int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- return PDH_status4_sticky_can_bus_off_decode(statusFrame.sticky_can_bus_off);
-}
-
-HAL_Bool HAL_REV_CheckPDHStickyHardwareFault(HAL_REVPDHHandle handle,
+HAL_Bool HAL_GetREVPDHSwitchableChannelState(HAL_REVPDHHandle handle,
int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
+ PDH_status_4_t statusFrame = HAL_GetREVPDHStatus4(handle, status);
if (*status != 0) {
return 0.0;
}
- return PDH_status4_sticky_hardware_fault_decode(
- statusFrame.sticky_hardware_fault);
+ return PDH_status_4_switch_channel_state_decode(
+ statusFrame.switch_channel_state);
}
-HAL_Bool HAL_REV_CheckPDHStickyFirmwareFault(HAL_REVPDHHandle handle,
- int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
+double HAL_GetREVPDHVoltage(HAL_REVPDHHandle handle, int32_t* status) {
+ PDH_status_4_t statusFrame = HAL_GetREVPDHStatus4(handle, status);
if (*status != 0) {
return 0.0;
}
- return PDH_status4_sticky_firmware_fault_decode(
- statusFrame.sticky_firmware_fault);
+ return PDH_status_4_v_bus_decode(statusFrame.v_bus);
}
-HAL_Bool HAL_REV_CheckPDHStickyChannelBrownout(HAL_REVPDHHandle handle,
- int32_t channel,
- int32_t* status) {
- if (channel < 20 || channel > 23) {
- *status = RESOURCE_OUT_OF_RANGE;
- return 0.0;
- }
-
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- switch (channel) {
- case 20:
- return PDH_status4_sticky_ch20_brownout_decode(
- statusFrame.sticky_ch20_brownout);
- case 21:
- return PDH_status4_sticky_ch21_brownout_decode(
- statusFrame.sticky_ch21_brownout);
- case 22:
- return PDH_status4_sticky_ch22_brownout_decode(
- statusFrame.sticky_ch22_brownout);
- case 23:
- return PDH_status4_sticky_ch23_brownout_decode(
- statusFrame.sticky_ch23_brownout);
- }
- return 0;
-}
-
-HAL_Bool HAL_REV_CheckPDHStickyHasReset(HAL_REVPDHHandle handle,
- int32_t* status) {
- PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
-
- if (*status != 0) {
- return 0.0;
- }
-
- return PDH_status4_sticky_has_reset_decode(statusFrame.sticky_has_reset);
-}
-
-REV_PDH_Version HAL_REV_GetPDHVersion(HAL_REVPDHHandle handle,
- int32_t* status) {
- REV_PDH_Version version;
- std::memset(&version, 0, sizeof(version));
+void HAL_GetREVPDHVersion(HAL_REVPDHHandle handle,
+ HAL_PowerDistributionVersion* version,
+ int32_t* status) {
+ std::memset(version, 0, sizeof(*version));
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
@@ -742,36 +490,141 @@
auto hpdh = REVPDHHandles->Get(handle);
if (hpdh == nullptr) {
*status = HAL_HANDLE_ERROR;
- return version;
+ return;
+ }
+
+ if (hpdh->versionInfo.firmwareMajor > 0) {
+ version->firmwareMajor = hpdh->versionInfo.firmwareMajor;
+ version->firmwareMinor = hpdh->versionInfo.firmwareMinor;
+ version->firmwareFix = hpdh->versionInfo.firmwareFix;
+ version->hardwareMajor = hpdh->versionInfo.hardwareMajor;
+ version->hardwareMinor = hpdh->versionInfo.hardwareMinor;
+ version->uniqueId = hpdh->versionInfo.uniqueId;
+
+ *status = 0;
+ return;
}
HAL_WriteCANRTRFrame(hpdh->hcan, PDH_VERSION_LENGTH, PDH_VERSION_FRAME_API,
status);
if (*status != 0) {
- return version;
+ return;
}
- HAL_ReadCANPacketTimeout(hpdh->hcan, PDH_VERSION_FRAME_API, packedData,
- &length, ×tamp, kDefaultControlPeriod * 2,
- status);
+ uint32_t timeoutMs = 100;
+ for (uint32_t i = 0; i <= timeoutMs; i++) {
+ HAL_ReadCANPacketNew(hpdh->hcan, PDH_VERSION_FRAME_API, packedData, &length,
+ ×tamp, status);
+ if (*status == 0) {
+ break;
+ }
+ std::this_thread::sleep_for(std::chrono::milliseconds(1));
+ }
if (*status != 0) {
- return version;
+ return;
}
PDH_version_unpack(&result, packedData, PDH_VERSION_LENGTH);
- version.firmwareMajor = result.firmware_year;
- version.firmwareMinor = result.firmware_minor;
- version.firmwareFix = result.firmware_fix;
- version.hardwareRev = result.hardware_code;
- version.uniqueId = result.unique_id;
+ version->firmwareMajor = result.firmware_year;
+ version->firmwareMinor = result.firmware_minor;
+ version->firmwareFix = result.firmware_fix;
+ version->hardwareMinor = result.hardware_minor;
+ version->hardwareMajor = result.hardware_major;
+ version->uniqueId = result.unique_id;
- return version;
+ hpdh->versionInfo = *version;
}
-void HAL_REV_ClearPDHFaults(HAL_REVPDHHandle handle, int32_t* status) {
+void HAL_GetREVPDHFaults(HAL_REVPDHHandle handle,
+ HAL_PowerDistributionFaults* faults, int32_t* status) {
+ std::memset(faults, 0, sizeof(*faults));
+ auto hpdh = REVPDHHandles->Get(handle);
+ if (hpdh == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+
+ PDH_status_0_t status0 = HAL_ReadREVPDHStatus0(hpdh->hcan, status);
+ PDH_status_1_t status1 = HAL_ReadREVPDHStatus1(hpdh->hcan, status);
+ PDH_status_2_t status2 = HAL_ReadREVPDHStatus2(hpdh->hcan, status);
+ PDH_status_3_t status3 = HAL_ReadREVPDHStatus3(hpdh->hcan, status);
+ PDH_status_4_t status4 = HAL_ReadREVPDHStatus4(hpdh->hcan, status);
+
+ faults->channel0BreakerFault = status0.channel_0_breaker_fault;
+ faults->channel1BreakerFault = status0.channel_1_breaker_fault;
+ faults->channel2BreakerFault = status0.channel_2_breaker_fault;
+ faults->channel3BreakerFault = status0.channel_3_breaker_fault;
+ faults->channel4BreakerFault = status1.channel_4_breaker_fault;
+ faults->channel5BreakerFault = status1.channel_5_breaker_fault;
+ faults->channel6BreakerFault = status1.channel_6_breaker_fault;
+ faults->channel7BreakerFault = status1.channel_7_breaker_fault;
+ faults->channel8BreakerFault = status2.channel_8_breaker_fault;
+ faults->channel9BreakerFault = status2.channel_9_breaker_fault;
+ faults->channel10BreakerFault = status2.channel_10_breaker_fault;
+ faults->channel11BreakerFault = status2.channel_11_breaker_fault;
+ faults->channel12BreakerFault = status3.channel_12_breaker_fault;
+ faults->channel13BreakerFault = status3.channel_13_breaker_fault;
+ faults->channel14BreakerFault = status3.channel_14_breaker_fault;
+ faults->channel15BreakerFault = status3.channel_15_breaker_fault;
+ faults->channel16BreakerFault = status3.channel_16_breaker_fault;
+ faults->channel17BreakerFault = status3.channel_17_breaker_fault;
+ faults->channel18BreakerFault = status3.channel_18_breaker_fault;
+ faults->channel19BreakerFault = status3.channel_19_breaker_fault;
+ faults->channel20BreakerFault = status3.channel_20_breaker_fault;
+ faults->channel21BreakerFault = status3.channel_21_breaker_fault;
+ faults->channel22BreakerFault = status3.channel_22_breaker_fault;
+ faults->channel23BreakerFault = status3.channel_23_breaker_fault;
+ faults->brownout = status4.brownout_fault;
+ faults->canWarning = status4.can_warning_fault;
+ faults->hardwareFault = status4.hardware_fault;
+}
+
+void HAL_GetREVPDHStickyFaults(HAL_REVPDHHandle handle,
+ HAL_PowerDistributionStickyFaults* stickyFaults,
+ int32_t* status) {
+ std::memset(stickyFaults, 0, sizeof(*stickyFaults));
+ auto hpdh = REVPDHHandles->Get(handle);
+ if (hpdh == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+
+ PDH_status_4_t status4 = HAL_ReadREVPDHStatus4(hpdh->hcan, status);
+
+ stickyFaults->channel0BreakerFault = status4.sticky_ch0_breaker_fault;
+ stickyFaults->channel1BreakerFault = status4.sticky_ch1_breaker_fault;
+ stickyFaults->channel2BreakerFault = status4.sticky_ch2_breaker_fault;
+ stickyFaults->channel3BreakerFault = status4.sticky_ch3_breaker_fault;
+ stickyFaults->channel4BreakerFault = status4.sticky_ch4_breaker_fault;
+ stickyFaults->channel5BreakerFault = status4.sticky_ch5_breaker_fault;
+ stickyFaults->channel6BreakerFault = status4.sticky_ch6_breaker_fault;
+ stickyFaults->channel7BreakerFault = status4.sticky_ch7_breaker_fault;
+ stickyFaults->channel8BreakerFault = status4.sticky_ch8_breaker_fault;
+ stickyFaults->channel9BreakerFault = status4.sticky_ch9_breaker_fault;
+ stickyFaults->channel10BreakerFault = status4.sticky_ch10_breaker_fault;
+ stickyFaults->channel11BreakerFault = status4.sticky_ch11_breaker_fault;
+ stickyFaults->channel12BreakerFault = status4.sticky_ch12_breaker_fault;
+ stickyFaults->channel13BreakerFault = status4.sticky_ch13_breaker_fault;
+ stickyFaults->channel14BreakerFault = status4.sticky_ch14_breaker_fault;
+ stickyFaults->channel15BreakerFault = status4.sticky_ch15_breaker_fault;
+ stickyFaults->channel16BreakerFault = status4.sticky_ch16_breaker_fault;
+ stickyFaults->channel17BreakerFault = status4.sticky_ch17_breaker_fault;
+ stickyFaults->channel18BreakerFault = status4.sticky_ch18_breaker_fault;
+ stickyFaults->channel19BreakerFault = status4.sticky_ch19_breaker_fault;
+ stickyFaults->channel20BreakerFault = status4.sticky_ch20_breaker_fault;
+ stickyFaults->channel21BreakerFault = status4.sticky_ch21_breaker_fault;
+ stickyFaults->channel22BreakerFault = status4.sticky_ch22_breaker_fault;
+ stickyFaults->channel23BreakerFault = status4.sticky_ch23_breaker_fault;
+ stickyFaults->brownout = status4.sticky_brownout_fault;
+ stickyFaults->canWarning = status4.sticky_can_warning_fault;
+ stickyFaults->canBusOff = status4.sticky_can_bus_off_fault;
+ stickyFaults->hasReset = status4.sticky_has_reset_fault;
+}
+
+void HAL_ClearREVPDHStickyFaults(HAL_REVPDHHandle handle, int32_t* status) {
auto hpdh = REVPDHHandles->Get(handle);
if (hpdh == nullptr) {
*status = HAL_HANDLE_ERROR;
@@ -783,16 +636,4 @@
PDH_CLEAR_FAULTS_FRAME_API, status);
}
-void HAL_REV_IdentifyPDH(HAL_REVPDHHandle handle, int32_t* status) {
- auto hpdh = REVPDHHandles->Get(handle);
- if (hpdh == nullptr) {
- *status = HAL_HANDLE_ERROR;
- return;
- }
-
- uint8_t packedData[8] = {0};
- HAL_WriteCANPacket(hpdh->hcan, packedData, PDH_IDENTIFY_LENGTH,
- PDH_IDENTIFY_FRAME_API, status);
-}
-
} // extern "C"
diff --git a/hal/src/main/native/athena/REVPDH.h b/hal/src/main/native/athena/REVPDH.h
index 228d05c..d0b10f2 100644
--- a/hal/src/main/native/athena/REVPDH.h
+++ b/hal/src/main/native/athena/REVPDH.h
@@ -6,6 +6,7 @@
#include <stdint.h>
+#include "hal/PowerDistribution.h"
#include "hal/Types.h"
/**
@@ -14,14 +15,6 @@
* @{
*/
-struct REV_PDH_Version {
- uint32_t firmwareMajor;
- uint32_t firmwareMinor;
- uint32_t firmwareFix;
- uint32_t hardwareRev;
- uint32_t uniqueId;
-};
-
#ifdef __cplusplus
extern "C" {
#endif
@@ -32,21 +25,21 @@
* @param module the device CAN ID (1 .. 63)
* @return the created PDH handle
*/
-HAL_REVPDHHandle HAL_REV_InitializePDH(int32_t module,
- const char* allocationLocation,
- int32_t* status);
+HAL_REVPDHHandle HAL_InitializeREVPDH(int32_t module,
+ const char* allocationLocation,
+ int32_t* status);
/**
* Frees a PDH device handle.
*
* @param handle the previously created PDH handle
*/
-void HAL_REV_FreePDH(HAL_REVPDHHandle handle);
+void HAL_FreeREVPDH(HAL_REVPDHHandle handle);
/**
* Gets the module number for a pdh.
*/
-int32_t HAL_REV_GetPDHModuleNumber(HAL_REVPDHHandle handle, int32_t* status);
+int32_t HAL_GetREVPDHModuleNumber(HAL_REVPDHHandle handle, int32_t* status);
/**
* Checks if a PDH module number is valid.
@@ -56,34 +49,34 @@
* @param module module number (1 .. 63)
* @return 1 if the module number is valid; 0 otherwise
*/
-HAL_Bool HAL_REV_CheckPDHModuleNumber(int32_t module);
+HAL_Bool HAL_CheckREVPDHModuleNumber(int32_t module);
/**
* Checks if a PDH channel number is valid.
*
- * @param module channel number (0 .. HAL_REV_PDH_NUM_CHANNELS)
+ * @param module channel number (0 .. kNumREVPDHChannels)
* @return 1 if the channel number is valid; 0 otherwise
*/
-HAL_Bool HAL_REV_CheckPDHChannelNumber(int32_t channel);
+HAL_Bool HAL_CheckREVPDHChannelNumber(int32_t channel);
/**
* Gets the current of a PDH channel in Amps.
*
* @param handle PDH handle
* @param channel the channel to retrieve the current of (0 ..
- * HAL_REV_PDH_NUM_CHANNELS)
+ * kNumREVPDHChannels)
*
* @return the current of the PDH channel in Amps
*/
-double HAL_REV_GetPDHChannelCurrent(HAL_REVPDHHandle handle, int32_t channel,
- int32_t* status);
+double HAL_GetREVPDHChannelCurrent(HAL_REVPDHHandle handle, int32_t channel,
+ int32_t* status);
/**
* @param handle PDH handle
* @param currents array of currents
*/
-void HAL_REV_GetPDHAllChannelCurrents(HAL_REVPDHHandle handle, double* currents,
- int32_t* status);
+void HAL_GetREVPDHAllChannelCurrents(HAL_REVPDHHandle handle, double* currents,
+ int32_t* status);
/**
* Gets the total current of the PDH in Amps, measured to the nearest even
@@ -93,7 +86,7 @@
*
* @return the total current of the PDH in Amps
*/
-uint16_t HAL_REV_GetPDHTotalCurrent(HAL_REVPDHHandle handle, int32_t* status);
+uint16_t HAL_GetREVPDHTotalCurrent(HAL_REVPDHHandle handle, int32_t* status);
/**
* Sets the state of the switchable channel on a PDH device.
@@ -102,8 +95,8 @@
* @param enabled 1 if the switchable channel should be enabled; 0
* otherwise
*/
-void HAL_REV_SetPDHSwitchableChannel(HAL_REVPDHHandle handle, HAL_Bool enabled,
- int32_t* status);
+void HAL_SetREVPDHSwitchableChannel(HAL_REVPDHHandle handle, HAL_Bool enabled,
+ int32_t* status);
/**
* Gets the current state of the switchable channel on a PDH device.
@@ -114,200 +107,56 @@
* @param handle PDH handle
* @return 1 if the switchable channel is enabled; 0 otherwise
*/
-HAL_Bool HAL_REV_GetPDHSwitchableChannelState(HAL_REVPDHHandle handle,
- int32_t* status);
-
-/**
- * Checks if a PDH channel is currently experiencing a brownout condition.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- * @param channel the channel to retrieve the brownout status of
- *
- * @return 1 if the channel is experiencing a brownout; 0 otherwise
- */
-HAL_Bool HAL_REV_CheckPDHChannelBrownout(HAL_REVPDHHandle handle,
- int32_t channel, int32_t* status);
-
-/**
- * Gets the voltage being supplied to a PDH device.
- *
- * @param handle PDH handle
- *
- * @return the voltage at the input of the PDH in Volts
- */
-double HAL_REV_GetPDHSupplyVoltage(HAL_REVPDHHandle handle, int32_t* status);
-
-/**
- * Checks if a PDH device is currently enabled.
- *
- * @param handle PDH handle
- *
- * @return 1 if the PDH is enabled; 0 otherwise
- */
-HAL_Bool HAL_REV_IsPDHEnabled(HAL_REVPDHHandle handle, int32_t* status);
-
-/**
- * Checks if the input voltage on a PDH device is currently below the minimum
- * voltage.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the PDH is experiencing a brownout; 0 otherwise
- */
-HAL_Bool HAL_REV_CheckPDHBrownout(HAL_REVPDHHandle handle, int32_t* status);
-
-/**
- * Checks if the CAN RX or TX error levels on a PDH device have exceeded the
- * warning threshold.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device has exceeded the warning threshold; 0
- * otherwise
- */
-HAL_Bool HAL_REV_CheckPDHCANWarning(HAL_REVPDHHandle handle, int32_t* status);
-
-/**
- * Checks if a PDH device is currently malfunctioning.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device is in a hardware fault state; 0
- * otherwise
- */
-HAL_Bool HAL_REV_CheckPDHHardwareFault(HAL_REVPDHHandle handle,
- int32_t* status);
-
-/**
- * Checks if the input voltage on a PDH device has gone below the specified
- * minimum voltage.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device has had a brownout; 0 otherwise
- */
-HAL_Bool HAL_REV_CheckPDHStickyBrownout(HAL_REVPDHHandle handle,
- int32_t* status);
-
-/**
- * Checks if the CAN RX or TX error levels on a PDH device have exceeded the
- * warning threshold.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device has exceeded the CAN warning threshold;
- * 0 otherwise
- */
-HAL_Bool HAL_REV_CheckPDHStickyCANWarning(HAL_REVPDHHandle handle,
- int32_t* status);
-
-/**
- * Checks if the CAN bus on a PDH device has previously experienced a 'Bus Off'
- * event.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device has experienced a 'Bus Off' event; 0
- * otherwise
- */
-HAL_Bool HAL_REV_CheckPDHStickyCANBusOff(HAL_REVPDHHandle handle,
- int32_t* status);
-
-/**
- * Checks if a PDH device has malfunctioned.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device has had a malfunction; 0 otherwise
- */
-HAL_Bool HAL_REV_CheckPDHStickyHardwareFault(HAL_REVPDHHandle handle,
+HAL_Bool HAL_GetREVPDHSwitchableChannelState(HAL_REVPDHHandle handle,
int32_t* status);
/**
- * Checks if the firmware on a PDH device has malfunctioned and reset during
- * operation.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device has had a malfunction and reset; 0
- * otherwise
- */
-HAL_Bool HAL_REV_CheckPDHStickyFirmwareFault(HAL_REVPDHHandle handle,
- int32_t* status);
-
-/**
- * Checks if a brownout has happened on channels 20-23 of a PDH device while it
- * was enabled.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- * @param channel PDH channel to retrieve sticky brownout status (20 ..
- * 23)
- *
- *
- * @return 1 if the channel has had a brownout; 0 otherwise
- */
-HAL_Bool HAL_REV_CheckPDHStickyChannelBrownout(HAL_REVPDHHandle handle,
- int32_t channel,
- int32_t* status);
-
-/**
- * Checks if a PDH device has reset.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- *
- * @return 1 if the device has reset; 0 otherwise
- */
-HAL_Bool HAL_REV_CheckPDHStickyHasReset(HAL_REVPDHHandle handle,
- int32_t* status);
-
-/**
* Gets the firmware and hardware versions of a PDH device.
*
* @param handle PDH handle
*
* @return version information
*/
-REV_PDH_Version HAL_REV_GetPDHVersion(HAL_REVPDHHandle handle, int32_t* status);
+void HAL_GetREVPDHVersion(HAL_REVPDHHandle handle,
+ HAL_PowerDistributionVersion* version,
+ int32_t* status);
+
+/**
+ * Gets the voltage being supplied to a PDH device.
+ *
+ * @param handle PDH handle
+ *
+ * @return the voltage at the input of the PDH in Volts
+ */
+double HAL_GetREVPDHVoltage(HAL_REVPDHHandle handle, int32_t* status);
+
+/**
+ * Gets the faults of a PDH device.
+ *
+ * @param handle PDH handle
+ *
+ * @return the faults of the PDH
+ */
+void HAL_GetREVPDHFaults(HAL_REVPDHHandle handle,
+ HAL_PowerDistributionFaults* faults, int32_t* status);
+
+/**
+ * Gets the sticky faults of a PDH device.
+ *
+ * @param handle PDH handle
+ *
+ * @return the sticky faults of the PDH
+ */
+void HAL_GetREVPDHStickyFaults(HAL_REVPDHHandle handle,
+ HAL_PowerDistributionStickyFaults* stickyFaults,
+ int32_t* status);
/**
* Clears the sticky faults on a PDH device.
*
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
* @param handle PDH handle
*/
-void HAL_REV_ClearPDHFaults(HAL_REVPDHHandle handle, int32_t* status);
-
-/**
- * Identifies a PDH device by blinking its LED.
- *
- * NOTE: Not implemented in firmware as of 2021-04-23.
- *
- * @param handle PDH handle
- */
-void HAL_REV_IdentifyPDH(HAL_REVPDHHandle handle, int32_t* status);
+void HAL_ClearREVPDHStickyFaults(HAL_REVPDHHandle handle, int32_t* status);
#ifdef __cplusplus
} // extern "C"
diff --git a/hal/src/main/native/athena/REVPH.cpp b/hal/src/main/native/athena/REVPH.cpp
index 155f92c..5b18de6 100644
--- a/hal/src/main/native/athena/REVPH.cpp
+++ b/hal/src/main/native/athena/REVPH.cpp
@@ -4,6 +4,8 @@
#include "hal/REVPH.h"
+#include <thread>
+
#include <fmt/format.h>
#include "HALInitializer.h"
@@ -23,28 +25,34 @@
HAL_CANDeviceType::HAL_CAN_Dev_kPneumatics;
static constexpr int32_t kDefaultControlPeriod = 20;
-// static constexpr uint8_t kDefaultSensorMask = (1 <<
-// HAL_REV_PHSENSOR_DIGITAL);
static constexpr uint8_t kDefaultCompressorDuty = 255;
static constexpr uint8_t kDefaultPressureTarget = 120;
static constexpr uint8_t kDefaultPressureHysteresis = 60;
-#define HAL_REV_MAX_PULSE_TIME 65534
-#define HAL_REV_MAX_PRESSURE_TARGET 120
-#define HAL_REV_MAX_PRESSURE_HYSTERESIS HAL_REV_MAX_PRESSURE_TARGET
+#define HAL_REVPH_MAX_PULSE_TIME 65534
static constexpr uint32_t APIFromExtId(uint32_t extId) {
return (extId >> 6) & 0x3FF;
}
+static constexpr uint32_t PH_STATUS_0_FRAME_API =
+ APIFromExtId(PH_STATUS_0_FRAME_ID);
+static constexpr uint32_t PH_STATUS_1_FRAME_API =
+ APIFromExtId(PH_STATUS_1_FRAME_ID);
+
static constexpr uint32_t PH_SET_ALL_FRAME_API =
APIFromExtId(PH_SET_ALL_FRAME_ID);
static constexpr uint32_t PH_PULSE_ONCE_FRAME_API =
APIFromExtId(PH_PULSE_ONCE_FRAME_ID);
-static constexpr uint32_t PH_STATUS0_FRAME_API =
- APIFromExtId(PH_STATUS0_FRAME_ID);
-static constexpr uint32_t PH_STATUS1_FRAME_API =
- APIFromExtId(PH_STATUS1_FRAME_ID);
+
+static constexpr uint32_t PH_COMPRESSOR_CONFIG_API =
+ APIFromExtId(PH_COMPRESSOR_CONFIG_FRAME_ID);
+
+static constexpr uint32_t PH_CLEAR_FAULTS_FRAME_API =
+ APIFromExtId(PH_CLEAR_FAULTS_FRAME_ID);
+
+static constexpr uint32_t PH_VERSION_FRAME_API =
+ APIFromExtId(PH_VERSION_FRAME_ID);
static constexpr int32_t kPHFrameStatus0Timeout = 50;
static constexpr int32_t kPHFrameStatus1Timeout = 50;
@@ -57,6 +65,7 @@
wpi::mutex solenoidLock;
HAL_CANHandle hcan;
std::string previousAllocation;
+ HAL_REVPHVersion versionInfo;
};
} // namespace
@@ -73,38 +82,38 @@
}
} // namespace hal::init
-static PH_status0_t HAL_REV_ReadPHStatus0(HAL_CANHandle hcan, int32_t* status) {
+static PH_status_0_t HAL_ReadREVPHStatus0(HAL_CANHandle hcan, int32_t* status) {
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
- PH_status0_t result = {};
+ PH_status_0_t result = {};
- HAL_ReadCANPacketTimeout(hcan, PH_STATUS0_FRAME_API, packedData, &length,
+ HAL_ReadCANPacketTimeout(hcan, PH_STATUS_0_FRAME_API, packedData, &length,
×tamp, kPHFrameStatus0Timeout * 2, status);
if (*status != 0) {
return result;
}
- PH_status0_unpack(&result, packedData, PH_STATUS0_LENGTH);
+ PH_status_0_unpack(&result, packedData, PH_STATUS_0_LENGTH);
return result;
}
-static PH_status1_t HAL_REV_ReadPHStatus1(HAL_CANHandle hcan, int32_t* status) {
+static PH_status_1_t HAL_ReadREVPHStatus1(HAL_CANHandle hcan, int32_t* status) {
uint8_t packedData[8] = {0};
int32_t length = 0;
uint64_t timestamp = 0;
- PH_status1_t result = {};
+ PH_status_1_t result = {};
- HAL_ReadCANPacketTimeout(hcan, PH_STATUS1_FRAME_API, packedData, &length,
+ HAL_ReadCANPacketTimeout(hcan, PH_STATUS_1_FRAME_API, packedData, &length,
×tamp, kPHFrameStatus1Timeout * 2, status);
if (*status != 0) {
return result;
}
- PH_status1_unpack(&result, packedData, PH_STATUS1_LENGTH);
+ PH_status_1_unpack(&result, packedData, PH_STATUS_1_LENGTH);
return result;
}
@@ -115,9 +124,9 @@
kSolenoidControlledViaPulse
};
-static void HAL_REV_UpdateDesiredPHSolenoidState(REV_PHObj* hph,
- int32_t solenoid,
- REV_SolenoidState state) {
+static void HAL_UpdateDesiredREVPHSolenoidState(REV_PHObj* hph,
+ int32_t solenoid,
+ REV_SolenoidState state) {
switch (solenoid) {
case 0:
hph->desiredSolenoidsState.channel_0 = state;
@@ -170,15 +179,15 @@
}
}
-static void HAL_REV_SendSolenoidsState(REV_PHObj* hph, int32_t* status) {
+static void HAL_SendREVPHSolenoidsState(REV_PHObj* hph, int32_t* status) {
uint8_t packedData[PH_SET_ALL_LENGTH] = {0};
PH_set_all_pack(packedData, &(hph->desiredSolenoidsState), PH_SET_ALL_LENGTH);
HAL_WriteCANPacketRepeating(hph->hcan, packedData, PH_SET_ALL_LENGTH,
PH_SET_ALL_FRAME_API, hph->controlPeriod, status);
}
-static HAL_Bool HAL_REV_CheckPHPulseTime(int32_t time) {
- return ((time > 0) && (time <= HAL_REV_MAX_PULSE_TIME)) ? 1 : 0;
+static HAL_Bool HAL_CheckREVPHPulseTime(int32_t time) {
+ return ((time > 0) && (time <= HAL_REVPH_MAX_PULSE_TIME)) ? 1 : 0;
}
HAL_REVPHHandle HAL_InitializeREVPH(int32_t module,
@@ -215,9 +224,12 @@
hph->previousAllocation = allocationLocation ? allocationLocation : "";
hph->hcan = hcan;
hph->controlPeriod = kDefaultControlPeriod;
+ std::memset(&hph->desiredSolenoidsState, 0,
+ sizeof(hph->desiredSolenoidsState));
+ std::memset(&hph->versionInfo, 0, sizeof(hph->versionInfo));
// Start closed-loop compressor control by starting solenoid state updates
- HAL_REV_SendSolenoidsState(hph.get(), status);
+ HAL_SendREVPHSolenoidsState(hph.get(), status);
return handle;
}
@@ -247,7 +259,7 @@
return false;
}
- PH_status0_t status0 = HAL_REV_ReadPHStatus0(ph->hcan, status);
+ PH_status_0_t status0 = HAL_ReadREVPHStatus0(ph->hcan, status);
if (*status != 0) {
return false;
@@ -256,14 +268,86 @@
return status0.compressor_on;
}
-void HAL_SetREVPHClosedLoopControl(HAL_REVPHHandle handle, HAL_Bool enabled,
- int32_t* status) {
- // TODO
+void HAL_SetREVPHCompressorConfig(HAL_REVPHHandle handle,
+ const HAL_REVPHCompressorConfig* config,
+ int32_t* status) {
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+
+ PH_compressor_config_t frameData;
+ frameData.minimum_tank_pressure =
+ PH_compressor_config_minimum_tank_pressure_encode(
+ config->minAnalogVoltage);
+ frameData.maximum_tank_pressure =
+ PH_compressor_config_maximum_tank_pressure_encode(
+ config->maxAnalogVoltage);
+ frameData.force_disable = config->forceDisable;
+ frameData.use_digital = config->useDigital;
+
+ uint8_t packedData[PH_COMPRESSOR_CONFIG_LENGTH] = {0};
+ PH_compressor_config_pack(packedData, &frameData,
+ PH_COMPRESSOR_CONFIG_LENGTH);
+ HAL_WriteCANPacket(ph->hcan, packedData, PH_COMPRESSOR_CONFIG_LENGTH,
+ PH_COMPRESSOR_CONFIG_API, status);
}
-HAL_Bool HAL_GetREVPHClosedLoopControl(HAL_REVPHHandle handle,
- int32_t* status) {
- return false; // TODO
+void HAL_SetREVPHClosedLoopControlDisabled(HAL_REVPHHandle handle,
+ int32_t* status) {
+ HAL_REVPHCompressorConfig config = {0, 0, 0, 0};
+ config.forceDisable = true;
+
+ HAL_SetREVPHCompressorConfig(handle, &config, status);
+}
+
+void HAL_SetREVPHClosedLoopControlDigital(HAL_REVPHHandle handle,
+ int32_t* status) {
+ HAL_REVPHCompressorConfig config = {0, 0, 0, 0};
+ config.useDigital = true;
+
+ HAL_SetREVPHCompressorConfig(handle, &config, status);
+}
+
+void HAL_SetREVPHClosedLoopControlAnalog(HAL_REVPHHandle handle,
+ double minAnalogVoltage,
+ double maxAnalogVoltage,
+ int32_t* status) {
+ HAL_REVPHCompressorConfig config = {0, 0, 0, 0};
+ config.minAnalogVoltage = minAnalogVoltage;
+ config.maxAnalogVoltage = maxAnalogVoltage;
+
+ HAL_SetREVPHCompressorConfig(handle, &config, status);
+}
+
+void HAL_SetREVPHClosedLoopControlHybrid(HAL_REVPHHandle handle,
+ double minAnalogVoltage,
+ double maxAnalogVoltage,
+ int32_t* status) {
+ HAL_REVPHCompressorConfig config = {0, 0, 0, 0};
+ config.minAnalogVoltage = minAnalogVoltage;
+ config.maxAnalogVoltage = maxAnalogVoltage;
+ config.useDigital = true;
+
+ HAL_SetREVPHCompressorConfig(handle, &config, status);
+}
+
+HAL_REVPHCompressorConfigType HAL_GetREVPHCompressorConfig(
+ HAL_REVPHHandle handle, int32_t* status) {
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return HAL_REVPHCompressorConfigType_kDisabled;
+ }
+
+ PH_status_0_t status0 = HAL_ReadREVPHStatus0(ph->hcan, status);
+
+ if (*status != 0) {
+ return HAL_REVPHCompressorConfigType_kDisabled;
+ }
+
+ return static_cast<HAL_REVPHCompressorConfigType>(status0.compressor_config);
}
HAL_Bool HAL_GetREVPHPressureSwitch(HAL_REVPHHandle handle, int32_t* status) {
@@ -273,7 +357,7 @@
return false;
}
- PH_status0_t status0 = HAL_REV_ReadPHStatus0(ph->hcan, status);
+ PH_status_0_t status0 = HAL_ReadREVPHStatus0(ph->hcan, status);
if (*status != 0) {
return false;
@@ -289,17 +373,17 @@
return 0;
}
- PH_status1_t status1 = HAL_REV_ReadPHStatus1(ph->hcan, status);
+ PH_status_1_t status1 = HAL_ReadREVPHStatus1(ph->hcan, status);
if (*status != 0) {
return 0;
}
- return PH_status1_compressor_current_decode(status1.compressor_current);
+ return PH_status_1_compressor_current_decode(status1.compressor_current);
}
-double HAL_GetREVPHAnalogPressure(HAL_REVPHHandle handle, int32_t channel,
- int32_t* status) {
+double HAL_GetREVPHAnalogVoltage(HAL_REVPHHandle handle, int32_t channel,
+ int32_t* status) {
auto ph = REVPHHandles->Get(handle);
if (ph == nullptr) {
*status = HAL_HANDLE_ERROR;
@@ -313,16 +397,138 @@
return 0;
}
- PH_status0_t status0 = HAL_REV_ReadPHStatus0(ph->hcan, status);
+ PH_status_0_t status0 = HAL_ReadREVPHStatus0(ph->hcan, status);
if (*status != 0) {
return 0;
}
- if (channel == 1) {
- return PH_status0_analog_0_decode(status0.analog_0);
+ if (channel == 0) {
+ return PH_status_0_analog_0_decode(status0.analog_0);
}
- return PH_status0_analog_1_decode(status0.analog_1);
+ return PH_status_0_analog_1_decode(status0.analog_1);
+}
+
+double HAL_GetREVPHVoltage(HAL_REVPHHandle handle, int32_t* status) {
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return 0;
+ }
+
+ PH_status_1_t status1 = HAL_ReadREVPHStatus1(ph->hcan, status);
+
+ if (*status != 0) {
+ return 0;
+ }
+
+ return PH_status_1_v_bus_decode(status1.v_bus);
+}
+
+double HAL_GetREVPH5VVoltage(HAL_REVPHHandle handle, int32_t* status) {
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return 0;
+ }
+
+ PH_status_1_t status1 = HAL_ReadREVPHStatus1(ph->hcan, status);
+
+ if (*status != 0) {
+ return 0;
+ }
+
+ return PH_status_1_supply_voltage_5_v_decode(status1.supply_voltage_5_v);
+}
+
+double HAL_GetREVPHSolenoidCurrent(HAL_REVPHHandle handle, int32_t* status) {
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return 0;
+ }
+
+ PH_status_1_t status1 = HAL_ReadREVPHStatus1(ph->hcan, status);
+
+ if (*status != 0) {
+ return 0;
+ }
+
+ return PH_status_1_solenoid_current_decode(status1.solenoid_current);
+}
+
+double HAL_GetREVPHSolenoidVoltage(HAL_REVPHHandle handle, int32_t* status) {
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return 0;
+ }
+
+ PH_status_1_t status1 = HAL_ReadREVPHStatus1(ph->hcan, status);
+
+ if (*status != 0) {
+ return 0;
+ }
+
+ return PH_status_1_solenoid_voltage_decode(status1.solenoid_voltage);
+}
+
+void HAL_GetREVPHVersion(HAL_REVPHHandle handle, HAL_REVPHVersion* version,
+ int32_t* status) {
+ std::memset(version, 0, sizeof(*version));
+ uint8_t packedData[8] = {0};
+ int32_t length = 0;
+ uint64_t timestamp = 0;
+ PH_version_t result = {};
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+
+ if (ph->versionInfo.firmwareMajor > 0) {
+ version->firmwareMajor = ph->versionInfo.firmwareMajor;
+ version->firmwareMinor = ph->versionInfo.firmwareMinor;
+ version->firmwareFix = ph->versionInfo.firmwareFix;
+ version->hardwareMajor = ph->versionInfo.hardwareMajor;
+ version->hardwareMinor = ph->versionInfo.hardwareMinor;
+ version->uniqueId = ph->versionInfo.uniqueId;
+
+ *status = 0;
+ return;
+ }
+
+ HAL_WriteCANRTRFrame(ph->hcan, PH_VERSION_LENGTH, PH_VERSION_FRAME_API,
+ status);
+
+ if (*status != 0) {
+ return;
+ }
+
+ uint32_t timeoutMs = 100;
+ for (uint32_t i = 0; i <= timeoutMs; i++) {
+ HAL_ReadCANPacketNew(ph->hcan, PH_VERSION_FRAME_API, packedData, &length,
+ ×tamp, status);
+ if (*status == 0) {
+ break;
+ }
+ std::this_thread::sleep_for(std::chrono::milliseconds(1));
+ }
+
+ if (*status != 0) {
+ return;
+ }
+
+ PH_version_unpack(&result, packedData, PH_VERSION_LENGTH);
+
+ version->firmwareMajor = result.firmware_year;
+ version->firmwareMinor = result.firmware_minor;
+ version->firmwareFix = result.firmware_fix;
+ version->hardwareMinor = result.hardware_minor;
+ version->hardwareMajor = result.hardware_major;
+ version->uniqueId = result.unique_id;
+
+ ph->versionInfo = *version;
}
int32_t HAL_GetREVPHSolenoids(HAL_REVPHHandle handle, int32_t* status) {
@@ -332,7 +538,7 @@
return 0;
}
- PH_status0_t status0 = HAL_REV_ReadPHStatus0(ph->hcan, status);
+ PH_status_0_t status0 = HAL_ReadREVPHStatus0(ph->hcan, status);
if (*status != 0) {
return 0;
@@ -372,11 +578,11 @@
// The mask bit for the solenoid is set, so we update the solenoid state
REV_SolenoidState desiredSolenoidState =
values & (1 << solenoid) ? kSolenoidEnabled : kSolenoidDisabled;
- HAL_REV_UpdateDesiredPHSolenoidState(ph.get(), solenoid,
- desiredSolenoidState);
+ HAL_UpdateDesiredREVPHSolenoidState(ph.get(), solenoid,
+ desiredSolenoidState);
}
}
- HAL_REV_SendSolenoidsState(ph.get(), status);
+ HAL_SendREVPHSolenoidsState(ph.get(), status);
}
void HAL_FireREVPHOneShot(HAL_REVPHHandle handle, int32_t index, int32_t durMs,
@@ -395,7 +601,7 @@
return;
}
- if (!HAL_REV_CheckPHPulseTime(durMs)) {
+ if (!HAL_CheckREVPHPulseTime(durMs)) {
*status = PARAMETER_OUT_OF_RANGE;
hal::SetLastError(
status,
@@ -406,9 +612,9 @@
{
std::scoped_lock lock{ph->solenoidLock};
- HAL_REV_UpdateDesiredPHSolenoidState(ph.get(), index,
- kSolenoidControlledViaPulse);
- HAL_REV_SendSolenoidsState(ph.get(), status);
+ HAL_UpdateDesiredREVPHSolenoidState(ph.get(), index,
+ kSolenoidControlledViaPulse);
+ HAL_SendREVPHSolenoidsState(ph.get(), status);
}
if (*status != 0) {
@@ -478,3 +684,69 @@
HAL_WriteCANPacket(ph->hcan, packedData, PH_PULSE_ONCE_LENGTH,
PH_PULSE_ONCE_FRAME_API, status);
}
+
+void HAL_GetREVPHFaults(HAL_REVPHHandle handle, HAL_REVPHFaults* faults,
+ int32_t* status) {
+ std::memset(faults, 0, sizeof(*faults));
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+
+ PH_status_0_t status0 = HAL_ReadREVPHStatus0(ph->hcan, status);
+ faults->channel0Fault = status0.channel_0_fault;
+ faults->channel1Fault = status0.channel_1_fault;
+ faults->channel2Fault = status0.channel_2_fault;
+ faults->channel3Fault = status0.channel_3_fault;
+ faults->channel4Fault = status0.channel_4_fault;
+ faults->channel5Fault = status0.channel_5_fault;
+ faults->channel6Fault = status0.channel_6_fault;
+ faults->channel7Fault = status0.channel_7_fault;
+ faults->channel8Fault = status0.channel_8_fault;
+ faults->channel9Fault = status0.channel_9_fault;
+ faults->channel10Fault = status0.channel_10_fault;
+ faults->channel11Fault = status0.channel_11_fault;
+ faults->channel12Fault = status0.channel_12_fault;
+ faults->channel13Fault = status0.channel_13_fault;
+ faults->channel14Fault = status0.channel_14_fault;
+ faults->channel15Fault = status0.channel_15_fault;
+ faults->compressorOverCurrent = status0.compressor_oc_fault;
+ faults->compressorOpen = status0.compressor_open_fault;
+ faults->solenoidOverCurrent = status0.solenoid_oc_fault;
+ faults->brownout = status0.brownout_fault;
+ faults->canWarning = status0.can_warning_fault;
+ faults->hardwareFault = status0.hardware_fault;
+}
+
+void HAL_GetREVPHStickyFaults(HAL_REVPHHandle handle,
+ HAL_REVPHStickyFaults* stickyFaults,
+ int32_t* status) {
+ std::memset(stickyFaults, 0, sizeof(*stickyFaults));
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+
+ PH_status_1_t status1 = HAL_ReadREVPHStatus1(ph->hcan, status);
+ stickyFaults->compressorOverCurrent = status1.sticky_compressor_oc_fault;
+ stickyFaults->compressorOpen = status1.sticky_compressor_open_fault;
+ stickyFaults->solenoidOverCurrent = status1.sticky_solenoid_oc_fault;
+ stickyFaults->brownout = status1.sticky_brownout_fault;
+ stickyFaults->canWarning = status1.sticky_can_warning_fault;
+ stickyFaults->canBusOff = status1.sticky_can_bus_off_fault;
+ stickyFaults->hasReset = status1.sticky_has_reset_fault;
+}
+
+void HAL_ClearREVPHStickyFaults(HAL_REVPHHandle handle, int32_t* status) {
+ auto ph = REVPHHandles->Get(handle);
+ if (ph == nullptr) {
+ *status = HAL_HANDLE_ERROR;
+ return;
+ }
+
+ uint8_t packedData[8] = {0};
+ HAL_WriteCANPacket(ph->hcan, packedData, PH_CLEAR_FAULTS_LENGTH,
+ PH_CLEAR_FAULTS_FRAME_API, status);
+}
diff --git a/hal/src/main/native/athena/SPI.cpp b/hal/src/main/native/athena/SPI.cpp
index 1121fd8..0df6fdb 100644
--- a/hal/src/main/native/athena/SPI.cpp
+++ b/hal/src/main/native/athena/SPI.cpp
@@ -496,9 +496,8 @@
}
// configure DMA
- tDMAChannelDescriptor desc;
- spiSystem->getSystemInterface()->getDmaDescriptor(g_SpiAutoData_index, &desc);
- spiAutoDMA = std::make_unique<tDMAManager>(desc.channel, bufferSize, status);
+ spiAutoDMA =
+ std::make_unique<tDMAManager>(g_SpiAutoData_index, bufferSize, status);
}
void HAL_FreeSPIAuto(HAL_SPIPort port, int32_t* status) {
diff --git a/hal/src/main/native/athena/SerialPort.cpp b/hal/src/main/native/athena/SerialPort.cpp
index 374986b..9a25d87 100644
--- a/hal/src/main/native/athena/SerialPort.cpp
+++ b/hal/src/main/native/athena/SerialPort.cpp
@@ -14,7 +14,6 @@
#include <cstdio>
#include <cstdlib>
#include <cstring>
-#include <iostream>
#include <stdexcept>
#include <string>
#include <thread>
@@ -83,7 +82,7 @@
serialPort->portId = open(portName, O_RDWR | O_NOCTTY);
if (serialPort->portId < 0) {
- *status = errno;
+ *status = -errno;
if (*status == EACCES) {
*status = HAL_CONSOLE_OUT_ENABLED_ERROR;
}
@@ -94,8 +93,20 @@
std::memset(&serialPort->tty, 0, sizeof(serialPort->tty));
serialPort->baudRate = B9600;
- cfsetospeed(&serialPort->tty, static_cast<speed_t>(serialPort->baudRate));
- cfsetispeed(&serialPort->tty, static_cast<speed_t>(serialPort->baudRate));
+ if (cfsetospeed(&serialPort->tty,
+ static_cast<speed_t>(serialPort->baudRate)) != 0) {
+ *status = -errno;
+ close(serialPort->portId);
+ serialPortHandles->Free(handle);
+ return HAL_kInvalidHandle;
+ }
+ if (cfsetispeed(&serialPort->tty,
+ static_cast<speed_t>(serialPort->baudRate)) != 0) {
+ *status = -errno;
+ close(serialPort->portId);
+ serialPortHandles->Free(handle);
+ return HAL_kInvalidHandle;
+ }
serialPort->tty.c_cflag &= ~PARENB;
serialPort->tty.c_cflag &= ~CSTOPB;
@@ -115,9 +126,14 @@
*/
serialPort->tty.c_oflag = ~OPOST;
- tcflush(serialPort->portId, TCIOFLUSH);
+ if (tcflush(serialPort->portId, TCIOFLUSH) != 0) {
+ *status = -errno;
+ close(serialPort->portId);
+ serialPortHandles->Free(handle);
+ return HAL_kInvalidHandle;
+ }
if (tcsetattr(serialPort->portId, TCSANOW, &serialPort->tty) != 0) {
- *status = errno;
+ *status = -errno;
close(serialPort->portId);
serialPortHandles->Free(handle);
return HAL_kInvalidHandle;
diff --git a/hal/src/main/native/athena/mockdata/REVPHData.cpp b/hal/src/main/native/athena/mockdata/REVPHData.cpp
index d617694..f2c4e85 100644
--- a/hal/src/main/native/athena/mockdata/REVPHData.cpp
+++ b/hal/src/main/native/athena/mockdata/REVPHData.cpp
@@ -15,7 +15,8 @@
HAL_SIMDATAVALUE_STUB_CAPI_CHANNEL(HAL_Bool, HALSIM, REVPHSolenoidOutput, false)
DEFINE_CAPI(HAL_Bool, Initialized, false)
DEFINE_CAPI(HAL_Bool, CompressorOn, false)
-DEFINE_CAPI(HAL_Bool, ClosedLoopEnabled, false)
+DEFINE_CAPI(HAL_REVPHCompressorConfigType, CompressorConfigType,
+ HAL_REVPHCompressorConfigType_kDisabled)
DEFINE_CAPI(HAL_Bool, PressureSwitch, false)
DEFINE_CAPI(double, CompressorCurrent, 0)
diff --git a/hal/src/main/native/athena/rev/PDHFrames.cpp b/hal/src/main/native/athena/rev/PDHFrames.cpp
index b50a148..eaf33bd 100644
--- a/hal/src/main/native/athena/rev/PDHFrames.cpp
+++ b/hal/src/main/native/athena/rev/PDHFrames.cpp
@@ -112,9 +112,9 @@
return (uint32_t)((uint32_t)(value & mask) >> shift);
}
-int PDH_switch_channel_set_pack(
+int PDH_set_switch_channel_pack(
uint8_t *dst_p,
- const struct PDH_switch_channel_set_t *src_p,
+ const struct PDH_set_switch_channel_t *src_p,
size_t size)
{
if (size < 1u) {
@@ -124,13 +124,12 @@
memset(&dst_p[0], 0, 1);
dst_p[0] |= pack_left_shift_u8(src_p->output_set_value, 0u, 0x01u);
- dst_p[0] |= pack_left_shift_u8(src_p->use_system_enable, 1u, 0x02u);
return (1);
}
-int PDH_switch_channel_set_unpack(
- struct PDH_switch_channel_set_t *dst_p,
+int PDH_set_switch_channel_unpack(
+ struct PDH_set_switch_channel_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -139,44 +138,28 @@
}
dst_p->output_set_value = unpack_right_shift_u8(src_p[0], 0u, 0x01u);
- dst_p->use_system_enable = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
return (0);
}
-uint8_t PDH_switch_channel_set_output_set_value_encode(double value)
+uint8_t PDH_set_switch_channel_output_set_value_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_switch_channel_set_output_set_value_decode(uint8_t value)
+double PDH_set_switch_channel_output_set_value_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_switch_channel_set_output_set_value_is_in_range(uint8_t value)
+bool PDH_set_switch_channel_output_set_value_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_switch_channel_set_use_system_enable_encode(double value)
-{
- return (uint8_t)(value);
-}
-
-double PDH_switch_channel_set_use_system_enable_decode(uint8_t value)
-{
- return ((double)value);
-}
-
-bool PDH_switch_channel_set_use_system_enable_is_in_range(uint8_t value)
-{
- return (value <= 1u);
-}
-
-int PDH_status0_pack(
+int PDH_status_0_pack(
uint8_t *dst_p,
- const struct PDH_status0_t *src_p,
+ const struct PDH_status_0_t *src_p,
size_t size)
{
if (size < 8u) {
@@ -191,22 +174,22 @@
dst_p[2] |= pack_right_shift_u16(src_p->channel_1_current, 6u, 0x0fu);
dst_p[2] |= pack_left_shift_u16(src_p->channel_2_current, 4u, 0xf0u);
dst_p[3] |= pack_right_shift_u16(src_p->channel_2_current, 4u, 0x3fu);
- dst_p[3] |= pack_left_shift_u8(src_p->channel_0_brownout, 6u, 0x40u);
- dst_p[3] |= pack_left_shift_u8(src_p->channel_1_brownout, 7u, 0x80u);
+ dst_p[3] |= pack_left_shift_u8(src_p->channel_0_breaker_fault, 6u, 0x40u);
+ dst_p[3] |= pack_left_shift_u8(src_p->channel_1_breaker_fault, 7u, 0x80u);
dst_p[4] |= pack_left_shift_u16(src_p->channel_3_current, 0u, 0xffu);
dst_p[5] |= pack_right_shift_u16(src_p->channel_3_current, 8u, 0x03u);
dst_p[5] |= pack_left_shift_u16(src_p->channel_4_current, 2u, 0xfcu);
dst_p[6] |= pack_right_shift_u16(src_p->channel_4_current, 6u, 0x0fu);
dst_p[6] |= pack_left_shift_u16(src_p->channel_5_current, 4u, 0xf0u);
dst_p[7] |= pack_right_shift_u16(src_p->channel_5_current, 4u, 0x3fu);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_2_brownout, 6u, 0x40u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_3_brownout, 7u, 0x80u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_2_breaker_fault, 6u, 0x40u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_3_breaker_fault, 7u, 0x80u);
return (8);
}
-int PDH_status0_unpack(
- struct PDH_status0_t *dst_p,
+int PDH_status_0_unpack(
+ struct PDH_status_0_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -220,173 +203,173 @@
dst_p->channel_1_current |= unpack_left_shift_u16(src_p[2], 6u, 0x0fu);
dst_p->channel_2_current = unpack_right_shift_u16(src_p[2], 4u, 0xf0u);
dst_p->channel_2_current |= unpack_left_shift_u16(src_p[3], 4u, 0x3fu);
- dst_p->channel_0_brownout = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
- dst_p->channel_1_brownout = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
+ dst_p->channel_0_breaker_fault = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
+ dst_p->channel_1_breaker_fault = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
dst_p->channel_3_current = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
dst_p->channel_3_current |= unpack_left_shift_u16(src_p[5], 8u, 0x03u);
dst_p->channel_4_current = unpack_right_shift_u16(src_p[5], 2u, 0xfcu);
dst_p->channel_4_current |= unpack_left_shift_u16(src_p[6], 6u, 0x0fu);
dst_p->channel_5_current = unpack_right_shift_u16(src_p[6], 4u, 0xf0u);
dst_p->channel_5_current |= unpack_left_shift_u16(src_p[7], 4u, 0x3fu);
- dst_p->channel_2_brownout = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
- dst_p->channel_3_brownout = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
+ dst_p->channel_2_breaker_fault = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
+ dst_p->channel_3_breaker_fault = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
return (0);
}
-uint16_t PDH_status0_channel_0_current_encode(double value)
+uint16_t PDH_status_0_channel_0_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status0_channel_0_current_decode(uint16_t value)
+double PDH_status_0_channel_0_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status0_channel_0_current_is_in_range(uint16_t value)
+bool PDH_status_0_channel_0_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status0_channel_1_current_encode(double value)
+uint16_t PDH_status_0_channel_1_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status0_channel_1_current_decode(uint16_t value)
+double PDH_status_0_channel_1_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status0_channel_1_current_is_in_range(uint16_t value)
+bool PDH_status_0_channel_1_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status0_channel_2_current_encode(double value)
+uint16_t PDH_status_0_channel_2_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status0_channel_2_current_decode(uint16_t value)
+double PDH_status_0_channel_2_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status0_channel_2_current_is_in_range(uint16_t value)
+bool PDH_status_0_channel_2_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint8_t PDH_status0_channel_0_brownout_encode(double value)
+uint8_t PDH_status_0_channel_0_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status0_channel_0_brownout_decode(uint8_t value)
+double PDH_status_0_channel_0_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status0_channel_0_brownout_is_in_range(uint8_t value)
+bool PDH_status_0_channel_0_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status0_channel_1_brownout_encode(double value)
+uint8_t PDH_status_0_channel_1_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status0_channel_1_brownout_decode(uint8_t value)
+double PDH_status_0_channel_1_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status0_channel_1_brownout_is_in_range(uint8_t value)
+bool PDH_status_0_channel_1_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint16_t PDH_status0_channel_3_current_encode(double value)
+uint16_t PDH_status_0_channel_3_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status0_channel_3_current_decode(uint16_t value)
+double PDH_status_0_channel_3_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status0_channel_3_current_is_in_range(uint16_t value)
+bool PDH_status_0_channel_3_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status0_channel_4_current_encode(double value)
+uint16_t PDH_status_0_channel_4_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status0_channel_4_current_decode(uint16_t value)
+double PDH_status_0_channel_4_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status0_channel_4_current_is_in_range(uint16_t value)
+bool PDH_status_0_channel_4_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status0_channel_5_current_encode(double value)
+uint16_t PDH_status_0_channel_5_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status0_channel_5_current_decode(uint16_t value)
+double PDH_status_0_channel_5_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status0_channel_5_current_is_in_range(uint16_t value)
+bool PDH_status_0_channel_5_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint8_t PDH_status0_channel_2_brownout_encode(double value)
+uint8_t PDH_status_0_channel_2_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status0_channel_2_brownout_decode(uint8_t value)
+double PDH_status_0_channel_2_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status0_channel_2_brownout_is_in_range(uint8_t value)
+bool PDH_status_0_channel_2_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status0_channel_3_brownout_encode(double value)
+uint8_t PDH_status_0_channel_3_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status0_channel_3_brownout_decode(uint8_t value)
+double PDH_status_0_channel_3_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status0_channel_3_brownout_is_in_range(uint8_t value)
+bool PDH_status_0_channel_3_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-int PDH_status1_pack(
+int PDH_status_1_pack(
uint8_t *dst_p,
- const struct PDH_status1_t *src_p,
+ const struct PDH_status_1_t *src_p,
size_t size)
{
if (size < 8u) {
@@ -401,22 +384,22 @@
dst_p[2] |= pack_right_shift_u16(src_p->channel_7_current, 6u, 0x0fu);
dst_p[2] |= pack_left_shift_u16(src_p->channel_8_current, 4u, 0xf0u);
dst_p[3] |= pack_right_shift_u16(src_p->channel_8_current, 4u, 0x3fu);
- dst_p[3] |= pack_left_shift_u8(src_p->channel_4_brownout, 6u, 0x40u);
- dst_p[3] |= pack_left_shift_u8(src_p->channel_5_brownout, 7u, 0x80u);
+ dst_p[3] |= pack_left_shift_u8(src_p->channel_4_breaker_fault, 6u, 0x40u);
+ dst_p[3] |= pack_left_shift_u8(src_p->channel_5_breaker_fault, 7u, 0x80u);
dst_p[4] |= pack_left_shift_u16(src_p->channel_9_current, 0u, 0xffu);
dst_p[5] |= pack_right_shift_u16(src_p->channel_9_current, 8u, 0x03u);
dst_p[5] |= pack_left_shift_u16(src_p->channel_10_current, 2u, 0xfcu);
dst_p[6] |= pack_right_shift_u16(src_p->channel_10_current, 6u, 0x0fu);
dst_p[6] |= pack_left_shift_u16(src_p->channel_11_current, 4u, 0xf0u);
dst_p[7] |= pack_right_shift_u16(src_p->channel_11_current, 4u, 0x3fu);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_6_brownout, 6u, 0x40u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_7_brownout, 7u, 0x80u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_6_breaker_fault, 6u, 0x40u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_7_breaker_fault, 7u, 0x80u);
return (8);
}
-int PDH_status1_unpack(
- struct PDH_status1_t *dst_p,
+int PDH_status_1_unpack(
+ struct PDH_status_1_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -430,173 +413,173 @@
dst_p->channel_7_current |= unpack_left_shift_u16(src_p[2], 6u, 0x0fu);
dst_p->channel_8_current = unpack_right_shift_u16(src_p[2], 4u, 0xf0u);
dst_p->channel_8_current |= unpack_left_shift_u16(src_p[3], 4u, 0x3fu);
- dst_p->channel_4_brownout = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
- dst_p->channel_5_brownout = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
+ dst_p->channel_4_breaker_fault = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
+ dst_p->channel_5_breaker_fault = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
dst_p->channel_9_current = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
dst_p->channel_9_current |= unpack_left_shift_u16(src_p[5], 8u, 0x03u);
dst_p->channel_10_current = unpack_right_shift_u16(src_p[5], 2u, 0xfcu);
dst_p->channel_10_current |= unpack_left_shift_u16(src_p[6], 6u, 0x0fu);
dst_p->channel_11_current = unpack_right_shift_u16(src_p[6], 4u, 0xf0u);
dst_p->channel_11_current |= unpack_left_shift_u16(src_p[7], 4u, 0x3fu);
- dst_p->channel_6_brownout = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
- dst_p->channel_7_brownout = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
+ dst_p->channel_6_breaker_fault = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
+ dst_p->channel_7_breaker_fault = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
return (0);
}
-uint16_t PDH_status1_channel_6_current_encode(double value)
+uint16_t PDH_status_1_channel_6_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status1_channel_6_current_decode(uint16_t value)
+double PDH_status_1_channel_6_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status1_channel_6_current_is_in_range(uint16_t value)
+bool PDH_status_1_channel_6_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status1_channel_7_current_encode(double value)
+uint16_t PDH_status_1_channel_7_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status1_channel_7_current_decode(uint16_t value)
+double PDH_status_1_channel_7_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status1_channel_7_current_is_in_range(uint16_t value)
+bool PDH_status_1_channel_7_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status1_channel_8_current_encode(double value)
+uint16_t PDH_status_1_channel_8_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status1_channel_8_current_decode(uint16_t value)
+double PDH_status_1_channel_8_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status1_channel_8_current_is_in_range(uint16_t value)
+bool PDH_status_1_channel_8_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint8_t PDH_status1_channel_4_brownout_encode(double value)
+uint8_t PDH_status_1_channel_4_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status1_channel_4_brownout_decode(uint8_t value)
+double PDH_status_1_channel_4_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status1_channel_4_brownout_is_in_range(uint8_t value)
+bool PDH_status_1_channel_4_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status1_channel_5_brownout_encode(double value)
+uint8_t PDH_status_1_channel_5_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status1_channel_5_brownout_decode(uint8_t value)
+double PDH_status_1_channel_5_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status1_channel_5_brownout_is_in_range(uint8_t value)
+bool PDH_status_1_channel_5_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint16_t PDH_status1_channel_9_current_encode(double value)
+uint16_t PDH_status_1_channel_9_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status1_channel_9_current_decode(uint16_t value)
+double PDH_status_1_channel_9_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status1_channel_9_current_is_in_range(uint16_t value)
+bool PDH_status_1_channel_9_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status1_channel_10_current_encode(double value)
+uint16_t PDH_status_1_channel_10_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status1_channel_10_current_decode(uint16_t value)
+double PDH_status_1_channel_10_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status1_channel_10_current_is_in_range(uint16_t value)
+bool PDH_status_1_channel_10_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status1_channel_11_current_encode(double value)
+uint16_t PDH_status_1_channel_11_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status1_channel_11_current_decode(uint16_t value)
+double PDH_status_1_channel_11_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status1_channel_11_current_is_in_range(uint16_t value)
+bool PDH_status_1_channel_11_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint8_t PDH_status1_channel_6_brownout_encode(double value)
+uint8_t PDH_status_1_channel_6_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status1_channel_6_brownout_decode(uint8_t value)
+double PDH_status_1_channel_6_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status1_channel_6_brownout_is_in_range(uint8_t value)
+bool PDH_status_1_channel_6_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status1_channel_7_brownout_encode(double value)
+uint8_t PDH_status_1_channel_7_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status1_channel_7_brownout_decode(uint8_t value)
+double PDH_status_1_channel_7_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status1_channel_7_brownout_is_in_range(uint8_t value)
+bool PDH_status_1_channel_7_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-int PDH_status2_pack(
+int PDH_status_2_pack(
uint8_t *dst_p,
- const struct PDH_status2_t *src_p,
+ const struct PDH_status_2_t *src_p,
size_t size)
{
if (size < 8u) {
@@ -611,22 +594,22 @@
dst_p[2] |= pack_right_shift_u16(src_p->channel_13_current, 6u, 0x0fu);
dst_p[2] |= pack_left_shift_u16(src_p->channel_14_current, 4u, 0xf0u);
dst_p[3] |= pack_right_shift_u16(src_p->channel_14_current, 4u, 0x3fu);
- dst_p[3] |= pack_left_shift_u8(src_p->channel_8_brownout, 6u, 0x40u);
- dst_p[3] |= pack_left_shift_u8(src_p->channel_9_brownout, 7u, 0x80u);
+ dst_p[3] |= pack_left_shift_u8(src_p->channel_8_breaker_fault, 6u, 0x40u);
+ dst_p[3] |= pack_left_shift_u8(src_p->channel_9_breaker_fault, 7u, 0x80u);
dst_p[4] |= pack_left_shift_u16(src_p->channel_15_current, 0u, 0xffu);
dst_p[5] |= pack_right_shift_u16(src_p->channel_15_current, 8u, 0x03u);
dst_p[5] |= pack_left_shift_u16(src_p->channel_16_current, 2u, 0xfcu);
dst_p[6] |= pack_right_shift_u16(src_p->channel_16_current, 6u, 0x0fu);
dst_p[6] |= pack_left_shift_u16(src_p->channel_17_current, 4u, 0xf0u);
dst_p[7] |= pack_right_shift_u16(src_p->channel_17_current, 4u, 0x3fu);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_10_brownout, 6u, 0x40u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_11_brownout, 7u, 0x80u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_10_breaker_fault, 6u, 0x40u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_11_breaker_fault, 7u, 0x80u);
return (8);
}
-int PDH_status2_unpack(
- struct PDH_status2_t *dst_p,
+int PDH_status_2_unpack(
+ struct PDH_status_2_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -640,173 +623,173 @@
dst_p->channel_13_current |= unpack_left_shift_u16(src_p[2], 6u, 0x0fu);
dst_p->channel_14_current = unpack_right_shift_u16(src_p[2], 4u, 0xf0u);
dst_p->channel_14_current |= unpack_left_shift_u16(src_p[3], 4u, 0x3fu);
- dst_p->channel_8_brownout = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
- dst_p->channel_9_brownout = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
+ dst_p->channel_8_breaker_fault = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
+ dst_p->channel_9_breaker_fault = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
dst_p->channel_15_current = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
dst_p->channel_15_current |= unpack_left_shift_u16(src_p[5], 8u, 0x03u);
dst_p->channel_16_current = unpack_right_shift_u16(src_p[5], 2u, 0xfcu);
dst_p->channel_16_current |= unpack_left_shift_u16(src_p[6], 6u, 0x0fu);
dst_p->channel_17_current = unpack_right_shift_u16(src_p[6], 4u, 0xf0u);
dst_p->channel_17_current |= unpack_left_shift_u16(src_p[7], 4u, 0x3fu);
- dst_p->channel_10_brownout = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
- dst_p->channel_11_brownout = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
+ dst_p->channel_10_breaker_fault = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
+ dst_p->channel_11_breaker_fault = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
return (0);
}
-uint16_t PDH_status2_channel_12_current_encode(double value)
+uint16_t PDH_status_2_channel_12_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status2_channel_12_current_decode(uint16_t value)
+double PDH_status_2_channel_12_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status2_channel_12_current_is_in_range(uint16_t value)
+bool PDH_status_2_channel_12_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status2_channel_13_current_encode(double value)
+uint16_t PDH_status_2_channel_13_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status2_channel_13_current_decode(uint16_t value)
+double PDH_status_2_channel_13_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status2_channel_13_current_is_in_range(uint16_t value)
+bool PDH_status_2_channel_13_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status2_channel_14_current_encode(double value)
+uint16_t PDH_status_2_channel_14_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status2_channel_14_current_decode(uint16_t value)
+double PDH_status_2_channel_14_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status2_channel_14_current_is_in_range(uint16_t value)
+bool PDH_status_2_channel_14_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint8_t PDH_status2_channel_8_brownout_encode(double value)
+uint8_t PDH_status_2_channel_8_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status2_channel_8_brownout_decode(uint8_t value)
+double PDH_status_2_channel_8_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status2_channel_8_brownout_is_in_range(uint8_t value)
+bool PDH_status_2_channel_8_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status2_channel_9_brownout_encode(double value)
+uint8_t PDH_status_2_channel_9_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status2_channel_9_brownout_decode(uint8_t value)
+double PDH_status_2_channel_9_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status2_channel_9_brownout_is_in_range(uint8_t value)
+bool PDH_status_2_channel_9_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint16_t PDH_status2_channel_15_current_encode(double value)
+uint16_t PDH_status_2_channel_15_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status2_channel_15_current_decode(uint16_t value)
+double PDH_status_2_channel_15_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status2_channel_15_current_is_in_range(uint16_t value)
+bool PDH_status_2_channel_15_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status2_channel_16_current_encode(double value)
+uint16_t PDH_status_2_channel_16_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status2_channel_16_current_decode(uint16_t value)
+double PDH_status_2_channel_16_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status2_channel_16_current_is_in_range(uint16_t value)
+bool PDH_status_2_channel_16_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status2_channel_17_current_encode(double value)
+uint16_t PDH_status_2_channel_17_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status2_channel_17_current_decode(uint16_t value)
+double PDH_status_2_channel_17_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status2_channel_17_current_is_in_range(uint16_t value)
+bool PDH_status_2_channel_17_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint8_t PDH_status2_channel_10_brownout_encode(double value)
+uint8_t PDH_status_2_channel_10_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status2_channel_10_brownout_decode(uint8_t value)
+double PDH_status_2_channel_10_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status2_channel_10_brownout_is_in_range(uint8_t value)
+bool PDH_status_2_channel_10_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status2_channel_11_brownout_encode(double value)
+uint8_t PDH_status_2_channel_11_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status2_channel_11_brownout_decode(uint8_t value)
+double PDH_status_2_channel_11_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status2_channel_11_brownout_is_in_range(uint8_t value)
+bool PDH_status_2_channel_11_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-int PDH_status3_pack(
+int PDH_status_3_pack(
uint8_t *dst_p,
- const struct PDH_status3_t *src_p,
+ const struct PDH_status_3_t *src_p,
size_t size)
{
if (size < 8u) {
@@ -819,28 +802,28 @@
dst_p[1] |= pack_right_shift_u16(src_p->channel_18_current, 8u, 0x03u);
dst_p[1] |= pack_left_shift_u16(src_p->channel_19_current, 2u, 0xfcu);
dst_p[2] |= pack_right_shift_u16(src_p->channel_19_current, 6u, 0x0fu);
- dst_p[2] |= pack_left_shift_u8(src_p->channel_12_brownout, 4u, 0x10u);
- dst_p[2] |= pack_left_shift_u8(src_p->channel_13_brownout, 5u, 0x20u);
- dst_p[2] |= pack_left_shift_u8(src_p->channel_14_brownout, 6u, 0x40u);
- dst_p[2] |= pack_left_shift_u8(src_p->channel_15_brownout, 7u, 0x80u);
+ dst_p[2] |= pack_left_shift_u8(src_p->channel_12_breaker_fault, 4u, 0x10u);
+ dst_p[2] |= pack_left_shift_u8(src_p->channel_13_breaker_fault, 5u, 0x20u);
+ dst_p[2] |= pack_left_shift_u8(src_p->channel_14_breaker_fault, 6u, 0x40u);
+ dst_p[2] |= pack_left_shift_u8(src_p->channel_15_breaker_fault, 7u, 0x80u);
dst_p[3] |= pack_left_shift_u8(src_p->channel_20_current, 0u, 0xffu);
dst_p[4] |= pack_left_shift_u8(src_p->channel_21_current, 0u, 0xffu);
dst_p[5] |= pack_left_shift_u8(src_p->channel_22_current, 0u, 0xffu);
dst_p[6] |= pack_left_shift_u8(src_p->channel_23_current, 0u, 0xffu);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_16_brownout, 0u, 0x01u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_17_brownout, 1u, 0x02u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_18_brownout, 2u, 0x04u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_19_brownout, 3u, 0x08u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_20_brownout, 4u, 0x10u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_21_brownout, 5u, 0x20u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_22_brownout, 6u, 0x40u);
- dst_p[7] |= pack_left_shift_u8(src_p->channel_23_brownout, 7u, 0x80u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_16_breaker_fault, 0u, 0x01u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_17_breaker_fault, 1u, 0x02u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_18_breaker_fault, 2u, 0x04u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_19_breaker_fault, 3u, 0x08u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_20_breaker_fault, 4u, 0x10u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_21_breaker_fault, 5u, 0x20u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_22_breaker_fault, 6u, 0x40u);
+ dst_p[7] |= pack_left_shift_u8(src_p->channel_23_breaker_fault, 7u, 0x80u);
return (8);
}
-int PDH_status3_unpack(
- struct PDH_status3_t *dst_p,
+int PDH_status_3_unpack(
+ struct PDH_status_3_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -852,307 +835,307 @@
dst_p->channel_18_current |= unpack_left_shift_u16(src_p[1], 8u, 0x03u);
dst_p->channel_19_current = unpack_right_shift_u16(src_p[1], 2u, 0xfcu);
dst_p->channel_19_current |= unpack_left_shift_u16(src_p[2], 6u, 0x0fu);
- dst_p->channel_12_brownout = unpack_right_shift_u8(src_p[2], 4u, 0x10u);
- dst_p->channel_13_brownout = unpack_right_shift_u8(src_p[2], 5u, 0x20u);
- dst_p->channel_14_brownout = unpack_right_shift_u8(src_p[2], 6u, 0x40u);
- dst_p->channel_15_brownout = unpack_right_shift_u8(src_p[2], 7u, 0x80u);
+ dst_p->channel_12_breaker_fault = unpack_right_shift_u8(src_p[2], 4u, 0x10u);
+ dst_p->channel_13_breaker_fault = unpack_right_shift_u8(src_p[2], 5u, 0x20u);
+ dst_p->channel_14_breaker_fault = unpack_right_shift_u8(src_p[2], 6u, 0x40u);
+ dst_p->channel_15_breaker_fault = unpack_right_shift_u8(src_p[2], 7u, 0x80u);
dst_p->channel_20_current = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
dst_p->channel_21_current = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
dst_p->channel_22_current = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
dst_p->channel_23_current = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
- dst_p->channel_16_brownout = unpack_right_shift_u8(src_p[7], 0u, 0x01u);
- dst_p->channel_17_brownout = unpack_right_shift_u8(src_p[7], 1u, 0x02u);
- dst_p->channel_18_brownout = unpack_right_shift_u8(src_p[7], 2u, 0x04u);
- dst_p->channel_19_brownout = unpack_right_shift_u8(src_p[7], 3u, 0x08u);
- dst_p->channel_20_brownout = unpack_right_shift_u8(src_p[7], 4u, 0x10u);
- dst_p->channel_21_brownout = unpack_right_shift_u8(src_p[7], 5u, 0x20u);
- dst_p->channel_22_brownout = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
- dst_p->channel_23_brownout = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
+ dst_p->channel_16_breaker_fault = unpack_right_shift_u8(src_p[7], 0u, 0x01u);
+ dst_p->channel_17_breaker_fault = unpack_right_shift_u8(src_p[7], 1u, 0x02u);
+ dst_p->channel_18_breaker_fault = unpack_right_shift_u8(src_p[7], 2u, 0x04u);
+ dst_p->channel_19_breaker_fault = unpack_right_shift_u8(src_p[7], 3u, 0x08u);
+ dst_p->channel_20_breaker_fault = unpack_right_shift_u8(src_p[7], 4u, 0x10u);
+ dst_p->channel_21_breaker_fault = unpack_right_shift_u8(src_p[7], 5u, 0x20u);
+ dst_p->channel_22_breaker_fault = unpack_right_shift_u8(src_p[7], 6u, 0x40u);
+ dst_p->channel_23_breaker_fault = unpack_right_shift_u8(src_p[7], 7u, 0x80u);
return (0);
}
-uint16_t PDH_status3_channel_18_current_encode(double value)
+uint16_t PDH_status_3_channel_18_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status3_channel_18_current_decode(uint16_t value)
+double PDH_status_3_channel_18_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status3_channel_18_current_is_in_range(uint16_t value)
+bool PDH_status_3_channel_18_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint16_t PDH_status3_channel_19_current_encode(double value)
+uint16_t PDH_status_3_channel_19_current_encode(double value)
{
return (uint16_t)(value / 0.125);
}
-double PDH_status3_channel_19_current_decode(uint16_t value)
+double PDH_status_3_channel_19_current_decode(uint16_t value)
{
return ((double)value * 0.125);
}
-bool PDH_status3_channel_19_current_is_in_range(uint16_t value)
+bool PDH_status_3_channel_19_current_is_in_range(uint16_t value)
{
return (value <= 1023u);
}
-uint8_t PDH_status3_channel_12_brownout_encode(double value)
+uint8_t PDH_status_3_channel_12_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_12_brownout_decode(uint8_t value)
+double PDH_status_3_channel_12_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_12_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_12_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_13_brownout_encode(double value)
+uint8_t PDH_status_3_channel_13_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_13_brownout_decode(uint8_t value)
+double PDH_status_3_channel_13_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_13_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_13_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_14_brownout_encode(double value)
+uint8_t PDH_status_3_channel_14_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_14_brownout_decode(uint8_t value)
+double PDH_status_3_channel_14_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_14_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_14_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_15_brownout_encode(double value)
+uint8_t PDH_status_3_channel_15_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_15_brownout_decode(uint8_t value)
+double PDH_status_3_channel_15_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_15_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_15_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_20_current_encode(double value)
+uint8_t PDH_status_3_channel_20_current_encode(double value)
{
return (uint8_t)(value / 0.0625);
}
-double PDH_status3_channel_20_current_decode(uint8_t value)
+double PDH_status_3_channel_20_current_decode(uint8_t value)
{
return ((double)value * 0.0625);
}
-bool PDH_status3_channel_20_current_is_in_range(uint8_t value)
+bool PDH_status_3_channel_20_current_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PDH_status3_channel_21_current_encode(double value)
+uint8_t PDH_status_3_channel_21_current_encode(double value)
{
return (uint8_t)(value / 0.0625);
}
-double PDH_status3_channel_21_current_decode(uint8_t value)
+double PDH_status_3_channel_21_current_decode(uint8_t value)
{
return ((double)value * 0.0625);
}
-bool PDH_status3_channel_21_current_is_in_range(uint8_t value)
+bool PDH_status_3_channel_21_current_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PDH_status3_channel_22_current_encode(double value)
+uint8_t PDH_status_3_channel_22_current_encode(double value)
{
return (uint8_t)(value / 0.0625);
}
-double PDH_status3_channel_22_current_decode(uint8_t value)
+double PDH_status_3_channel_22_current_decode(uint8_t value)
{
return ((double)value * 0.0625);
}
-bool PDH_status3_channel_22_current_is_in_range(uint8_t value)
+bool PDH_status_3_channel_22_current_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PDH_status3_channel_23_current_encode(double value)
+uint8_t PDH_status_3_channel_23_current_encode(double value)
{
return (uint8_t)(value / 0.0625);
}
-double PDH_status3_channel_23_current_decode(uint8_t value)
+double PDH_status_3_channel_23_current_decode(uint8_t value)
{
return ((double)value * 0.0625);
}
-bool PDH_status3_channel_23_current_is_in_range(uint8_t value)
+bool PDH_status_3_channel_23_current_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PDH_status3_channel_16_brownout_encode(double value)
+uint8_t PDH_status_3_channel_16_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_16_brownout_decode(uint8_t value)
+double PDH_status_3_channel_16_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_16_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_16_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_17_brownout_encode(double value)
+uint8_t PDH_status_3_channel_17_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_17_brownout_decode(uint8_t value)
+double PDH_status_3_channel_17_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_17_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_17_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_18_brownout_encode(double value)
+uint8_t PDH_status_3_channel_18_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_18_brownout_decode(uint8_t value)
+double PDH_status_3_channel_18_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_18_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_18_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_19_brownout_encode(double value)
+uint8_t PDH_status_3_channel_19_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_19_brownout_decode(uint8_t value)
+double PDH_status_3_channel_19_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_19_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_19_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_20_brownout_encode(double value)
+uint8_t PDH_status_3_channel_20_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_20_brownout_decode(uint8_t value)
+double PDH_status_3_channel_20_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_20_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_20_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_21_brownout_encode(double value)
+uint8_t PDH_status_3_channel_21_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_21_brownout_decode(uint8_t value)
+double PDH_status_3_channel_21_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_21_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_21_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_22_brownout_encode(double value)
+uint8_t PDH_status_3_channel_22_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_22_brownout_decode(uint8_t value)
+double PDH_status_3_channel_22_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_22_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_22_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status3_channel_23_brownout_encode(double value)
+uint8_t PDH_status_3_channel_23_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status3_channel_23_brownout_decode(uint8_t value)
+double PDH_status_3_channel_23_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status3_channel_23_brownout_is_in_range(uint8_t value)
+bool PDH_status_3_channel_23_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-int PDH_status4_pack(
+int PDH_status_4_pack(
uint8_t *dst_p,
- const struct PDH_status4_t *src_p,
+ const struct PDH_status_4_t *src_p,
size_t size)
{
if (size < 8u) {
@@ -1165,29 +1148,49 @@
dst_p[1] |= pack_right_shift_u16(src_p->v_bus, 8u, 0x0fu);
dst_p[1] |= pack_left_shift_u8(src_p->system_enable, 4u, 0x10u);
dst_p[1] |= pack_left_shift_u8(src_p->rsvd0, 5u, 0xe0u);
- dst_p[2] |= pack_left_shift_u8(src_p->brownout, 0u, 0x01u);
+ dst_p[2] |= pack_left_shift_u8(src_p->brownout_fault, 0u, 0x01u);
dst_p[2] |= pack_left_shift_u8(src_p->rsvd1, 1u, 0x02u);
- dst_p[2] |= pack_left_shift_u8(src_p->can_warning, 2u, 0x04u);
+ dst_p[2] |= pack_left_shift_u8(src_p->can_warning_fault, 2u, 0x04u);
dst_p[2] |= pack_left_shift_u8(src_p->hardware_fault, 3u, 0x08u);
- dst_p[2] |= pack_left_shift_u8(src_p->sw_state, 4u, 0x10u);
- dst_p[2] |= pack_left_shift_u8(src_p->sticky_brownout, 5u, 0x20u);
+ dst_p[2] |= pack_left_shift_u8(src_p->switch_channel_state, 4u, 0x10u);
+ dst_p[2] |= pack_left_shift_u8(src_p->sticky_brownout_fault, 5u, 0x20u);
dst_p[2] |= pack_left_shift_u8(src_p->rsvd2, 6u, 0x40u);
- dst_p[2] |= pack_left_shift_u8(src_p->sticky_can_warning, 7u, 0x80u);
- dst_p[3] |= pack_left_shift_u8(src_p->sticky_can_bus_off, 0u, 0x01u);
+ dst_p[2] |= pack_left_shift_u8(src_p->sticky_can_warning_fault, 7u, 0x80u);
+ dst_p[3] |= pack_left_shift_u8(src_p->sticky_can_bus_off_fault, 0u, 0x01u);
dst_p[3] |= pack_left_shift_u8(src_p->sticky_hardware_fault, 1u, 0x02u);
dst_p[3] |= pack_left_shift_u8(src_p->sticky_firmware_fault, 2u, 0x04u);
- dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch20_brownout, 3u, 0x08u);
- dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch21_brownout, 4u, 0x10u);
- dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch22_brownout, 5u, 0x20u);
- dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch23_brownout, 6u, 0x40u);
- dst_p[3] |= pack_left_shift_u8(src_p->sticky_has_reset, 7u, 0x80u);
+ dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch20_breaker_fault, 3u, 0x08u);
+ dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch21_breaker_fault, 4u, 0x10u);
+ dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch22_breaker_fault, 5u, 0x20u);
+ dst_p[3] |= pack_left_shift_u8(src_p->sticky_ch23_breaker_fault, 6u, 0x40u);
+ dst_p[3] |= pack_left_shift_u8(src_p->sticky_has_reset_fault, 7u, 0x80u);
dst_p[4] |= pack_left_shift_u8(src_p->total_current, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch0_breaker_fault, 0u, 0x01u);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch1_breaker_fault, 1u, 0x02u);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch2_breaker_fault, 2u, 0x04u);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch3_breaker_fault, 3u, 0x08u);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch4_breaker_fault, 4u, 0x10u);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch5_breaker_fault, 5u, 0x20u);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch6_breaker_fault, 6u, 0x40u);
+ dst_p[5] |= pack_left_shift_u8(src_p->sticky_ch7_breaker_fault, 7u, 0x80u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch8_breaker_fault, 0u, 0x01u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch9_breaker_fault, 1u, 0x02u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch10_breaker_fault, 2u, 0x04u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch11_breaker_fault, 3u, 0x08u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch12_breaker_fault, 4u, 0x10u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch13_breaker_fault, 5u, 0x20u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch14_breaker_fault, 6u, 0x40u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_ch15_breaker_fault, 7u, 0x80u);
+ dst_p[7] |= pack_left_shift_u8(src_p->sticky_ch16_breaker_fault, 0u, 0x01u);
+ dst_p[7] |= pack_left_shift_u8(src_p->sticky_ch17_breaker_fault, 1u, 0x02u);
+ dst_p[7] |= pack_left_shift_u8(src_p->sticky_ch18_breaker_fault, 2u, 0x04u);
+ dst_p[7] |= pack_left_shift_u8(src_p->sticky_ch19_breaker_fault, 3u, 0x08u);
return (8);
}
-int PDH_status4_unpack(
- struct PDH_status4_t *dst_p,
+int PDH_status_4_unpack(
+ struct PDH_status_4_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -1199,329 +1202,649 @@
dst_p->v_bus |= unpack_left_shift_u16(src_p[1], 8u, 0x0fu);
dst_p->system_enable = unpack_right_shift_u8(src_p[1], 4u, 0x10u);
dst_p->rsvd0 = unpack_right_shift_u8(src_p[1], 5u, 0xe0u);
- dst_p->brownout = unpack_right_shift_u8(src_p[2], 0u, 0x01u);
+ dst_p->brownout_fault = unpack_right_shift_u8(src_p[2], 0u, 0x01u);
dst_p->rsvd1 = unpack_right_shift_u8(src_p[2], 1u, 0x02u);
- dst_p->can_warning = unpack_right_shift_u8(src_p[2], 2u, 0x04u);
+ dst_p->can_warning_fault = unpack_right_shift_u8(src_p[2], 2u, 0x04u);
dst_p->hardware_fault = unpack_right_shift_u8(src_p[2], 3u, 0x08u);
- dst_p->sw_state = unpack_right_shift_u8(src_p[2], 4u, 0x10u);
- dst_p->sticky_brownout = unpack_right_shift_u8(src_p[2], 5u, 0x20u);
+ dst_p->switch_channel_state = unpack_right_shift_u8(src_p[2], 4u, 0x10u);
+ dst_p->sticky_brownout_fault = unpack_right_shift_u8(src_p[2], 5u, 0x20u);
dst_p->rsvd2 = unpack_right_shift_u8(src_p[2], 6u, 0x40u);
- dst_p->sticky_can_warning = unpack_right_shift_u8(src_p[2], 7u, 0x80u);
- dst_p->sticky_can_bus_off = unpack_right_shift_u8(src_p[3], 0u, 0x01u);
+ dst_p->sticky_can_warning_fault = unpack_right_shift_u8(src_p[2], 7u, 0x80u);
+ dst_p->sticky_can_bus_off_fault = unpack_right_shift_u8(src_p[3], 0u, 0x01u);
dst_p->sticky_hardware_fault = unpack_right_shift_u8(src_p[3], 1u, 0x02u);
dst_p->sticky_firmware_fault = unpack_right_shift_u8(src_p[3], 2u, 0x04u);
- dst_p->sticky_ch20_brownout = unpack_right_shift_u8(src_p[3], 3u, 0x08u);
- dst_p->sticky_ch21_brownout = unpack_right_shift_u8(src_p[3], 4u, 0x10u);
- dst_p->sticky_ch22_brownout = unpack_right_shift_u8(src_p[3], 5u, 0x20u);
- dst_p->sticky_ch23_brownout = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
- dst_p->sticky_has_reset = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
+ dst_p->sticky_ch20_breaker_fault = unpack_right_shift_u8(src_p[3], 3u, 0x08u);
+ dst_p->sticky_ch21_breaker_fault = unpack_right_shift_u8(src_p[3], 4u, 0x10u);
+ dst_p->sticky_ch22_breaker_fault = unpack_right_shift_u8(src_p[3], 5u, 0x20u);
+ dst_p->sticky_ch23_breaker_fault = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
+ dst_p->sticky_has_reset_fault = unpack_right_shift_u8(src_p[3], 7u, 0x80u);
dst_p->total_current = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->sticky_ch0_breaker_fault = unpack_right_shift_u8(src_p[5], 0u, 0x01u);
+ dst_p->sticky_ch1_breaker_fault = unpack_right_shift_u8(src_p[5], 1u, 0x02u);
+ dst_p->sticky_ch2_breaker_fault = unpack_right_shift_u8(src_p[5], 2u, 0x04u);
+ dst_p->sticky_ch3_breaker_fault = unpack_right_shift_u8(src_p[5], 3u, 0x08u);
+ dst_p->sticky_ch4_breaker_fault = unpack_right_shift_u8(src_p[5], 4u, 0x10u);
+ dst_p->sticky_ch5_breaker_fault = unpack_right_shift_u8(src_p[5], 5u, 0x20u);
+ dst_p->sticky_ch6_breaker_fault = unpack_right_shift_u8(src_p[5], 6u, 0x40u);
+ dst_p->sticky_ch7_breaker_fault = unpack_right_shift_u8(src_p[5], 7u, 0x80u);
+ dst_p->sticky_ch8_breaker_fault = unpack_right_shift_u8(src_p[6], 0u, 0x01u);
+ dst_p->sticky_ch9_breaker_fault = unpack_right_shift_u8(src_p[6], 1u, 0x02u);
+ dst_p->sticky_ch10_breaker_fault = unpack_right_shift_u8(src_p[6], 2u, 0x04u);
+ dst_p->sticky_ch11_breaker_fault = unpack_right_shift_u8(src_p[6], 3u, 0x08u);
+ dst_p->sticky_ch12_breaker_fault = unpack_right_shift_u8(src_p[6], 4u, 0x10u);
+ dst_p->sticky_ch13_breaker_fault = unpack_right_shift_u8(src_p[6], 5u, 0x20u);
+ dst_p->sticky_ch14_breaker_fault = unpack_right_shift_u8(src_p[6], 6u, 0x40u);
+ dst_p->sticky_ch15_breaker_fault = unpack_right_shift_u8(src_p[6], 7u, 0x80u);
+ dst_p->sticky_ch16_breaker_fault = unpack_right_shift_u8(src_p[7], 0u, 0x01u);
+ dst_p->sticky_ch17_breaker_fault = unpack_right_shift_u8(src_p[7], 1u, 0x02u);
+ dst_p->sticky_ch18_breaker_fault = unpack_right_shift_u8(src_p[7], 2u, 0x04u);
+ dst_p->sticky_ch19_breaker_fault = unpack_right_shift_u8(src_p[7], 3u, 0x08u);
return (0);
}
-uint16_t PDH_status4_v_bus_encode(double value)
+uint16_t PDH_status_4_v_bus_encode(double value)
{
return (uint16_t)(value / 0.0078125);
}
-double PDH_status4_v_bus_decode(uint16_t value)
+double PDH_status_4_v_bus_decode(uint16_t value)
{
return ((double)value * 0.0078125);
}
-bool PDH_status4_v_bus_is_in_range(uint16_t value)
+bool PDH_status_4_v_bus_is_in_range(uint16_t value)
{
return (value <= 4095u);
}
-uint8_t PDH_status4_system_enable_encode(double value)
+uint8_t PDH_status_4_system_enable_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_system_enable_decode(uint8_t value)
+double PDH_status_4_system_enable_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_system_enable_is_in_range(uint8_t value)
+bool PDH_status_4_system_enable_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_rsvd0_encode(double value)
+uint8_t PDH_status_4_rsvd0_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_rsvd0_decode(uint8_t value)
+double PDH_status_4_rsvd0_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_rsvd0_is_in_range(uint8_t value)
+bool PDH_status_4_rsvd0_is_in_range(uint8_t value)
{
return (value <= 7u);
}
-uint8_t PDH_status4_brownout_encode(double value)
+uint8_t PDH_status_4_brownout_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_brownout_decode(uint8_t value)
+double PDH_status_4_brownout_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_brownout_is_in_range(uint8_t value)
+bool PDH_status_4_brownout_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_rsvd1_encode(double value)
+uint8_t PDH_status_4_rsvd1_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_rsvd1_decode(uint8_t value)
+double PDH_status_4_rsvd1_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_rsvd1_is_in_range(uint8_t value)
+bool PDH_status_4_rsvd1_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_can_warning_encode(double value)
+uint8_t PDH_status_4_can_warning_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_can_warning_decode(uint8_t value)
+double PDH_status_4_can_warning_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_can_warning_is_in_range(uint8_t value)
+bool PDH_status_4_can_warning_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_hardware_fault_encode(double value)
+uint8_t PDH_status_4_hardware_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_hardware_fault_decode(uint8_t value)
+double PDH_status_4_hardware_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_hardware_fault_is_in_range(uint8_t value)
+bool PDH_status_4_hardware_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sw_state_encode(double value)
+uint8_t PDH_status_4_switch_channel_state_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sw_state_decode(uint8_t value)
+double PDH_status_4_switch_channel_state_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sw_state_is_in_range(uint8_t value)
+bool PDH_status_4_switch_channel_state_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_brownout_encode(double value)
+uint8_t PDH_status_4_sticky_brownout_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_brownout_decode(uint8_t value)
+double PDH_status_4_sticky_brownout_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_brownout_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_brownout_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_rsvd2_encode(double value)
+uint8_t PDH_status_4_rsvd2_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_rsvd2_decode(uint8_t value)
+double PDH_status_4_rsvd2_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_rsvd2_is_in_range(uint8_t value)
+bool PDH_status_4_rsvd2_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_can_warning_encode(double value)
+uint8_t PDH_status_4_sticky_can_warning_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_can_warning_decode(uint8_t value)
+double PDH_status_4_sticky_can_warning_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_can_warning_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_can_warning_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_can_bus_off_encode(double value)
+uint8_t PDH_status_4_sticky_can_bus_off_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_can_bus_off_decode(uint8_t value)
+double PDH_status_4_sticky_can_bus_off_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_can_bus_off_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_can_bus_off_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_hardware_fault_encode(double value)
+uint8_t PDH_status_4_sticky_hardware_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_hardware_fault_decode(uint8_t value)
+double PDH_status_4_sticky_hardware_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_hardware_fault_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_hardware_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_firmware_fault_encode(double value)
+uint8_t PDH_status_4_sticky_firmware_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_firmware_fault_decode(uint8_t value)
+double PDH_status_4_sticky_firmware_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_firmware_fault_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_firmware_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_ch20_brownout_encode(double value)
+uint8_t PDH_status_4_sticky_ch20_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_ch20_brownout_decode(uint8_t value)
+double PDH_status_4_sticky_ch20_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_ch20_brownout_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_ch20_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_ch21_brownout_encode(double value)
+uint8_t PDH_status_4_sticky_ch21_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_ch21_brownout_decode(uint8_t value)
+double PDH_status_4_sticky_ch21_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_ch21_brownout_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_ch21_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_ch22_brownout_encode(double value)
+uint8_t PDH_status_4_sticky_ch22_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_ch22_brownout_decode(uint8_t value)
+double PDH_status_4_sticky_ch22_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_ch22_brownout_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_ch22_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_ch23_brownout_encode(double value)
+uint8_t PDH_status_4_sticky_ch23_breaker_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_ch23_brownout_decode(uint8_t value)
+double PDH_status_4_sticky_ch23_breaker_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_ch23_brownout_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_ch23_breaker_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_sticky_has_reset_encode(double value)
+uint8_t PDH_status_4_sticky_has_reset_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_status4_sticky_has_reset_decode(uint8_t value)
+double PDH_status_4_sticky_has_reset_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_status4_sticky_has_reset_is_in_range(uint8_t value)
+bool PDH_status_4_sticky_has_reset_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PDH_status4_total_current_encode(double value)
+uint8_t PDH_status_4_total_current_encode(double value)
{
return (uint8_t)(value / 2.0);
}
-double PDH_status4_total_current_decode(uint8_t value)
+double PDH_status_4_total_current_decode(uint8_t value)
{
return ((double)value * 2.0);
}
-bool PDH_status4_total_current_is_in_range(uint8_t value)
+bool PDH_status_4_total_current_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
+uint8_t PDH_status_4_sticky_ch0_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch0_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch0_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch1_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch1_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch1_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch2_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch2_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch2_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch3_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch3_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch3_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch4_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch4_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch4_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch5_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch5_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch5_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch6_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch6_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch6_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch7_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch7_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch7_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch8_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch8_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch8_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch9_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch9_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch9_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch10_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch10_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch10_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch11_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch11_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch11_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch12_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch12_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch12_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch13_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch13_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch13_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch14_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch14_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch14_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch15_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch15_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch15_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch16_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch16_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch16_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch17_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch17_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch17_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch18_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch18_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch18_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PDH_status_4_sticky_ch19_breaker_fault_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_status_4_sticky_ch19_breaker_fault_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_status_4_sticky_ch19_breaker_fault_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
int PDH_clear_faults_pack(
uint8_t *dst_p,
const struct PDH_clear_faults_t *src_p,
@@ -1546,30 +1869,6 @@
return (0);
}
-int PDH_identify_pack(
- uint8_t *dst_p,
- const struct PDH_identify_t *src_p,
- size_t size)
-{
- (void)dst_p;
- (void)src_p;
- (void)size;
-
- return (0);
-}
-
-int PDH_identify_unpack(
- struct PDH_identify_t *dst_p,
- const uint8_t *src_p,
- size_t size)
-{
- (void)dst_p;
- (void)src_p;
- (void)size;
-
- return (0);
-}
-
int PDH_version_pack(
uint8_t *dst_p,
const struct PDH_version_t *src_p,
@@ -1584,11 +1883,11 @@
dst_p[0] |= pack_left_shift_u8(src_p->firmware_fix, 0u, 0xffu);
dst_p[1] |= pack_left_shift_u8(src_p->firmware_minor, 0u, 0xffu);
dst_p[2] |= pack_left_shift_u8(src_p->firmware_year, 0u, 0xffu);
- dst_p[3] |= pack_left_shift_u8(src_p->hardware_code, 0u, 0xffu);
- dst_p[4] |= pack_left_shift_u32(src_p->unique_id, 0u, 0xffu);
- dst_p[5] |= pack_right_shift_u32(src_p->unique_id, 8u, 0xffu);
- dst_p[6] |= pack_right_shift_u32(src_p->unique_id, 16u, 0xffu);
- dst_p[7] |= pack_right_shift_u32(src_p->unique_id, 24u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->hardware_minor, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->hardware_major, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->unique_id, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u32(src_p->unique_id, 8u, 0xffu);
+ dst_p[7] |= pack_right_shift_u32(src_p->unique_id, 16u, 0xffu);
return (8);
}
@@ -1605,11 +1904,11 @@
dst_p->firmware_fix = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
dst_p->firmware_minor = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
dst_p->firmware_year = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
- dst_p->hardware_code = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
- dst_p->unique_id = unpack_right_shift_u32(src_p[4], 0u, 0xffu);
- dst_p->unique_id |= unpack_left_shift_u32(src_p[5], 8u, 0xffu);
- dst_p->unique_id |= unpack_left_shift_u32(src_p[6], 16u, 0xffu);
- dst_p->unique_id |= unpack_left_shift_u32(src_p[7], 24u, 0xffu);
+ dst_p->hardware_minor = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->hardware_major = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->unique_id = unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+ dst_p->unique_id |= unpack_left_shift_u32(src_p[6], 8u, 0xffu);
+ dst_p->unique_id |= unpack_left_shift_u32(src_p[7], 16u, 0xffu);
return (0);
}
@@ -1665,17 +1964,34 @@
return (true);
}
-uint8_t PDH_version_hardware_code_encode(double value)
+uint8_t PDH_version_hardware_minor_encode(double value)
{
return (uint8_t)(value);
}
-double PDH_version_hardware_code_decode(uint8_t value)
+double PDH_version_hardware_minor_decode(uint8_t value)
{
return ((double)value);
}
-bool PDH_version_hardware_code_is_in_range(uint8_t value)
+bool PDH_version_hardware_minor_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t PDH_version_hardware_major_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PDH_version_hardware_major_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PDH_version_hardware_major_is_in_range(uint8_t value)
{
(void)value;
@@ -1694,97 +2010,5 @@
bool PDH_version_unique_id_is_in_range(uint32_t value)
{
- (void)value;
-
- return (true);
-}
-
-int PDH_configure_hr_channel_pack(
- uint8_t *dst_p,
- const struct PDH_configure_hr_channel_t *src_p,
- size_t size)
-{
- if (size < 3u) {
- return (-EINVAL);
- }
-
- memset(&dst_p[0], 0, 3);
-
- dst_p[0] |= pack_left_shift_u8(src_p->channel, 0u, 0xffu);
- dst_p[1] |= pack_left_shift_u16(src_p->period, 0u, 0xffu);
- dst_p[2] |= pack_right_shift_u16(src_p->period, 8u, 0xffu);
-
- return (3);
-}
-
-int PDH_configure_hr_channel_unpack(
- struct PDH_configure_hr_channel_t *dst_p,
- const uint8_t *src_p,
- size_t size)
-{
- if (size < 3u) {
- return (-EINVAL);
- }
-
- dst_p->channel = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
- dst_p->period = unpack_right_shift_u16(src_p[1], 0u, 0xffu);
- dst_p->period |= unpack_left_shift_u16(src_p[2], 8u, 0xffu);
-
- return (0);
-}
-
-uint8_t PDH_configure_hr_channel_channel_encode(double value)
-{
- return (uint8_t)(value);
-}
-
-double PDH_configure_hr_channel_channel_decode(uint8_t value)
-{
- return ((double)value);
-}
-
-bool PDH_configure_hr_channel_channel_is_in_range(uint8_t value)
-{
- return (value <= 23u);
-}
-
-uint16_t PDH_configure_hr_channel_period_encode(double value)
-{
- return (uint16_t)(value);
-}
-
-double PDH_configure_hr_channel_period_decode(uint16_t value)
-{
- return ((double)value);
-}
-
-bool PDH_configure_hr_channel_period_is_in_range(uint16_t value)
-{
- (void)value;
-
- return (true);
-}
-
-int PDH_enter_bootloader_pack(
- uint8_t *dst_p,
- const struct PDH_enter_bootloader_t *src_p,
- size_t size)
-{
- (void)dst_p;
- (void)src_p;
- (void)size;
-
- return (0);
-}
-
-int PDH_enter_bootloader_unpack(
- struct PDH_enter_bootloader_t *dst_p,
- const uint8_t *src_p,
- size_t size)
-{
- (void)dst_p;
- (void)src_p;
- (void)size;
-
- return (0);
+ return (value <= 16777215u);
}
diff --git a/hal/src/main/native/athena/rev/PDHFrames.h b/hal/src/main/native/athena/rev/PDHFrames.h
index 5d2452a..eb498c9 100644
--- a/hal/src/main/native/athena/rev/PDHFrames.h
+++ b/hal/src/main/native/athena/rev/PDHFrames.h
@@ -44,43 +44,34 @@
#endif
/* Frame ids. */
-#define PDH_SWITCH_CHANNEL_SET_FRAME_ID (0x8050840u)
-#define PDH_STATUS0_FRAME_ID (0x8051800u)
-#define PDH_STATUS1_FRAME_ID (0x8051840u)
-#define PDH_STATUS2_FRAME_ID (0x8051880u)
-#define PDH_STATUS3_FRAME_ID (0x80518c0u)
-#define PDH_STATUS4_FRAME_ID (0x8051900u)
+#define PDH_SET_SWITCH_CHANNEL_FRAME_ID (0x8050840u)
+#define PDH_STATUS_0_FRAME_ID (0x8051800u)
+#define PDH_STATUS_1_FRAME_ID (0x8051840u)
+#define PDH_STATUS_2_FRAME_ID (0x8051880u)
+#define PDH_STATUS_3_FRAME_ID (0x80518c0u)
+#define PDH_STATUS_4_FRAME_ID (0x8051900u)
#define PDH_CLEAR_FAULTS_FRAME_ID (0x8051b80u)
-#define PDH_IDENTIFY_FRAME_ID (0x8051d80u)
#define PDH_VERSION_FRAME_ID (0x8052600u)
-#define PDH_CONFIGURE_HR_CHANNEL_FRAME_ID (0x80538c0u)
-#define PDH_ENTER_BOOTLOADER_FRAME_ID (0x8057fc0u)
/* Frame lengths in bytes. */
-#define PDH_SWITCH_CHANNEL_SET_LENGTH (1u)
-#define PDH_STATUS0_LENGTH (8u)
-#define PDH_STATUS1_LENGTH (8u)
-#define PDH_STATUS2_LENGTH (8u)
-#define PDH_STATUS3_LENGTH (8u)
-#define PDH_STATUS4_LENGTH (8u)
+#define PDH_SET_SWITCH_CHANNEL_LENGTH (1u)
+#define PDH_STATUS_0_LENGTH (8u)
+#define PDH_STATUS_1_LENGTH (8u)
+#define PDH_STATUS_2_LENGTH (8u)
+#define PDH_STATUS_3_LENGTH (8u)
+#define PDH_STATUS_4_LENGTH (8u)
#define PDH_CLEAR_FAULTS_LENGTH (0u)
-#define PDH_IDENTIFY_LENGTH (0u)
#define PDH_VERSION_LENGTH (8u)
-#define PDH_CONFIGURE_HR_CHANNEL_LENGTH (3u)
-#define PDH_ENTER_BOOTLOADER_LENGTH (0u)
/* Extended or standard frame types. */
-#define PDH_SWITCH_CHANNEL_SET_IS_EXTENDED (1)
-#define PDH_STATUS0_IS_EXTENDED (1)
-#define PDH_STATUS1_IS_EXTENDED (1)
-#define PDH_STATUS2_IS_EXTENDED (1)
-#define PDH_STATUS3_IS_EXTENDED (1)
-#define PDH_STATUS4_IS_EXTENDED (1)
+#define PDH_SET_SWITCH_CHANNEL_IS_EXTENDED (1)
+#define PDH_STATUS_0_IS_EXTENDED (1)
+#define PDH_STATUS_1_IS_EXTENDED (1)
+#define PDH_STATUS_2_IS_EXTENDED (1)
+#define PDH_STATUS_3_IS_EXTENDED (1)
+#define PDH_STATUS_4_IS_EXTENDED (1)
#define PDH_CLEAR_FAULTS_IS_EXTENDED (1)
-#define PDH_IDENTIFY_IS_EXTENDED (1)
#define PDH_VERSION_IS_EXTENDED (1)
-#define PDH_CONFIGURE_HR_CHANNEL_IS_EXTENDED (1)
-#define PDH_ENTER_BOOTLOADER_IS_EXTENDED (1)
/* Frame cycle times in milliseconds. */
@@ -89,36 +80,29 @@
/**
- * Signals in message SwitchChannelSet.
+ * Signals in message Set_Switch_Channel.
*
* Set the switch channel output
*
* All signal values are as on the CAN bus.
*/
-struct PDH_switch_channel_set_t {
+struct PDH_set_switch_channel_t {
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
uint8_t output_set_value : 1;
-
- /**
- * Range: 0..1 (0..1 -)
- * Scale: 1
- * Offset: 0
- */
- uint8_t use_system_enable : 1;
};
/**
- * Signals in message Status0.
+ * Signals in message Status_0.
*
* Periodic status frame 0
*
* All signal values are as on the CAN bus.
*/
-struct PDH_status0_t {
+struct PDH_status_0_t {
/**
* Range: 0..1023 (0..127.875 A)
* Scale: 0.125
@@ -145,14 +129,14 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_0_brownout : 1;
+ uint8_t channel_0_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_1_brownout : 1;
+ uint8_t channel_1_breaker_fault : 1;
/**
* Range: 0..1023 (0..127.875 A)
@@ -180,24 +164,24 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_2_brownout : 1;
+ uint8_t channel_2_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_3_brownout : 1;
+ uint8_t channel_3_breaker_fault : 1;
};
/**
- * Signals in message Status1.
+ * Signals in message Status_1.
*
* Periodic status frame 1
*
* All signal values are as on the CAN bus.
*/
-struct PDH_status1_t {
+struct PDH_status_1_t {
/**
* Range: 0..1023 (0..127.875 A)
* Scale: 0.125
@@ -224,14 +208,14 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_4_brownout : 1;
+ uint8_t channel_4_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_5_brownout : 1;
+ uint8_t channel_5_breaker_fault : 1;
/**
* Range: 0..1023 (0..127.875 A)
@@ -259,24 +243,24 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_6_brownout : 1;
+ uint8_t channel_6_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_7_brownout : 1;
+ uint8_t channel_7_breaker_fault : 1;
};
/**
- * Signals in message Status2.
+ * Signals in message Status_2.
*
* Periodic status frame 2
*
* All signal values are as on the CAN bus.
*/
-struct PDH_status2_t {
+struct PDH_status_2_t {
/**
* Range: 0..1023 (0..127.875 A)
* Scale: 0.125
@@ -303,14 +287,14 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_8_brownout : 1;
+ uint8_t channel_8_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_9_brownout : 1;
+ uint8_t channel_9_breaker_fault : 1;
/**
* Range: 0..1023 (0..127.875 A)
@@ -338,24 +322,24 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_10_brownout : 1;
+ uint8_t channel_10_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_11_brownout : 1;
+ uint8_t channel_11_breaker_fault : 1;
};
/**
- * Signals in message Status3.
+ * Signals in message Status_3.
*
* Periodic status frame 3
*
* All signal values are as on the CAN bus.
*/
-struct PDH_status3_t {
+struct PDH_status_3_t {
/**
* Range: 0..1023 (0..127.875 A)
* Scale: 0.125
@@ -375,38 +359,38 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_12_brownout : 1;
+ uint8_t channel_12_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_13_brownout : 1;
+ uint8_t channel_13_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_14_brownout : 1;
+ uint8_t channel_14_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_15_brownout : 1;
+ uint8_t channel_15_breaker_fault : 1;
/**
- * Range: 0..255 (0..15.9375 A)
+ * Range: 0..511 (0..31.9375 A)
* Scale: 0.0625
* Offset: 0
*/
uint8_t channel_20_current : 8;
/**
- * Range: 0..255 (0..15.9375 A)
+ * Range: 0..511 (0..31.9375 A)
* Scale: 0.0625
* Offset: 0
*/
@@ -431,66 +415,66 @@
* Scale: 1
* Offset: 0
*/
- uint8_t channel_16_brownout : 1;
+ uint8_t channel_16_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_17_brownout : 1;
+ uint8_t channel_17_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_18_brownout : 1;
+ uint8_t channel_18_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_19_brownout : 1;
+ uint8_t channel_19_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_20_brownout : 1;
+ uint8_t channel_20_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_21_brownout : 1;
+ uint8_t channel_21_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_22_brownout : 1;
+ uint8_t channel_22_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel_23_brownout : 1;
+ uint8_t channel_23_breaker_fault : 1;
};
/**
- * Signals in message Status4.
+ * Signals in message Status_4.
*
* Periodic status frame 4
*
* All signal values are as on the CAN bus.
*/
-struct PDH_status4_t {
+struct PDH_status_4_t {
/**
* Range: 0..4095 (0..31.9921875 V)
* Scale: 0.0078125
@@ -517,7 +501,7 @@
* Scale: 1
* Offset: 0
*/
- uint8_t brownout : 1;
+ uint8_t brownout_fault : 1;
/**
* Range: 0..1 (0..1 -)
@@ -531,7 +515,7 @@
* Scale: 1
* Offset: 0
*/
- uint8_t can_warning : 1;
+ uint8_t can_warning_fault : 1;
/**
* Range: 0..1 (0..1 -)
@@ -545,14 +529,14 @@
* Scale: 1
* Offset: 0
*/
- uint8_t sw_state : 1;
+ uint8_t switch_channel_state : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_brownout : 1;
+ uint8_t sticky_brownout_fault : 1;
/**
* Range: 0..1 (0..1 -)
@@ -566,14 +550,14 @@
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_can_warning : 1;
+ uint8_t sticky_can_warning_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_can_bus_off : 1;
+ uint8_t sticky_can_bus_off_fault : 1;
/**
* Range: 0..1 (0..1 -)
@@ -594,35 +578,35 @@
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_ch20_brownout : 1;
+ uint8_t sticky_ch20_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_ch21_brownout : 1;
+ uint8_t sticky_ch21_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_ch22_brownout : 1;
+ uint8_t sticky_ch22_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_ch23_brownout : 1;
+ uint8_t sticky_ch23_breaker_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_has_reset : 1;
+ uint8_t sticky_has_reset_fault : 1;
/**
* Range: 0..255 (0..510 A)
@@ -630,10 +614,150 @@
* Offset: 0
*/
uint8_t total_current : 8;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch0_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch1_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch2_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch3_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch4_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch5_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch6_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch7_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch8_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch9_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch10_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch11_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch12_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch13_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch14_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch15_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch16_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch17_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch18_breaker_fault : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sticky_ch19_breaker_fault : 1;
};
/**
- * Signals in message ClearFaults.
+ * Signals in message Clear_Faults.
*
* Clear sticky faults on the device
*
@@ -647,20 +771,6 @@
};
/**
- * Signals in message Identify.
- *
- * Flash the LED on the device to identify this device
- *
- * All signal values are as on the CAN bus.
- */
-struct PDH_identify_t {
- /**
- * Dummy signal in empty message.
- */
- uint8_t dummy;
-};
-
-/**
* Signals in message Version.
*
* Get the version of the PDH device
@@ -694,55 +804,25 @@
* Scale: 1
* Offset: 0
*/
- uint8_t hardware_code : 8;
+ uint8_t hardware_minor : 8;
/**
- * Range: 0..4294967295 (0..4294967295 -)
+ * Range: 0..255 (0..255 -)
* Scale: 1
* Offset: 0
*/
- uint32_t unique_id : 32;
-};
+ uint8_t hardware_major : 8;
-/**
- * Signals in message ConfigureHRChannel.
- *
- * Configure a periodic high-resolution channel frame to send back data for a particular channel. This can be useful for more detailed diagnostics, or even for current based control or monitoring.
- *
- * All signal values are as on the CAN bus.
- */
-struct PDH_configure_hr_channel_t {
/**
- * Range: 0..23 (0..23 -)
+ * Range: 0..16777215 (0..16777215 -)
* Scale: 1
* Offset: 0
*/
- uint8_t channel : 8;
-
- /**
- * Range: 0..65535 (0..65535 -)
- * Scale: 1
- * Offset: 0
- */
- uint16_t period : 16;
+ uint32_t unique_id : 24;
};
/**
- * Signals in message Enter_Bootloader.
- *
- * Enter the REV bootloader from user application
- *
- * All signal values are as on the CAN bus.
- */
-struct PDH_enter_bootloader_t {
- /**
- * Dummy signal in empty message.
- */
- uint8_t dummy;
-};
-
-/**
- * Pack message SwitchChannelSet.
+ * Pack message Set_Switch_Channel.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -750,13 +830,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PDH_switch_channel_set_pack(
+int PDH_set_switch_channel_pack(
uint8_t *dst_p,
- const struct PDH_switch_channel_set_t *src_p,
+ const struct PDH_set_switch_channel_t *src_p,
size_t size);
/**
- * Unpack message SwitchChannelSet.
+ * Unpack message Set_Switch_Channel.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -764,8 +844,8 @@
*
* @return zero(0) or negative error code.
*/
-int PDH_switch_channel_set_unpack(
- struct PDH_switch_channel_set_t *dst_p,
+int PDH_set_switch_channel_unpack(
+ struct PDH_set_switch_channel_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -776,7 +856,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_switch_channel_set_output_set_value_encode(double value);
+uint8_t PDH_set_switch_channel_output_set_value_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -785,7 +865,7 @@
*
* @return Decoded signal.
*/
-double PDH_switch_channel_set_output_set_value_decode(uint8_t value);
+double PDH_set_switch_channel_output_set_value_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -794,37 +874,10 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_switch_channel_set_output_set_value_is_in_range(uint8_t value);
+bool PDH_set_switch_channel_output_set_value_is_in_range(uint8_t value);
/**
- * Encode given signal by applying scaling and offset.
- *
- * @param[in] value Signal to encode.
- *
- * @return Encoded signal.
- */
-uint8_t PDH_switch_channel_set_use_system_enable_encode(double value);
-
-/**
- * Decode given signal by applying scaling and offset.
- *
- * @param[in] value Signal to decode.
- *
- * @return Decoded signal.
- */
-double PDH_switch_channel_set_use_system_enable_decode(uint8_t value);
-
-/**
- * Check that given signal is in allowed range.
- *
- * @param[in] value Signal to check.
- *
- * @return true if in range, false otherwise.
- */
-bool PDH_switch_channel_set_use_system_enable_is_in_range(uint8_t value);
-
-/**
- * Pack message Status0.
+ * Pack message Status_0.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -832,13 +885,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PDH_status0_pack(
+int PDH_status_0_pack(
uint8_t *dst_p,
- const struct PDH_status0_t *src_p,
+ const struct PDH_status_0_t *src_p,
size_t size);
/**
- * Unpack message Status0.
+ * Unpack message Status_0.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -846,8 +899,8 @@
*
* @return zero(0) or negative error code.
*/
-int PDH_status0_unpack(
- struct PDH_status0_t *dst_p,
+int PDH_status_0_unpack(
+ struct PDH_status_0_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -858,7 +911,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status0_channel_0_current_encode(double value);
+uint16_t PDH_status_0_channel_0_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -867,7 +920,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_0_current_decode(uint16_t value);
+double PDH_status_0_channel_0_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -876,7 +929,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_0_current_is_in_range(uint16_t value);
+bool PDH_status_0_channel_0_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -885,7 +938,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status0_channel_1_current_encode(double value);
+uint16_t PDH_status_0_channel_1_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -894,7 +947,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_1_current_decode(uint16_t value);
+double PDH_status_0_channel_1_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -903,7 +956,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_1_current_is_in_range(uint16_t value);
+bool PDH_status_0_channel_1_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -912,7 +965,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status0_channel_2_current_encode(double value);
+uint16_t PDH_status_0_channel_2_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -921,7 +974,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_2_current_decode(uint16_t value);
+double PDH_status_0_channel_2_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -930,7 +983,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_2_current_is_in_range(uint16_t value);
+bool PDH_status_0_channel_2_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -939,7 +992,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status0_channel_0_brownout_encode(double value);
+uint8_t PDH_status_0_channel_0_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -948,7 +1001,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_0_brownout_decode(uint8_t value);
+double PDH_status_0_channel_0_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -957,7 +1010,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_0_brownout_is_in_range(uint8_t value);
+bool PDH_status_0_channel_0_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -966,7 +1019,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status0_channel_1_brownout_encode(double value);
+uint8_t PDH_status_0_channel_1_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -975,7 +1028,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_1_brownout_decode(uint8_t value);
+double PDH_status_0_channel_1_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -984,7 +1037,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_1_brownout_is_in_range(uint8_t value);
+bool PDH_status_0_channel_1_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -993,7 +1046,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status0_channel_3_current_encode(double value);
+uint16_t PDH_status_0_channel_3_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1002,7 +1055,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_3_current_decode(uint16_t value);
+double PDH_status_0_channel_3_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1011,7 +1064,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_3_current_is_in_range(uint16_t value);
+bool PDH_status_0_channel_3_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1020,7 +1073,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status0_channel_4_current_encode(double value);
+uint16_t PDH_status_0_channel_4_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1029,7 +1082,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_4_current_decode(uint16_t value);
+double PDH_status_0_channel_4_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1038,7 +1091,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_4_current_is_in_range(uint16_t value);
+bool PDH_status_0_channel_4_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1047,7 +1100,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status0_channel_5_current_encode(double value);
+uint16_t PDH_status_0_channel_5_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1056,7 +1109,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_5_current_decode(uint16_t value);
+double PDH_status_0_channel_5_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1065,7 +1118,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_5_current_is_in_range(uint16_t value);
+bool PDH_status_0_channel_5_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1074,7 +1127,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status0_channel_2_brownout_encode(double value);
+uint8_t PDH_status_0_channel_2_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1083,7 +1136,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_2_brownout_decode(uint8_t value);
+double PDH_status_0_channel_2_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1092,7 +1145,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_2_brownout_is_in_range(uint8_t value);
+bool PDH_status_0_channel_2_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1101,7 +1154,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status0_channel_3_brownout_encode(double value);
+uint8_t PDH_status_0_channel_3_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1110,7 +1163,7 @@
*
* @return Decoded signal.
*/
-double PDH_status0_channel_3_brownout_decode(uint8_t value);
+double PDH_status_0_channel_3_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1119,10 +1172,10 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status0_channel_3_brownout_is_in_range(uint8_t value);
+bool PDH_status_0_channel_3_breaker_fault_is_in_range(uint8_t value);
/**
- * Pack message Status1.
+ * Pack message Status_1.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -1130,13 +1183,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PDH_status1_pack(
+int PDH_status_1_pack(
uint8_t *dst_p,
- const struct PDH_status1_t *src_p,
+ const struct PDH_status_1_t *src_p,
size_t size);
/**
- * Unpack message Status1.
+ * Unpack message Status_1.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -1144,8 +1197,8 @@
*
* @return zero(0) or negative error code.
*/
-int PDH_status1_unpack(
- struct PDH_status1_t *dst_p,
+int PDH_status_1_unpack(
+ struct PDH_status_1_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -1156,7 +1209,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status1_channel_6_current_encode(double value);
+uint16_t PDH_status_1_channel_6_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1165,7 +1218,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_6_current_decode(uint16_t value);
+double PDH_status_1_channel_6_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1174,7 +1227,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_6_current_is_in_range(uint16_t value);
+bool PDH_status_1_channel_6_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1183,7 +1236,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status1_channel_7_current_encode(double value);
+uint16_t PDH_status_1_channel_7_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1192,7 +1245,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_7_current_decode(uint16_t value);
+double PDH_status_1_channel_7_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1201,7 +1254,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_7_current_is_in_range(uint16_t value);
+bool PDH_status_1_channel_7_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1210,7 +1263,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status1_channel_8_current_encode(double value);
+uint16_t PDH_status_1_channel_8_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1219,7 +1272,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_8_current_decode(uint16_t value);
+double PDH_status_1_channel_8_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1228,7 +1281,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_8_current_is_in_range(uint16_t value);
+bool PDH_status_1_channel_8_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1237,7 +1290,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status1_channel_4_brownout_encode(double value);
+uint8_t PDH_status_1_channel_4_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1246,7 +1299,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_4_brownout_decode(uint8_t value);
+double PDH_status_1_channel_4_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1255,7 +1308,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_4_brownout_is_in_range(uint8_t value);
+bool PDH_status_1_channel_4_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1264,7 +1317,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status1_channel_5_brownout_encode(double value);
+uint8_t PDH_status_1_channel_5_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1273,7 +1326,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_5_brownout_decode(uint8_t value);
+double PDH_status_1_channel_5_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1282,7 +1335,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_5_brownout_is_in_range(uint8_t value);
+bool PDH_status_1_channel_5_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1291,7 +1344,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status1_channel_9_current_encode(double value);
+uint16_t PDH_status_1_channel_9_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1300,7 +1353,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_9_current_decode(uint16_t value);
+double PDH_status_1_channel_9_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1309,7 +1362,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_9_current_is_in_range(uint16_t value);
+bool PDH_status_1_channel_9_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1318,7 +1371,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status1_channel_10_current_encode(double value);
+uint16_t PDH_status_1_channel_10_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1327,7 +1380,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_10_current_decode(uint16_t value);
+double PDH_status_1_channel_10_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1336,7 +1389,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_10_current_is_in_range(uint16_t value);
+bool PDH_status_1_channel_10_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1345,7 +1398,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status1_channel_11_current_encode(double value);
+uint16_t PDH_status_1_channel_11_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1354,7 +1407,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_11_current_decode(uint16_t value);
+double PDH_status_1_channel_11_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1363,7 +1416,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_11_current_is_in_range(uint16_t value);
+bool PDH_status_1_channel_11_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1372,7 +1425,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status1_channel_6_brownout_encode(double value);
+uint8_t PDH_status_1_channel_6_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1381,7 +1434,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_6_brownout_decode(uint8_t value);
+double PDH_status_1_channel_6_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1390,7 +1443,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_6_brownout_is_in_range(uint8_t value);
+bool PDH_status_1_channel_6_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1399,7 +1452,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status1_channel_7_brownout_encode(double value);
+uint8_t PDH_status_1_channel_7_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1408,7 +1461,7 @@
*
* @return Decoded signal.
*/
-double PDH_status1_channel_7_brownout_decode(uint8_t value);
+double PDH_status_1_channel_7_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1417,10 +1470,10 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status1_channel_7_brownout_is_in_range(uint8_t value);
+bool PDH_status_1_channel_7_breaker_fault_is_in_range(uint8_t value);
/**
- * Pack message Status2.
+ * Pack message Status_2.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -1428,13 +1481,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PDH_status2_pack(
+int PDH_status_2_pack(
uint8_t *dst_p,
- const struct PDH_status2_t *src_p,
+ const struct PDH_status_2_t *src_p,
size_t size);
/**
- * Unpack message Status2.
+ * Unpack message Status_2.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -1442,8 +1495,8 @@
*
* @return zero(0) or negative error code.
*/
-int PDH_status2_unpack(
- struct PDH_status2_t *dst_p,
+int PDH_status_2_unpack(
+ struct PDH_status_2_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -1454,7 +1507,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status2_channel_12_current_encode(double value);
+uint16_t PDH_status_2_channel_12_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1463,7 +1516,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_12_current_decode(uint16_t value);
+double PDH_status_2_channel_12_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1472,7 +1525,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_12_current_is_in_range(uint16_t value);
+bool PDH_status_2_channel_12_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1481,7 +1534,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status2_channel_13_current_encode(double value);
+uint16_t PDH_status_2_channel_13_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1490,7 +1543,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_13_current_decode(uint16_t value);
+double PDH_status_2_channel_13_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1499,7 +1552,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_13_current_is_in_range(uint16_t value);
+bool PDH_status_2_channel_13_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1508,7 +1561,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status2_channel_14_current_encode(double value);
+uint16_t PDH_status_2_channel_14_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1517,7 +1570,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_14_current_decode(uint16_t value);
+double PDH_status_2_channel_14_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1526,7 +1579,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_14_current_is_in_range(uint16_t value);
+bool PDH_status_2_channel_14_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1535,7 +1588,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status2_channel_8_brownout_encode(double value);
+uint8_t PDH_status_2_channel_8_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1544,7 +1597,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_8_brownout_decode(uint8_t value);
+double PDH_status_2_channel_8_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1553,7 +1606,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_8_brownout_is_in_range(uint8_t value);
+bool PDH_status_2_channel_8_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1562,7 +1615,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status2_channel_9_brownout_encode(double value);
+uint8_t PDH_status_2_channel_9_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1571,7 +1624,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_9_brownout_decode(uint8_t value);
+double PDH_status_2_channel_9_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1580,7 +1633,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_9_brownout_is_in_range(uint8_t value);
+bool PDH_status_2_channel_9_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1589,7 +1642,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status2_channel_15_current_encode(double value);
+uint16_t PDH_status_2_channel_15_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1598,7 +1651,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_15_current_decode(uint16_t value);
+double PDH_status_2_channel_15_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1607,7 +1660,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_15_current_is_in_range(uint16_t value);
+bool PDH_status_2_channel_15_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1616,7 +1669,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status2_channel_16_current_encode(double value);
+uint16_t PDH_status_2_channel_16_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1625,7 +1678,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_16_current_decode(uint16_t value);
+double PDH_status_2_channel_16_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1634,7 +1687,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_16_current_is_in_range(uint16_t value);
+bool PDH_status_2_channel_16_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1643,7 +1696,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status2_channel_17_current_encode(double value);
+uint16_t PDH_status_2_channel_17_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1652,7 +1705,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_17_current_decode(uint16_t value);
+double PDH_status_2_channel_17_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1661,7 +1714,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_17_current_is_in_range(uint16_t value);
+bool PDH_status_2_channel_17_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1670,7 +1723,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status2_channel_10_brownout_encode(double value);
+uint8_t PDH_status_2_channel_10_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1679,7 +1732,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_10_brownout_decode(uint8_t value);
+double PDH_status_2_channel_10_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1688,7 +1741,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_10_brownout_is_in_range(uint8_t value);
+bool PDH_status_2_channel_10_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1697,7 +1750,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status2_channel_11_brownout_encode(double value);
+uint8_t PDH_status_2_channel_11_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1706,7 +1759,7 @@
*
* @return Decoded signal.
*/
-double PDH_status2_channel_11_brownout_decode(uint8_t value);
+double PDH_status_2_channel_11_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1715,10 +1768,10 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status2_channel_11_brownout_is_in_range(uint8_t value);
+bool PDH_status_2_channel_11_breaker_fault_is_in_range(uint8_t value);
/**
- * Pack message Status3.
+ * Pack message Status_3.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -1726,13 +1779,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PDH_status3_pack(
+int PDH_status_3_pack(
uint8_t *dst_p,
- const struct PDH_status3_t *src_p,
+ const struct PDH_status_3_t *src_p,
size_t size);
/**
- * Unpack message Status3.
+ * Unpack message Status_3.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -1740,8 +1793,8 @@
*
* @return zero(0) or negative error code.
*/
-int PDH_status3_unpack(
- struct PDH_status3_t *dst_p,
+int PDH_status_3_unpack(
+ struct PDH_status_3_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -1752,7 +1805,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status3_channel_18_current_encode(double value);
+uint16_t PDH_status_3_channel_18_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1761,7 +1814,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_18_current_decode(uint16_t value);
+double PDH_status_3_channel_18_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1770,7 +1823,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_18_current_is_in_range(uint16_t value);
+bool PDH_status_3_channel_18_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1779,7 +1832,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status3_channel_19_current_encode(double value);
+uint16_t PDH_status_3_channel_19_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1788,7 +1841,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_19_current_decode(uint16_t value);
+double PDH_status_3_channel_19_current_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -1797,7 +1850,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_19_current_is_in_range(uint16_t value);
+bool PDH_status_3_channel_19_current_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1806,7 +1859,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_12_brownout_encode(double value);
+uint8_t PDH_status_3_channel_12_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1815,7 +1868,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_12_brownout_decode(uint8_t value);
+double PDH_status_3_channel_12_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1824,7 +1877,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_12_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_12_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1833,7 +1886,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_13_brownout_encode(double value);
+uint8_t PDH_status_3_channel_13_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1842,7 +1895,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_13_brownout_decode(uint8_t value);
+double PDH_status_3_channel_13_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1851,7 +1904,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_13_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_13_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1860,7 +1913,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_14_brownout_encode(double value);
+uint8_t PDH_status_3_channel_14_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1869,7 +1922,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_14_brownout_decode(uint8_t value);
+double PDH_status_3_channel_14_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1878,7 +1931,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_14_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_14_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1887,7 +1940,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_15_brownout_encode(double value);
+uint8_t PDH_status_3_channel_15_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1896,7 +1949,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_15_brownout_decode(uint8_t value);
+double PDH_status_3_channel_15_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1905,7 +1958,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_15_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_15_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1914,7 +1967,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_20_current_encode(double value);
+uint8_t PDH_status_3_channel_20_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1923,7 +1976,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_20_current_decode(uint8_t value);
+double PDH_status_3_channel_20_current_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1932,7 +1985,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_20_current_is_in_range(uint8_t value);
+bool PDH_status_3_channel_20_current_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1941,7 +1994,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_21_current_encode(double value);
+uint8_t PDH_status_3_channel_21_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1950,7 +2003,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_21_current_decode(uint8_t value);
+double PDH_status_3_channel_21_current_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1959,7 +2012,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_21_current_is_in_range(uint8_t value);
+bool PDH_status_3_channel_21_current_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1968,7 +2021,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_22_current_encode(double value);
+uint8_t PDH_status_3_channel_22_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1977,7 +2030,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_22_current_decode(uint8_t value);
+double PDH_status_3_channel_22_current_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1986,7 +2039,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_22_current_is_in_range(uint8_t value);
+bool PDH_status_3_channel_22_current_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1995,7 +2048,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_23_current_encode(double value);
+uint8_t PDH_status_3_channel_23_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2004,7 +2057,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_23_current_decode(uint8_t value);
+double PDH_status_3_channel_23_current_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2013,7 +2066,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_23_current_is_in_range(uint8_t value);
+bool PDH_status_3_channel_23_current_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2022,7 +2075,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_16_brownout_encode(double value);
+uint8_t PDH_status_3_channel_16_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2031,7 +2084,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_16_brownout_decode(uint8_t value);
+double PDH_status_3_channel_16_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2040,7 +2093,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_16_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_16_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2049,7 +2102,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_17_brownout_encode(double value);
+uint8_t PDH_status_3_channel_17_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2058,7 +2111,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_17_brownout_decode(uint8_t value);
+double PDH_status_3_channel_17_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2067,7 +2120,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_17_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_17_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2076,7 +2129,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_18_brownout_encode(double value);
+uint8_t PDH_status_3_channel_18_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2085,7 +2138,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_18_brownout_decode(uint8_t value);
+double PDH_status_3_channel_18_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2094,7 +2147,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_18_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_18_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2103,7 +2156,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_19_brownout_encode(double value);
+uint8_t PDH_status_3_channel_19_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2112,7 +2165,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_19_brownout_decode(uint8_t value);
+double PDH_status_3_channel_19_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2121,7 +2174,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_19_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_19_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2130,7 +2183,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_20_brownout_encode(double value);
+uint8_t PDH_status_3_channel_20_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2139,7 +2192,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_20_brownout_decode(uint8_t value);
+double PDH_status_3_channel_20_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2148,7 +2201,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_20_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_20_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2157,7 +2210,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_21_brownout_encode(double value);
+uint8_t PDH_status_3_channel_21_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2166,7 +2219,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_21_brownout_decode(uint8_t value);
+double PDH_status_3_channel_21_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2175,7 +2228,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_21_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_21_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2184,7 +2237,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_22_brownout_encode(double value);
+uint8_t PDH_status_3_channel_22_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2193,7 +2246,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_22_brownout_decode(uint8_t value);
+double PDH_status_3_channel_22_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2202,7 +2255,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_22_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_22_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2211,7 +2264,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status3_channel_23_brownout_encode(double value);
+uint8_t PDH_status_3_channel_23_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2220,7 +2273,7 @@
*
* @return Decoded signal.
*/
-double PDH_status3_channel_23_brownout_decode(uint8_t value);
+double PDH_status_3_channel_23_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2229,10 +2282,10 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status3_channel_23_brownout_is_in_range(uint8_t value);
+bool PDH_status_3_channel_23_breaker_fault_is_in_range(uint8_t value);
/**
- * Pack message Status4.
+ * Pack message Status_4.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -2240,13 +2293,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PDH_status4_pack(
+int PDH_status_4_pack(
uint8_t *dst_p,
- const struct PDH_status4_t *src_p,
+ const struct PDH_status_4_t *src_p,
size_t size);
/**
- * Unpack message Status4.
+ * Unpack message Status_4.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -2254,8 +2307,8 @@
*
* @return zero(0) or negative error code.
*/
-int PDH_status4_unpack(
- struct PDH_status4_t *dst_p,
+int PDH_status_4_unpack(
+ struct PDH_status_4_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -2266,7 +2319,7 @@
*
* @return Encoded signal.
*/
-uint16_t PDH_status4_v_bus_encode(double value);
+uint16_t PDH_status_4_v_bus_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2275,7 +2328,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_v_bus_decode(uint16_t value);
+double PDH_status_4_v_bus_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -2284,7 +2337,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_v_bus_is_in_range(uint16_t value);
+bool PDH_status_4_v_bus_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2293,7 +2346,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_system_enable_encode(double value);
+uint8_t PDH_status_4_system_enable_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2302,7 +2355,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_system_enable_decode(uint8_t value);
+double PDH_status_4_system_enable_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2311,7 +2364,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_system_enable_is_in_range(uint8_t value);
+bool PDH_status_4_system_enable_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2320,7 +2373,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_rsvd0_encode(double value);
+uint8_t PDH_status_4_rsvd0_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2329,7 +2382,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_rsvd0_decode(uint8_t value);
+double PDH_status_4_rsvd0_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2338,7 +2391,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_rsvd0_is_in_range(uint8_t value);
+bool PDH_status_4_rsvd0_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2347,7 +2400,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_brownout_encode(double value);
+uint8_t PDH_status_4_brownout_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2356,7 +2409,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_brownout_decode(uint8_t value);
+double PDH_status_4_brownout_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2365,7 +2418,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_brownout_is_in_range(uint8_t value);
+bool PDH_status_4_brownout_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2374,7 +2427,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_rsvd1_encode(double value);
+uint8_t PDH_status_4_rsvd1_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2383,7 +2436,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_rsvd1_decode(uint8_t value);
+double PDH_status_4_rsvd1_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2392,7 +2445,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_rsvd1_is_in_range(uint8_t value);
+bool PDH_status_4_rsvd1_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2401,7 +2454,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_can_warning_encode(double value);
+uint8_t PDH_status_4_can_warning_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2410,7 +2463,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_can_warning_decode(uint8_t value);
+double PDH_status_4_can_warning_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2419,7 +2472,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_can_warning_is_in_range(uint8_t value);
+bool PDH_status_4_can_warning_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2428,7 +2481,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_hardware_fault_encode(double value);
+uint8_t PDH_status_4_hardware_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2437,7 +2490,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_hardware_fault_decode(uint8_t value);
+double PDH_status_4_hardware_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2446,7 +2499,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_hardware_fault_is_in_range(uint8_t value);
+bool PDH_status_4_hardware_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2455,7 +2508,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sw_state_encode(double value);
+uint8_t PDH_status_4_switch_channel_state_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2464,7 +2517,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sw_state_decode(uint8_t value);
+double PDH_status_4_switch_channel_state_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2473,7 +2526,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sw_state_is_in_range(uint8_t value);
+bool PDH_status_4_switch_channel_state_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2482,7 +2535,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_brownout_encode(double value);
+uint8_t PDH_status_4_sticky_brownout_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2491,7 +2544,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_brownout_decode(uint8_t value);
+double PDH_status_4_sticky_brownout_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2500,7 +2553,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_brownout_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_brownout_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2509,7 +2562,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_rsvd2_encode(double value);
+uint8_t PDH_status_4_rsvd2_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2518,7 +2571,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_rsvd2_decode(uint8_t value);
+double PDH_status_4_rsvd2_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2527,7 +2580,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_rsvd2_is_in_range(uint8_t value);
+bool PDH_status_4_rsvd2_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2536,7 +2589,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_can_warning_encode(double value);
+uint8_t PDH_status_4_sticky_can_warning_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2545,7 +2598,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_can_warning_decode(uint8_t value);
+double PDH_status_4_sticky_can_warning_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2554,7 +2607,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_can_warning_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_can_warning_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2563,7 +2616,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_can_bus_off_encode(double value);
+uint8_t PDH_status_4_sticky_can_bus_off_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2572,7 +2625,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_can_bus_off_decode(uint8_t value);
+double PDH_status_4_sticky_can_bus_off_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2581,7 +2634,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_can_bus_off_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_can_bus_off_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2590,7 +2643,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_hardware_fault_encode(double value);
+uint8_t PDH_status_4_sticky_hardware_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2599,7 +2652,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_hardware_fault_decode(uint8_t value);
+double PDH_status_4_sticky_hardware_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2608,7 +2661,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_hardware_fault_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_hardware_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2617,7 +2670,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_firmware_fault_encode(double value);
+uint8_t PDH_status_4_sticky_firmware_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2626,7 +2679,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_firmware_fault_decode(uint8_t value);
+double PDH_status_4_sticky_firmware_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2635,7 +2688,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_firmware_fault_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_firmware_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2644,7 +2697,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_ch20_brownout_encode(double value);
+uint8_t PDH_status_4_sticky_ch20_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2653,7 +2706,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_ch20_brownout_decode(uint8_t value);
+double PDH_status_4_sticky_ch20_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2662,7 +2715,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_ch20_brownout_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_ch20_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2671,7 +2724,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_ch21_brownout_encode(double value);
+uint8_t PDH_status_4_sticky_ch21_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2680,7 +2733,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_ch21_brownout_decode(uint8_t value);
+double PDH_status_4_sticky_ch21_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2689,7 +2742,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_ch21_brownout_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_ch21_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2698,7 +2751,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_ch22_brownout_encode(double value);
+uint8_t PDH_status_4_sticky_ch22_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2707,7 +2760,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_ch22_brownout_decode(uint8_t value);
+double PDH_status_4_sticky_ch22_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2716,7 +2769,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_ch22_brownout_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_ch22_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2725,7 +2778,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_ch23_brownout_encode(double value);
+uint8_t PDH_status_4_sticky_ch23_breaker_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2734,7 +2787,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_ch23_brownout_decode(uint8_t value);
+double PDH_status_4_sticky_ch23_breaker_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2743,7 +2796,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_ch23_brownout_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_ch23_breaker_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2752,7 +2805,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_sticky_has_reset_encode(double value);
+uint8_t PDH_status_4_sticky_has_reset_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2761,7 +2814,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_sticky_has_reset_decode(uint8_t value);
+double PDH_status_4_sticky_has_reset_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2770,7 +2823,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_sticky_has_reset_is_in_range(uint8_t value);
+bool PDH_status_4_sticky_has_reset_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2779,7 +2832,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_status4_total_current_encode(double value);
+uint8_t PDH_status_4_total_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2788,7 +2841,7 @@
*
* @return Decoded signal.
*/
-double PDH_status4_total_current_decode(uint8_t value);
+double PDH_status_4_total_current_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2797,10 +2850,550 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_status4_total_current_is_in_range(uint8_t value);
+bool PDH_status_4_total_current_is_in_range(uint8_t value);
/**
- * Pack message ClearFaults.
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch0_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch0_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch0_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch1_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch1_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch1_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch2_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch2_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch2_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch3_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch3_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch3_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch4_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch4_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch4_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch5_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch5_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch5_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch6_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch6_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch6_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch7_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch7_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch7_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch8_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch8_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch8_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch9_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch9_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch9_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch10_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch10_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch10_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch11_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch11_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch11_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch12_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch12_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch12_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch13_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch13_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch13_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch14_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch14_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch14_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch15_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch15_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch15_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch16_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch16_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch16_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch17_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch17_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch17_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch18_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch18_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch18_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_status_4_sticky_ch19_breaker_fault_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_status_4_sticky_ch19_breaker_fault_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_status_4_sticky_ch19_breaker_fault_is_in_range(uint8_t value);
+
+/**
+ * Pack message Clear_Faults.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -2814,7 +3407,7 @@
size_t size);
/**
- * Unpack message ClearFaults.
+ * Unpack message Clear_Faults.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -2828,34 +3421,6 @@
size_t size);
/**
- * Pack message Identify.
- *
- * @param[out] dst_p Buffer to pack the message into.
- * @param[in] src_p Data to pack.
- * @param[in] size Size of dst_p.
- *
- * @return Size of packed data, or negative error code.
- */
-int PDH_identify_pack(
- uint8_t *dst_p,
- const struct PDH_identify_t *src_p,
- size_t size);
-
-/**
- * Unpack message Identify.
- *
- * @param[out] dst_p Object to unpack the message into.
- * @param[in] src_p Message to unpack.
- * @param[in] size Size of src_p.
- *
- * @return zero(0) or negative error code.
- */
-int PDH_identify_unpack(
- struct PDH_identify_t *dst_p,
- const uint8_t *src_p,
- size_t size);
-
-/**
* Pack message Version.
*
* @param[out] dst_p Buffer to pack the message into.
@@ -2971,7 +3536,7 @@
*
* @return Encoded signal.
*/
-uint8_t PDH_version_hardware_code_encode(double value);
+uint8_t PDH_version_hardware_minor_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2980,7 +3545,7 @@
*
* @return Decoded signal.
*/
-double PDH_version_hardware_code_decode(uint8_t value);
+double PDH_version_hardware_minor_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2989,7 +3554,34 @@
*
* @return true if in range, false otherwise.
*/
-bool PDH_version_hardware_code_is_in_range(uint8_t value);
+bool PDH_version_hardware_minor_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PDH_version_hardware_major_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PDH_version_hardware_major_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PDH_version_hardware_major_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3018,116 +3610,6 @@
*/
bool PDH_version_unique_id_is_in_range(uint32_t value);
-/**
- * Pack message ConfigureHRChannel.
- *
- * @param[out] dst_p Buffer to pack the message into.
- * @param[in] src_p Data to pack.
- * @param[in] size Size of dst_p.
- *
- * @return Size of packed data, or negative error code.
- */
-int PDH_configure_hr_channel_pack(
- uint8_t *dst_p,
- const struct PDH_configure_hr_channel_t *src_p,
- size_t size);
-
-/**
- * Unpack message ConfigureHRChannel.
- *
- * @param[out] dst_p Object to unpack the message into.
- * @param[in] src_p Message to unpack.
- * @param[in] size Size of src_p.
- *
- * @return zero(0) or negative error code.
- */
-int PDH_configure_hr_channel_unpack(
- struct PDH_configure_hr_channel_t *dst_p,
- const uint8_t *src_p,
- size_t size);
-
-/**
- * Encode given signal by applying scaling and offset.
- *
- * @param[in] value Signal to encode.
- *
- * @return Encoded signal.
- */
-uint8_t PDH_configure_hr_channel_channel_encode(double value);
-
-/**
- * Decode given signal by applying scaling and offset.
- *
- * @param[in] value Signal to decode.
- *
- * @return Decoded signal.
- */
-double PDH_configure_hr_channel_channel_decode(uint8_t value);
-
-/**
- * Check that given signal is in allowed range.
- *
- * @param[in] value Signal to check.
- *
- * @return true if in range, false otherwise.
- */
-bool PDH_configure_hr_channel_channel_is_in_range(uint8_t value);
-
-/**
- * Encode given signal by applying scaling and offset.
- *
- * @param[in] value Signal to encode.
- *
- * @return Encoded signal.
- */
-uint16_t PDH_configure_hr_channel_period_encode(double value);
-
-/**
- * Decode given signal by applying scaling and offset.
- *
- * @param[in] value Signal to decode.
- *
- * @return Decoded signal.
- */
-double PDH_configure_hr_channel_period_decode(uint16_t value);
-
-/**
- * Check that given signal is in allowed range.
- *
- * @param[in] value Signal to check.
- *
- * @return true if in range, false otherwise.
- */
-bool PDH_configure_hr_channel_period_is_in_range(uint16_t value);
-
-/**
- * Pack message Enter_Bootloader.
- *
- * @param[out] dst_p Buffer to pack the message into.
- * @param[in] src_p Data to pack.
- * @param[in] size Size of dst_p.
- *
- * @return Size of packed data, or negative error code.
- */
-int PDH_enter_bootloader_pack(
- uint8_t *dst_p,
- const struct PDH_enter_bootloader_t *src_p,
- size_t size);
-
-/**
- * Unpack message Enter_Bootloader.
- *
- * @param[out] dst_p Object to unpack the message into.
- * @param[in] src_p Message to unpack.
- * @param[in] size Size of src_p.
- *
- * @return zero(0) or negative error code.
- */
-int PDH_enter_bootloader_unpack(
- struct PDH_enter_bootloader_t *dst_p,
- const uint8_t *src_p,
- size_t size);
-
#ifdef __cplusplus
}
diff --git a/hal/src/main/native/athena/rev/PHFrames.cpp b/hal/src/main/native/athena/rev/PHFrames.cpp
index e7f77e0..d098c00 100644
--- a/hal/src/main/native/athena/rev/PHFrames.cpp
+++ b/hal/src/main/native/athena/rev/PHFrames.cpp
@@ -48,6 +48,14 @@
return (uint8_t)((uint8_t)(value << shift) & mask);
}
+static inline uint8_t pack_left_shift_u32(
+ uint32_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value << shift) & mask);
+}
+
static inline uint8_t pack_right_shift_u16(
uint16_t value,
uint8_t shift,
@@ -56,6 +64,14 @@
return (uint8_t)((uint8_t)(value >> shift) & mask);
}
+static inline uint8_t pack_right_shift_u32(
+ uint32_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value >> shift) & mask);
+}
+
static inline uint16_t unpack_left_shift_u16(
uint8_t value,
uint8_t shift,
@@ -64,6 +80,14 @@
return (uint16_t)((uint16_t)(value & mask) << shift);
}
+static inline uint32_t unpack_left_shift_u32(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint32_t)((uint32_t)(value & mask) << shift);
+}
+
static inline uint8_t unpack_right_shift_u8(
uint8_t value,
uint8_t shift,
@@ -80,6 +104,114 @@
return (uint16_t)((uint16_t)(value & mask) >> shift);
}
+static inline uint32_t unpack_right_shift_u32(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint32_t)((uint32_t)(value & mask) >> shift);
+}
+
+int PH_compressor_config_pack(
+ uint8_t *dst_p,
+ const struct PH_compressor_config_t *src_p,
+ size_t size)
+{
+ if (size < 5u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 5);
+
+ dst_p[0] |= pack_left_shift_u16(src_p->minimum_tank_pressure, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(src_p->minimum_tank_pressure, 8u, 0xffu);
+ dst_p[2] |= pack_left_shift_u16(src_p->maximum_tank_pressure, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(src_p->maximum_tank_pressure, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->force_disable, 0u, 0x01u);
+ dst_p[4] |= pack_left_shift_u8(src_p->use_digital, 1u, 0x02u);
+
+ return (5);
+}
+
+int PH_compressor_config_unpack(
+ struct PH_compressor_config_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 5u) {
+ return (-EINVAL);
+ }
+
+ dst_p->minimum_tank_pressure = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ dst_p->minimum_tank_pressure |= unpack_left_shift_u16(src_p[1], 8u, 0xffu);
+ dst_p->maximum_tank_pressure = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ dst_p->maximum_tank_pressure |= unpack_left_shift_u16(src_p[3], 8u, 0xffu);
+ dst_p->force_disable = unpack_right_shift_u8(src_p[4], 0u, 0x01u);
+ dst_p->use_digital = unpack_right_shift_u8(src_p[4], 1u, 0x02u);
+
+ return (0);
+}
+
+uint16_t PH_compressor_config_minimum_tank_pressure_encode(double value)
+{
+ return (uint16_t)(value / 0.001);
+}
+
+double PH_compressor_config_minimum_tank_pressure_decode(uint16_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool PH_compressor_config_minimum_tank_pressure_is_in_range(uint16_t value)
+{
+ return (value <= 5000u);
+}
+
+uint16_t PH_compressor_config_maximum_tank_pressure_encode(double value)
+{
+ return (uint16_t)(value / 0.001);
+}
+
+double PH_compressor_config_maximum_tank_pressure_decode(uint16_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool PH_compressor_config_maximum_tank_pressure_is_in_range(uint16_t value)
+{
+ return (value <= 5000u);
+}
+
+uint8_t PH_compressor_config_force_disable_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_compressor_config_force_disable_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_compressor_config_force_disable_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PH_compressor_config_use_digital_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_compressor_config_use_digital_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_compressor_config_use_digital_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
int PH_set_all_pack(
uint8_t *dst_p,
const struct PH_set_all_t *src_p,
@@ -701,9 +833,9 @@
return (true);
}
-int PH_status0_pack(
+int PH_status_0_pack(
uint8_t *dst_p,
- const struct PH_status0_t *src_p,
+ const struct PH_status_0_t *src_p,
size_t size)
{
if (size < 8u) {
@@ -731,11 +863,11 @@
dst_p[2] |= pack_left_shift_u8(src_p->analog_0, 0u, 0xffu);
dst_p[3] |= pack_left_shift_u8(src_p->analog_1, 0u, 0xffu);
dst_p[4] |= pack_left_shift_u8(src_p->digital_sensor, 0u, 0x01u);
- dst_p[4] |= pack_left_shift_u8(src_p->brownout, 1u, 0x02u);
- dst_p[4] |= pack_left_shift_u8(src_p->compressor_oc, 2u, 0x04u);
- dst_p[4] |= pack_left_shift_u8(src_p->compressor_open, 3u, 0x08u);
- dst_p[4] |= pack_left_shift_u8(src_p->solenoid_oc, 4u, 0x10u);
- dst_p[4] |= pack_left_shift_u8(src_p->can_warning, 5u, 0x20u);
+ dst_p[4] |= pack_left_shift_u8(src_p->brownout_fault, 1u, 0x02u);
+ dst_p[4] |= pack_left_shift_u8(src_p->compressor_oc_fault, 2u, 0x04u);
+ dst_p[4] |= pack_left_shift_u8(src_p->compressor_open_fault, 3u, 0x08u);
+ dst_p[4] |= pack_left_shift_u8(src_p->solenoid_oc_fault, 4u, 0x10u);
+ dst_p[4] |= pack_left_shift_u8(src_p->can_warning_fault, 5u, 0x20u);
dst_p[4] |= pack_left_shift_u8(src_p->hardware_fault, 6u, 0x40u);
dst_p[5] |= pack_left_shift_u8(src_p->channel_0_fault, 0u, 0x01u);
dst_p[5] |= pack_left_shift_u8(src_p->channel_1_fault, 1u, 0x02u);
@@ -755,12 +887,14 @@
dst_p[6] |= pack_left_shift_u8(src_p->channel_15_fault, 7u, 0x80u);
dst_p[7] |= pack_left_shift_u8(src_p->compressor_on, 0u, 0x01u);
dst_p[7] |= pack_left_shift_u8(src_p->system_enabled, 1u, 0x02u);
+ dst_p[7] |= pack_left_shift_u8(src_p->robo_rio_present, 2u, 0x04u);
+ dst_p[7] |= pack_left_shift_u8(src_p->compressor_config, 3u, 0x18u);
return (8);
}
-int PH_status0_unpack(
- struct PH_status0_t *dst_p,
+int PH_status_0_unpack(
+ struct PH_status_0_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -787,11 +921,11 @@
dst_p->analog_0 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
dst_p->analog_1 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
dst_p->digital_sensor = unpack_right_shift_u8(src_p[4], 0u, 0x01u);
- dst_p->brownout = unpack_right_shift_u8(src_p[4], 1u, 0x02u);
- dst_p->compressor_oc = unpack_right_shift_u8(src_p[4], 2u, 0x04u);
- dst_p->compressor_open = unpack_right_shift_u8(src_p[4], 3u, 0x08u);
- dst_p->solenoid_oc = unpack_right_shift_u8(src_p[4], 4u, 0x10u);
- dst_p->can_warning = unpack_right_shift_u8(src_p[4], 5u, 0x20u);
+ dst_p->brownout_fault = unpack_right_shift_u8(src_p[4], 1u, 0x02u);
+ dst_p->compressor_oc_fault = unpack_right_shift_u8(src_p[4], 2u, 0x04u);
+ dst_p->compressor_open_fault = unpack_right_shift_u8(src_p[4], 3u, 0x08u);
+ dst_p->solenoid_oc_fault = unpack_right_shift_u8(src_p[4], 4u, 0x10u);
+ dst_p->can_warning_fault = unpack_right_shift_u8(src_p[4], 5u, 0x20u);
dst_p->hardware_fault = unpack_right_shift_u8(src_p[4], 6u, 0x40u);
dst_p->channel_0_fault = unpack_right_shift_u8(src_p[5], 0u, 0x01u);
dst_p->channel_1_fault = unpack_right_shift_u8(src_p[5], 1u, 0x02u);
@@ -811,662 +945,694 @@
dst_p->channel_15_fault = unpack_right_shift_u8(src_p[6], 7u, 0x80u);
dst_p->compressor_on = unpack_right_shift_u8(src_p[7], 0u, 0x01u);
dst_p->system_enabled = unpack_right_shift_u8(src_p[7], 1u, 0x02u);
+ dst_p->robo_rio_present = unpack_right_shift_u8(src_p[7], 2u, 0x04u);
+ dst_p->compressor_config = unpack_right_shift_u8(src_p[7], 3u, 0x18u);
return (0);
}
-uint8_t PH_status0_channel_0_encode(double value)
+uint8_t PH_status_0_channel_0_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_0_decode(uint8_t value)
+double PH_status_0_channel_0_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_0_is_in_range(uint8_t value)
+bool PH_status_0_channel_0_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_1_encode(double value)
+uint8_t PH_status_0_channel_1_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_1_decode(uint8_t value)
+double PH_status_0_channel_1_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_1_is_in_range(uint8_t value)
+bool PH_status_0_channel_1_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_2_encode(double value)
+uint8_t PH_status_0_channel_2_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_2_decode(uint8_t value)
+double PH_status_0_channel_2_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_2_is_in_range(uint8_t value)
+bool PH_status_0_channel_2_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_3_encode(double value)
+uint8_t PH_status_0_channel_3_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_3_decode(uint8_t value)
+double PH_status_0_channel_3_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_3_is_in_range(uint8_t value)
+bool PH_status_0_channel_3_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_4_encode(double value)
+uint8_t PH_status_0_channel_4_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_4_decode(uint8_t value)
+double PH_status_0_channel_4_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_4_is_in_range(uint8_t value)
+bool PH_status_0_channel_4_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_5_encode(double value)
+uint8_t PH_status_0_channel_5_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_5_decode(uint8_t value)
+double PH_status_0_channel_5_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_5_is_in_range(uint8_t value)
+bool PH_status_0_channel_5_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_6_encode(double value)
+uint8_t PH_status_0_channel_6_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_6_decode(uint8_t value)
+double PH_status_0_channel_6_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_6_is_in_range(uint8_t value)
+bool PH_status_0_channel_6_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_7_encode(double value)
+uint8_t PH_status_0_channel_7_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_7_decode(uint8_t value)
+double PH_status_0_channel_7_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_7_is_in_range(uint8_t value)
+bool PH_status_0_channel_7_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_8_encode(double value)
+uint8_t PH_status_0_channel_8_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_8_decode(uint8_t value)
+double PH_status_0_channel_8_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_8_is_in_range(uint8_t value)
+bool PH_status_0_channel_8_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_9_encode(double value)
+uint8_t PH_status_0_channel_9_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_9_decode(uint8_t value)
+double PH_status_0_channel_9_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_9_is_in_range(uint8_t value)
+bool PH_status_0_channel_9_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_10_encode(double value)
+uint8_t PH_status_0_channel_10_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_10_decode(uint8_t value)
+double PH_status_0_channel_10_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_10_is_in_range(uint8_t value)
+bool PH_status_0_channel_10_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_11_encode(double value)
+uint8_t PH_status_0_channel_11_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_11_decode(uint8_t value)
+double PH_status_0_channel_11_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_11_is_in_range(uint8_t value)
+bool PH_status_0_channel_11_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_12_encode(double value)
+uint8_t PH_status_0_channel_12_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_12_decode(uint8_t value)
+double PH_status_0_channel_12_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_12_is_in_range(uint8_t value)
+bool PH_status_0_channel_12_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_13_encode(double value)
+uint8_t PH_status_0_channel_13_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_13_decode(uint8_t value)
+double PH_status_0_channel_13_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_13_is_in_range(uint8_t value)
+bool PH_status_0_channel_13_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_14_encode(double value)
+uint8_t PH_status_0_channel_14_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_14_decode(uint8_t value)
+double PH_status_0_channel_14_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_14_is_in_range(uint8_t value)
+bool PH_status_0_channel_14_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_15_encode(double value)
+uint8_t PH_status_0_channel_15_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_15_decode(uint8_t value)
+double PH_status_0_channel_15_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_15_is_in_range(uint8_t value)
+bool PH_status_0_channel_15_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_analog_0_encode(double value)
+uint8_t PH_status_0_analog_0_encode(double value)
{
return (uint8_t)(value / 0.01961);
}
-double PH_status0_analog_0_decode(uint8_t value)
+double PH_status_0_analog_0_decode(uint8_t value)
{
return ((double)value * 0.01961);
}
-bool PH_status0_analog_0_is_in_range(uint8_t value)
+bool PH_status_0_analog_0_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PH_status0_analog_1_encode(double value)
+uint8_t PH_status_0_analog_1_encode(double value)
{
return (uint8_t)(value / 0.01961);
}
-double PH_status0_analog_1_decode(uint8_t value)
+double PH_status_0_analog_1_decode(uint8_t value)
{
return ((double)value * 0.01961);
}
-bool PH_status0_analog_1_is_in_range(uint8_t value)
+bool PH_status_0_analog_1_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PH_status0_digital_sensor_encode(double value)
+uint8_t PH_status_0_digital_sensor_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_digital_sensor_decode(uint8_t value)
+double PH_status_0_digital_sensor_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_digital_sensor_is_in_range(uint8_t value)
+bool PH_status_0_digital_sensor_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_brownout_encode(double value)
+uint8_t PH_status_0_brownout_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_brownout_decode(uint8_t value)
+double PH_status_0_brownout_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_brownout_is_in_range(uint8_t value)
+bool PH_status_0_brownout_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_compressor_oc_encode(double value)
+uint8_t PH_status_0_compressor_oc_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_compressor_oc_decode(uint8_t value)
+double PH_status_0_compressor_oc_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_compressor_oc_is_in_range(uint8_t value)
+bool PH_status_0_compressor_oc_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_compressor_open_encode(double value)
+uint8_t PH_status_0_compressor_open_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_compressor_open_decode(uint8_t value)
+double PH_status_0_compressor_open_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_compressor_open_is_in_range(uint8_t value)
+bool PH_status_0_compressor_open_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_solenoid_oc_encode(double value)
+uint8_t PH_status_0_solenoid_oc_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_solenoid_oc_decode(uint8_t value)
+double PH_status_0_solenoid_oc_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_solenoid_oc_is_in_range(uint8_t value)
+bool PH_status_0_solenoid_oc_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_can_warning_encode(double value)
+uint8_t PH_status_0_can_warning_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_can_warning_decode(uint8_t value)
+double PH_status_0_can_warning_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_can_warning_is_in_range(uint8_t value)
+bool PH_status_0_can_warning_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_hardware_fault_encode(double value)
+uint8_t PH_status_0_hardware_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_hardware_fault_decode(uint8_t value)
+double PH_status_0_hardware_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_hardware_fault_is_in_range(uint8_t value)
+bool PH_status_0_hardware_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_0_fault_encode(double value)
+uint8_t PH_status_0_channel_0_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_0_fault_decode(uint8_t value)
+double PH_status_0_channel_0_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_0_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_0_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_1_fault_encode(double value)
+uint8_t PH_status_0_channel_1_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_1_fault_decode(uint8_t value)
+double PH_status_0_channel_1_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_1_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_1_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_2_fault_encode(double value)
+uint8_t PH_status_0_channel_2_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_2_fault_decode(uint8_t value)
+double PH_status_0_channel_2_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_2_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_2_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_3_fault_encode(double value)
+uint8_t PH_status_0_channel_3_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_3_fault_decode(uint8_t value)
+double PH_status_0_channel_3_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_3_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_3_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_4_fault_encode(double value)
+uint8_t PH_status_0_channel_4_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_4_fault_decode(uint8_t value)
+double PH_status_0_channel_4_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_4_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_4_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_5_fault_encode(double value)
+uint8_t PH_status_0_channel_5_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_5_fault_decode(uint8_t value)
+double PH_status_0_channel_5_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_5_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_5_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_6_fault_encode(double value)
+uint8_t PH_status_0_channel_6_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_6_fault_decode(uint8_t value)
+double PH_status_0_channel_6_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_6_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_6_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_7_fault_encode(double value)
+uint8_t PH_status_0_channel_7_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_7_fault_decode(uint8_t value)
+double PH_status_0_channel_7_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_7_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_7_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_8_fault_encode(double value)
+uint8_t PH_status_0_channel_8_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_8_fault_decode(uint8_t value)
+double PH_status_0_channel_8_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_8_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_8_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_9_fault_encode(double value)
+uint8_t PH_status_0_channel_9_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_9_fault_decode(uint8_t value)
+double PH_status_0_channel_9_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_9_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_9_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_10_fault_encode(double value)
+uint8_t PH_status_0_channel_10_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_10_fault_decode(uint8_t value)
+double PH_status_0_channel_10_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_10_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_10_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_11_fault_encode(double value)
+uint8_t PH_status_0_channel_11_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_11_fault_decode(uint8_t value)
+double PH_status_0_channel_11_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_11_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_11_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_12_fault_encode(double value)
+uint8_t PH_status_0_channel_12_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_12_fault_decode(uint8_t value)
+double PH_status_0_channel_12_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_12_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_12_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_13_fault_encode(double value)
+uint8_t PH_status_0_channel_13_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_13_fault_decode(uint8_t value)
+double PH_status_0_channel_13_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_13_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_13_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_14_fault_encode(double value)
+uint8_t PH_status_0_channel_14_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_14_fault_decode(uint8_t value)
+double PH_status_0_channel_14_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_14_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_14_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_channel_15_fault_encode(double value)
+uint8_t PH_status_0_channel_15_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_channel_15_fault_decode(uint8_t value)
+double PH_status_0_channel_15_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_channel_15_fault_is_in_range(uint8_t value)
+bool PH_status_0_channel_15_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_compressor_on_encode(double value)
+uint8_t PH_status_0_compressor_on_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_compressor_on_decode(uint8_t value)
+double PH_status_0_compressor_on_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_compressor_on_is_in_range(uint8_t value)
+bool PH_status_0_compressor_on_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status0_system_enabled_encode(double value)
+uint8_t PH_status_0_system_enabled_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status0_system_enabled_decode(uint8_t value)
+double PH_status_0_system_enabled_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status0_system_enabled_is_in_range(uint8_t value)
+bool PH_status_0_system_enabled_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-int PH_status1_pack(
+uint8_t PH_status_0_robo_rio_present_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_status_0_robo_rio_present_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_status_0_robo_rio_present_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t PH_status_0_compressor_config_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_status_0_compressor_config_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_status_0_compressor_config_is_in_range(uint8_t value)
+{
+ return (value <= 3u);
+}
+
+int PH_status_1_pack(
uint8_t *dst_p,
- const struct PH_status1_t *src_p,
+ const struct PH_status_1_t *src_p,
size_t size)
{
if (size < 8u) {
@@ -1480,21 +1646,22 @@
dst_p[2] |= pack_right_shift_u16(src_p->solenoid_voltage, 8u, 0x0fu);
dst_p[4] |= pack_left_shift_u8(src_p->compressor_current, 0u, 0xffu);
dst_p[5] |= pack_left_shift_u8(src_p->solenoid_current, 0u, 0xffu);
- dst_p[6] |= pack_left_shift_u8(src_p->sticky_brownout, 0u, 0x01u);
- dst_p[6] |= pack_left_shift_u8(src_p->sticky_compressor_over_current, 1u, 0x02u);
- dst_p[6] |= pack_left_shift_u8(src_p->sticky_compressor_not_present, 2u, 0x04u);
- dst_p[6] |= pack_left_shift_u8(src_p->sticky_solenoid_over_current, 3u, 0x08u);
- dst_p[6] |= pack_left_shift_u8(src_p->sticky_can_warning, 4u, 0x10u);
- dst_p[6] |= pack_left_shift_u8(src_p->sticky_can_bus_off, 5u, 0x20u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_brownout_fault, 0u, 0x01u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_compressor_oc_fault, 1u, 0x02u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_compressor_open_fault, 2u, 0x04u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_solenoid_oc_fault, 3u, 0x08u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_can_warning_fault, 4u, 0x10u);
+ dst_p[6] |= pack_left_shift_u8(src_p->sticky_can_bus_off_fault, 5u, 0x20u);
dst_p[6] |= pack_left_shift_u8(src_p->sticky_hardware_fault, 6u, 0x40u);
dst_p[6] |= pack_left_shift_u8(src_p->sticky_firmware_fault, 7u, 0x80u);
- dst_p[7] |= pack_left_shift_u8(src_p->sticky_has_reset, 0u, 0x01u);
+ dst_p[7] |= pack_left_shift_u8(src_p->sticky_has_reset_fault, 0u, 0x01u);
+ dst_p[7] |= pack_left_shift_u8(src_p->supply_voltage_5_v, 1u, 0xfeu);
return (8);
}
-int PH_status1_unpack(
- struct PH_status1_t *dst_p,
+int PH_status_1_unpack(
+ struct PH_status_1_t *dst_p,
const uint8_t *src_p,
size_t size)
{
@@ -1507,214 +1674,398 @@
dst_p->solenoid_voltage |= unpack_left_shift_u16(src_p[2], 8u, 0x0fu);
dst_p->compressor_current = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
dst_p->solenoid_current = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
- dst_p->sticky_brownout = unpack_right_shift_u8(src_p[6], 0u, 0x01u);
- dst_p->sticky_compressor_over_current = unpack_right_shift_u8(src_p[6], 1u, 0x02u);
- dst_p->sticky_compressor_not_present = unpack_right_shift_u8(src_p[6], 2u, 0x04u);
- dst_p->sticky_solenoid_over_current = unpack_right_shift_u8(src_p[6], 3u, 0x08u);
- dst_p->sticky_can_warning = unpack_right_shift_u8(src_p[6], 4u, 0x10u);
- dst_p->sticky_can_bus_off = unpack_right_shift_u8(src_p[6], 5u, 0x20u);
+ dst_p->sticky_brownout_fault = unpack_right_shift_u8(src_p[6], 0u, 0x01u);
+ dst_p->sticky_compressor_oc_fault = unpack_right_shift_u8(src_p[6], 1u, 0x02u);
+ dst_p->sticky_compressor_open_fault = unpack_right_shift_u8(src_p[6], 2u, 0x04u);
+ dst_p->sticky_solenoid_oc_fault = unpack_right_shift_u8(src_p[6], 3u, 0x08u);
+ dst_p->sticky_can_warning_fault = unpack_right_shift_u8(src_p[6], 4u, 0x10u);
+ dst_p->sticky_can_bus_off_fault = unpack_right_shift_u8(src_p[6], 5u, 0x20u);
dst_p->sticky_hardware_fault = unpack_right_shift_u8(src_p[6], 6u, 0x40u);
dst_p->sticky_firmware_fault = unpack_right_shift_u8(src_p[6], 7u, 0x80u);
- dst_p->sticky_has_reset = unpack_right_shift_u8(src_p[7], 0u, 0x01u);
+ dst_p->sticky_has_reset_fault = unpack_right_shift_u8(src_p[7], 0u, 0x01u);
+ dst_p->supply_voltage_5_v = unpack_right_shift_u8(src_p[7], 1u, 0xfeu);
return (0);
}
-uint8_t PH_status1_v_bus_encode(double value)
+uint8_t PH_status_1_v_bus_encode(double value)
{
return (uint8_t)((value - 4.0) / 0.0625);
}
-double PH_status1_v_bus_decode(uint8_t value)
+double PH_status_1_v_bus_decode(uint8_t value)
{
return (((double)value * 0.0625) + 4.0);
}
-bool PH_status1_v_bus_is_in_range(uint8_t value)
+bool PH_status_1_v_bus_is_in_range(uint8_t value)
{
return (value <= 192u);
}
-uint16_t PH_status1_solenoid_voltage_encode(double value)
+uint16_t PH_status_1_solenoid_voltage_encode(double value)
{
return (uint16_t)(value / 0.0078125);
}
-double PH_status1_solenoid_voltage_decode(uint16_t value)
+double PH_status_1_solenoid_voltage_decode(uint16_t value)
{
return ((double)value * 0.0078125);
}
-bool PH_status1_solenoid_voltage_is_in_range(uint16_t value)
+bool PH_status_1_solenoid_voltage_is_in_range(uint16_t value)
{
return (value <= 4096u);
}
-uint8_t PH_status1_compressor_current_encode(double value)
+uint8_t PH_status_1_compressor_current_encode(double value)
{
return (uint8_t)(value / 0.125);
}
-double PH_status1_compressor_current_decode(uint8_t value)
+double PH_status_1_compressor_current_decode(uint8_t value)
{
return ((double)value * 0.125);
}
-bool PH_status1_compressor_current_is_in_range(uint8_t value)
+bool PH_status_1_compressor_current_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PH_status1_solenoid_current_encode(double value)
+uint8_t PH_status_1_solenoid_current_encode(double value)
{
return (uint8_t)(value / 0.125);
}
-double PH_status1_solenoid_current_decode(uint8_t value)
+double PH_status_1_solenoid_current_decode(uint8_t value)
{
return ((double)value * 0.125);
}
-bool PH_status1_solenoid_current_is_in_range(uint8_t value)
+bool PH_status_1_solenoid_current_is_in_range(uint8_t value)
{
(void)value;
return (true);
}
-uint8_t PH_status1_sticky_brownout_encode(double value)
+uint8_t PH_status_1_sticky_brownout_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_brownout_decode(uint8_t value)
+double PH_status_1_sticky_brownout_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_brownout_is_in_range(uint8_t value)
+bool PH_status_1_sticky_brownout_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_compressor_over_current_encode(double value)
+uint8_t PH_status_1_sticky_compressor_oc_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_compressor_over_current_decode(uint8_t value)
+double PH_status_1_sticky_compressor_oc_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_compressor_over_current_is_in_range(uint8_t value)
+bool PH_status_1_sticky_compressor_oc_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_compressor_not_present_encode(double value)
+uint8_t PH_status_1_sticky_compressor_open_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_compressor_not_present_decode(uint8_t value)
+double PH_status_1_sticky_compressor_open_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_compressor_not_present_is_in_range(uint8_t value)
+bool PH_status_1_sticky_compressor_open_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_solenoid_over_current_encode(double value)
+uint8_t PH_status_1_sticky_solenoid_oc_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_solenoid_over_current_decode(uint8_t value)
+double PH_status_1_sticky_solenoid_oc_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_solenoid_over_current_is_in_range(uint8_t value)
+bool PH_status_1_sticky_solenoid_oc_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_can_warning_encode(double value)
+uint8_t PH_status_1_sticky_can_warning_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_can_warning_decode(uint8_t value)
+double PH_status_1_sticky_can_warning_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_can_warning_is_in_range(uint8_t value)
+bool PH_status_1_sticky_can_warning_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_can_bus_off_encode(double value)
+uint8_t PH_status_1_sticky_can_bus_off_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_can_bus_off_decode(uint8_t value)
+double PH_status_1_sticky_can_bus_off_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_can_bus_off_is_in_range(uint8_t value)
+bool PH_status_1_sticky_can_bus_off_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_hardware_fault_encode(double value)
+uint8_t PH_status_1_sticky_hardware_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_hardware_fault_decode(uint8_t value)
+double PH_status_1_sticky_hardware_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_hardware_fault_is_in_range(uint8_t value)
+bool PH_status_1_sticky_hardware_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_firmware_fault_encode(double value)
+uint8_t PH_status_1_sticky_firmware_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_firmware_fault_decode(uint8_t value)
+double PH_status_1_sticky_firmware_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_firmware_fault_is_in_range(uint8_t value)
+bool PH_status_1_sticky_firmware_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
-uint8_t PH_status1_sticky_has_reset_encode(double value)
+uint8_t PH_status_1_sticky_has_reset_fault_encode(double value)
{
return (uint8_t)(value);
}
-double PH_status1_sticky_has_reset_decode(uint8_t value)
+double PH_status_1_sticky_has_reset_fault_decode(uint8_t value)
{
return ((double)value);
}
-bool PH_status1_sticky_has_reset_is_in_range(uint8_t value)
+bool PH_status_1_sticky_has_reset_fault_is_in_range(uint8_t value)
{
return (value <= 1u);
}
+
+uint8_t PH_status_1_supply_voltage_5_v_encode(double value)
+{
+ return (uint8_t)((value - 4.5) / 0.0078125);
+}
+
+double PH_status_1_supply_voltage_5_v_decode(uint8_t value)
+{
+ return (((double)value * 0.0078125) + 4.5);
+}
+
+bool PH_status_1_supply_voltage_5_v_is_in_range(uint8_t value)
+{
+ return (value <= 128u);
+}
+
+int PH_clear_faults_pack(
+ uint8_t *dst_p,
+ const struct PH_clear_faults_t *src_p,
+ size_t size)
+{
+ (void)dst_p;
+ (void)src_p;
+ (void)size;
+
+ return (0);
+}
+
+int PH_clear_faults_unpack(
+ struct PH_clear_faults_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ (void)dst_p;
+ (void)src_p;
+ (void)size;
+
+ return (0);
+}
+
+int PH_version_pack(
+ uint8_t *dst_p,
+ const struct PH_version_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->firmware_fix, 0u, 0xffu);
+ dst_p[1] |= pack_left_shift_u8(src_p->firmware_minor, 0u, 0xffu);
+ dst_p[2] |= pack_left_shift_u8(src_p->firmware_year, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->hardware_minor, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->hardware_major, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->unique_id, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u32(src_p->unique_id, 8u, 0xffu);
+ dst_p[7] |= pack_right_shift_u32(src_p->unique_id, 16u, 0xffu);
+
+ return (8);
+}
+
+int PH_version_unpack(
+ struct PH_version_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->firmware_fix = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->firmware_minor = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->firmware_year = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->hardware_minor = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->hardware_major = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->unique_id = unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+ dst_p->unique_id |= unpack_left_shift_u32(src_p[6], 8u, 0xffu);
+ dst_p->unique_id |= unpack_left_shift_u32(src_p[7], 16u, 0xffu);
+
+ return (0);
+}
+
+uint8_t PH_version_firmware_fix_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_version_firmware_fix_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_version_firmware_fix_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t PH_version_firmware_minor_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_version_firmware_minor_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_version_firmware_minor_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t PH_version_firmware_year_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_version_firmware_year_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_version_firmware_year_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t PH_version_hardware_minor_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_version_hardware_minor_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_version_hardware_minor_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t PH_version_hardware_major_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double PH_version_hardware_major_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool PH_version_hardware_major_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t PH_version_unique_id_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double PH_version_unique_id_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool PH_version_unique_id_is_in_range(uint32_t value)
+{
+ return (value <= 16777215u);
+}
diff --git a/hal/src/main/native/athena/rev/PHFrames.h b/hal/src/main/native/athena/rev/PHFrames.h
index 295be0a..20411a8 100644
--- a/hal/src/main/native/athena/rev/PHFrames.h
+++ b/hal/src/main/native/athena/rev/PHFrames.h
@@ -44,22 +44,31 @@
#endif
/* Frame ids. */
+#define PH_COMPRESSOR_CONFIG_FRAME_ID (0x9050840u)
#define PH_SET_ALL_FRAME_ID (0x9050c00u)
#define PH_PULSE_ONCE_FRAME_ID (0x9050c40u)
-#define PH_STATUS0_FRAME_ID (0x9051800u)
-#define PH_STATUS1_FRAME_ID (0x9051840u)
+#define PH_STATUS_0_FRAME_ID (0x9051800u)
+#define PH_STATUS_1_FRAME_ID (0x9051840u)
+#define PH_CLEAR_FAULTS_FRAME_ID (0x9051b80u)
+#define PH_VERSION_FRAME_ID (0x9052600u)
/* Frame lengths in bytes. */
+#define PH_COMPRESSOR_CONFIG_LENGTH (5u)
#define PH_SET_ALL_LENGTH (4u)
#define PH_PULSE_ONCE_LENGTH (4u)
-#define PH_STATUS0_LENGTH (8u)
-#define PH_STATUS1_LENGTH (8u)
+#define PH_STATUS_0_LENGTH (8u)
+#define PH_STATUS_1_LENGTH (8u)
+#define PH_CLEAR_FAULTS_LENGTH (0u)
+#define PH_VERSION_LENGTH (8u)
/* Extended or standard frame types. */
+#define PH_COMPRESSOR_CONFIG_IS_EXTENDED (1)
#define PH_SET_ALL_IS_EXTENDED (1)
#define PH_PULSE_ONCE_IS_EXTENDED (1)
-#define PH_STATUS0_IS_EXTENDED (1)
-#define PH_STATUS1_IS_EXTENDED (1)
+#define PH_STATUS_0_IS_EXTENDED (1)
+#define PH_STATUS_1_IS_EXTENDED (1)
+#define PH_CLEAR_FAULTS_IS_EXTENDED (1)
+#define PH_VERSION_IS_EXTENDED (1)
/* Frame cycle times in milliseconds. */
@@ -68,7 +77,44 @@
/**
- * Signals in message SetAll.
+ * Signals in message Compressor_Config.
+ *
+ * Configures compressor to use digitial/analog sensors
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct PH_compressor_config_t {
+ /**
+ * Range: 0..5000 (0..5 V)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ uint16_t minimum_tank_pressure : 16;
+
+ /**
+ * Range: 0..5000 (0..5 V)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ uint16_t maximum_tank_pressure : 16;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t force_disable : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t use_digital : 1;
+};
+
+/**
+ * Signals in message Set_All.
*
* Set state of all channels
*
@@ -189,7 +235,7 @@
};
/**
- * Signals in message PulseOnce.
+ * Signals in message Pulse_Once.
*
* Pulse selected channels once
*
@@ -317,13 +363,13 @@
};
/**
- * Signals in message Status0.
+ * Signals in message Status_0.
*
* Periodic status frame 0
*
* All signal values are as on the CAN bus.
*/
-struct PH_status0_t {
+struct PH_status_0_t {
/**
* Range: 0..1 (0..1 -)
* Scale: 1
@@ -462,35 +508,35 @@
* Scale: 1
* Offset: 0
*/
- uint8_t brownout : 1;
+ uint8_t brownout_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t compressor_oc : 1;
+ uint8_t compressor_oc_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t compressor_open : 1;
+ uint8_t compressor_open_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t solenoid_oc : 1;
+ uint8_t solenoid_oc_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t can_warning : 1;
+ uint8_t can_warning_fault : 1;
/**
* Range: 0..1 (0..1 -)
@@ -624,16 +670,30 @@
* Offset: 0
*/
uint8_t system_enabled : 1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t robo_rio_present : 1;
+
+ /**
+ * Range: 0..3 (0..3 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t compressor_config : 2;
};
/**
- * Signals in message Status1.
+ * Signals in message Status_1.
*
* Periodic status frame 1
*
* All signal values are as on the CAN bus.
*/
-struct PH_status1_t {
+struct PH_status_1_t {
/**
* Range: 0..192 (4..16 V)
* Scale: 0.0625
@@ -667,42 +727,42 @@
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_brownout : 1;
+ uint8_t sticky_brownout_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_compressor_over_current : 1;
+ uint8_t sticky_compressor_oc_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_compressor_not_present : 1;
+ uint8_t sticky_compressor_open_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_solenoid_over_current : 1;
+ uint8_t sticky_solenoid_oc_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_can_warning : 1;
+ uint8_t sticky_can_warning_fault : 1;
/**
* Range: 0..1 (0..1 -)
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_can_bus_off : 1;
+ uint8_t sticky_can_bus_off_fault : 1;
/**
* Range: 0..1 (0..1 -)
@@ -723,11 +783,219 @@
* Scale: 1
* Offset: 0
*/
- uint8_t sticky_has_reset : 1;
+ uint8_t sticky_has_reset_fault : 1;
+
+ /**
+ * Range: 0..128 (4.5..5.5 V)
+ * Scale: 0.0078125
+ * Offset: 4.5
+ */
+ uint8_t supply_voltage_5_v : 7;
};
/**
- * Pack message SetAll.
+ * Signals in message Clear_Faults.
+ *
+ * Clear sticky faults on the device
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct PH_clear_faults_t {
+ /**
+ * Dummy signal in empty message.
+ */
+ uint8_t dummy;
+};
+
+/**
+ * Signals in message Version.
+ *
+ * Get the version of the PH
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct PH_version_t {
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t firmware_fix : 8;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t firmware_minor : 8;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t firmware_year : 8;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t hardware_minor : 8;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t hardware_major : 8;
+
+ /**
+ * Range: 0..16777215 (0..16777215 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t unique_id : 24;
+};
+
+/**
+ * Pack message Compressor_Config.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int PH_compressor_config_pack(
+ uint8_t *dst_p,
+ const struct PH_compressor_config_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Compressor_Config.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int PH_compressor_config_unpack(
+ struct PH_compressor_config_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t PH_compressor_config_minimum_tank_pressure_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_compressor_config_minimum_tank_pressure_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_compressor_config_minimum_tank_pressure_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t PH_compressor_config_maximum_tank_pressure_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_compressor_config_maximum_tank_pressure_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_compressor_config_maximum_tank_pressure_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_compressor_config_force_disable_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_compressor_config_force_disable_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_compressor_config_force_disable_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_compressor_config_use_digital_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_compressor_config_use_digital_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_compressor_config_use_digital_is_in_range(uint8_t value);
+
+/**
+ * Pack message Set_All.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -741,7 +1009,7 @@
size_t size);
/**
- * Unpack message SetAll.
+ * Unpack message Set_All.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -1187,7 +1455,7 @@
bool PH_set_all_channel_15_is_in_range(uint8_t value);
/**
- * Pack message PulseOnce.
+ * Pack message Pulse_Once.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -1201,7 +1469,7 @@
size_t size);
/**
- * Unpack message PulseOnce.
+ * Unpack message Pulse_Once.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -1674,7 +1942,7 @@
bool PH_pulse_once_pulse_length_ms_is_in_range(uint16_t value);
/**
- * Pack message Status0.
+ * Pack message Status_0.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -1682,13 +1950,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PH_status0_pack(
+int PH_status_0_pack(
uint8_t *dst_p,
- const struct PH_status0_t *src_p,
+ const struct PH_status_0_t *src_p,
size_t size);
/**
- * Unpack message Status0.
+ * Unpack message Status_0.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -1696,8 +1964,8 @@
*
* @return zero(0) or negative error code.
*/
-int PH_status0_unpack(
- struct PH_status0_t *dst_p,
+int PH_status_0_unpack(
+ struct PH_status_0_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -1708,7 +1976,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_0_encode(double value);
+uint8_t PH_status_0_channel_0_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1717,7 +1985,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_0_decode(uint8_t value);
+double PH_status_0_channel_0_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1726,7 +1994,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_0_is_in_range(uint8_t value);
+bool PH_status_0_channel_0_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1735,7 +2003,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_1_encode(double value);
+uint8_t PH_status_0_channel_1_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1744,7 +2012,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_1_decode(uint8_t value);
+double PH_status_0_channel_1_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1753,7 +2021,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_1_is_in_range(uint8_t value);
+bool PH_status_0_channel_1_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1762,7 +2030,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_2_encode(double value);
+uint8_t PH_status_0_channel_2_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1771,7 +2039,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_2_decode(uint8_t value);
+double PH_status_0_channel_2_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1780,7 +2048,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_2_is_in_range(uint8_t value);
+bool PH_status_0_channel_2_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1789,7 +2057,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_3_encode(double value);
+uint8_t PH_status_0_channel_3_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1798,7 +2066,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_3_decode(uint8_t value);
+double PH_status_0_channel_3_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1807,7 +2075,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_3_is_in_range(uint8_t value);
+bool PH_status_0_channel_3_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1816,7 +2084,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_4_encode(double value);
+uint8_t PH_status_0_channel_4_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1825,7 +2093,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_4_decode(uint8_t value);
+double PH_status_0_channel_4_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1834,7 +2102,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_4_is_in_range(uint8_t value);
+bool PH_status_0_channel_4_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1843,7 +2111,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_5_encode(double value);
+uint8_t PH_status_0_channel_5_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1852,7 +2120,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_5_decode(uint8_t value);
+double PH_status_0_channel_5_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1861,7 +2129,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_5_is_in_range(uint8_t value);
+bool PH_status_0_channel_5_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1870,7 +2138,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_6_encode(double value);
+uint8_t PH_status_0_channel_6_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1879,7 +2147,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_6_decode(uint8_t value);
+double PH_status_0_channel_6_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1888,7 +2156,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_6_is_in_range(uint8_t value);
+bool PH_status_0_channel_6_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1897,7 +2165,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_7_encode(double value);
+uint8_t PH_status_0_channel_7_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1906,7 +2174,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_7_decode(uint8_t value);
+double PH_status_0_channel_7_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1915,7 +2183,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_7_is_in_range(uint8_t value);
+bool PH_status_0_channel_7_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1924,7 +2192,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_8_encode(double value);
+uint8_t PH_status_0_channel_8_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1933,7 +2201,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_8_decode(uint8_t value);
+double PH_status_0_channel_8_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1942,7 +2210,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_8_is_in_range(uint8_t value);
+bool PH_status_0_channel_8_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1951,7 +2219,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_9_encode(double value);
+uint8_t PH_status_0_channel_9_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1960,7 +2228,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_9_decode(uint8_t value);
+double PH_status_0_channel_9_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1969,7 +2237,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_9_is_in_range(uint8_t value);
+bool PH_status_0_channel_9_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -1978,7 +2246,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_10_encode(double value);
+uint8_t PH_status_0_channel_10_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -1987,7 +2255,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_10_decode(uint8_t value);
+double PH_status_0_channel_10_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -1996,7 +2264,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_10_is_in_range(uint8_t value);
+bool PH_status_0_channel_10_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2005,7 +2273,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_11_encode(double value);
+uint8_t PH_status_0_channel_11_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2014,7 +2282,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_11_decode(uint8_t value);
+double PH_status_0_channel_11_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2023,7 +2291,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_11_is_in_range(uint8_t value);
+bool PH_status_0_channel_11_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2032,7 +2300,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_12_encode(double value);
+uint8_t PH_status_0_channel_12_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2041,7 +2309,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_12_decode(uint8_t value);
+double PH_status_0_channel_12_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2050,7 +2318,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_12_is_in_range(uint8_t value);
+bool PH_status_0_channel_12_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2059,7 +2327,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_13_encode(double value);
+uint8_t PH_status_0_channel_13_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2068,7 +2336,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_13_decode(uint8_t value);
+double PH_status_0_channel_13_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2077,7 +2345,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_13_is_in_range(uint8_t value);
+bool PH_status_0_channel_13_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2086,7 +2354,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_14_encode(double value);
+uint8_t PH_status_0_channel_14_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2095,7 +2363,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_14_decode(uint8_t value);
+double PH_status_0_channel_14_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2104,7 +2372,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_14_is_in_range(uint8_t value);
+bool PH_status_0_channel_14_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2113,7 +2381,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_15_encode(double value);
+uint8_t PH_status_0_channel_15_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2122,7 +2390,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_15_decode(uint8_t value);
+double PH_status_0_channel_15_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2131,7 +2399,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_15_is_in_range(uint8_t value);
+bool PH_status_0_channel_15_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2140,7 +2408,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_analog_0_encode(double value);
+uint8_t PH_status_0_analog_0_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2149,7 +2417,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_analog_0_decode(uint8_t value);
+double PH_status_0_analog_0_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2158,7 +2426,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_analog_0_is_in_range(uint8_t value);
+bool PH_status_0_analog_0_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2167,7 +2435,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_analog_1_encode(double value);
+uint8_t PH_status_0_analog_1_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2176,7 +2444,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_analog_1_decode(uint8_t value);
+double PH_status_0_analog_1_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2185,7 +2453,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_analog_1_is_in_range(uint8_t value);
+bool PH_status_0_analog_1_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2194,7 +2462,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_digital_sensor_encode(double value);
+uint8_t PH_status_0_digital_sensor_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2203,7 +2471,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_digital_sensor_decode(uint8_t value);
+double PH_status_0_digital_sensor_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2212,7 +2480,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_digital_sensor_is_in_range(uint8_t value);
+bool PH_status_0_digital_sensor_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2221,7 +2489,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_brownout_encode(double value);
+uint8_t PH_status_0_brownout_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2230,7 +2498,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_brownout_decode(uint8_t value);
+double PH_status_0_brownout_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2239,7 +2507,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_brownout_is_in_range(uint8_t value);
+bool PH_status_0_brownout_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2248,7 +2516,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_compressor_oc_encode(double value);
+uint8_t PH_status_0_compressor_oc_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2257,7 +2525,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_compressor_oc_decode(uint8_t value);
+double PH_status_0_compressor_oc_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2266,7 +2534,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_compressor_oc_is_in_range(uint8_t value);
+bool PH_status_0_compressor_oc_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2275,7 +2543,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_compressor_open_encode(double value);
+uint8_t PH_status_0_compressor_open_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2284,7 +2552,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_compressor_open_decode(uint8_t value);
+double PH_status_0_compressor_open_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2293,7 +2561,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_compressor_open_is_in_range(uint8_t value);
+bool PH_status_0_compressor_open_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2302,7 +2570,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_solenoid_oc_encode(double value);
+uint8_t PH_status_0_solenoid_oc_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2311,7 +2579,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_solenoid_oc_decode(uint8_t value);
+double PH_status_0_solenoid_oc_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2320,7 +2588,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_solenoid_oc_is_in_range(uint8_t value);
+bool PH_status_0_solenoid_oc_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2329,7 +2597,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_can_warning_encode(double value);
+uint8_t PH_status_0_can_warning_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2338,7 +2606,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_can_warning_decode(uint8_t value);
+double PH_status_0_can_warning_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2347,7 +2615,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_can_warning_is_in_range(uint8_t value);
+bool PH_status_0_can_warning_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2356,7 +2624,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_hardware_fault_encode(double value);
+uint8_t PH_status_0_hardware_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2365,7 +2633,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_hardware_fault_decode(uint8_t value);
+double PH_status_0_hardware_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2374,7 +2642,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_hardware_fault_is_in_range(uint8_t value);
+bool PH_status_0_hardware_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2383,7 +2651,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_0_fault_encode(double value);
+uint8_t PH_status_0_channel_0_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2392,7 +2660,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_0_fault_decode(uint8_t value);
+double PH_status_0_channel_0_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2401,7 +2669,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_0_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_0_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2410,7 +2678,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_1_fault_encode(double value);
+uint8_t PH_status_0_channel_1_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2419,7 +2687,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_1_fault_decode(uint8_t value);
+double PH_status_0_channel_1_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2428,7 +2696,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_1_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_1_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2437,7 +2705,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_2_fault_encode(double value);
+uint8_t PH_status_0_channel_2_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2446,7 +2714,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_2_fault_decode(uint8_t value);
+double PH_status_0_channel_2_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2455,7 +2723,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_2_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_2_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2464,7 +2732,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_3_fault_encode(double value);
+uint8_t PH_status_0_channel_3_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2473,7 +2741,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_3_fault_decode(uint8_t value);
+double PH_status_0_channel_3_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2482,7 +2750,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_3_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_3_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2491,7 +2759,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_4_fault_encode(double value);
+uint8_t PH_status_0_channel_4_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2500,7 +2768,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_4_fault_decode(uint8_t value);
+double PH_status_0_channel_4_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2509,7 +2777,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_4_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_4_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2518,7 +2786,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_5_fault_encode(double value);
+uint8_t PH_status_0_channel_5_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2527,7 +2795,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_5_fault_decode(uint8_t value);
+double PH_status_0_channel_5_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2536,7 +2804,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_5_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_5_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2545,7 +2813,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_6_fault_encode(double value);
+uint8_t PH_status_0_channel_6_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2554,7 +2822,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_6_fault_decode(uint8_t value);
+double PH_status_0_channel_6_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2563,7 +2831,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_6_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_6_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2572,7 +2840,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_7_fault_encode(double value);
+uint8_t PH_status_0_channel_7_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2581,7 +2849,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_7_fault_decode(uint8_t value);
+double PH_status_0_channel_7_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2590,7 +2858,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_7_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_7_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2599,7 +2867,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_8_fault_encode(double value);
+uint8_t PH_status_0_channel_8_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2608,7 +2876,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_8_fault_decode(uint8_t value);
+double PH_status_0_channel_8_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2617,7 +2885,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_8_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_8_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2626,7 +2894,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_9_fault_encode(double value);
+uint8_t PH_status_0_channel_9_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2635,7 +2903,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_9_fault_decode(uint8_t value);
+double PH_status_0_channel_9_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2644,7 +2912,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_9_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_9_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2653,7 +2921,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_10_fault_encode(double value);
+uint8_t PH_status_0_channel_10_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2662,7 +2930,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_10_fault_decode(uint8_t value);
+double PH_status_0_channel_10_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2671,7 +2939,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_10_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_10_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2680,7 +2948,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_11_fault_encode(double value);
+uint8_t PH_status_0_channel_11_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2689,7 +2957,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_11_fault_decode(uint8_t value);
+double PH_status_0_channel_11_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2698,7 +2966,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_11_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_11_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2707,7 +2975,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_12_fault_encode(double value);
+uint8_t PH_status_0_channel_12_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2716,7 +2984,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_12_fault_decode(uint8_t value);
+double PH_status_0_channel_12_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2725,7 +2993,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_12_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_12_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2734,7 +3002,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_13_fault_encode(double value);
+uint8_t PH_status_0_channel_13_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2743,7 +3011,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_13_fault_decode(uint8_t value);
+double PH_status_0_channel_13_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2752,7 +3020,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_13_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_13_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2761,7 +3029,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_14_fault_encode(double value);
+uint8_t PH_status_0_channel_14_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2770,7 +3038,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_14_fault_decode(uint8_t value);
+double PH_status_0_channel_14_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2779,7 +3047,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_14_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_14_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2788,7 +3056,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_channel_15_fault_encode(double value);
+uint8_t PH_status_0_channel_15_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2797,7 +3065,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_channel_15_fault_decode(uint8_t value);
+double PH_status_0_channel_15_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2806,7 +3074,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_channel_15_fault_is_in_range(uint8_t value);
+bool PH_status_0_channel_15_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2815,7 +3083,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_compressor_on_encode(double value);
+uint8_t PH_status_0_compressor_on_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2824,7 +3092,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_compressor_on_decode(uint8_t value);
+double PH_status_0_compressor_on_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2833,7 +3101,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_compressor_on_is_in_range(uint8_t value);
+bool PH_status_0_compressor_on_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2842,7 +3110,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status0_system_enabled_encode(double value);
+uint8_t PH_status_0_system_enabled_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2851,7 +3119,7 @@
*
* @return Decoded signal.
*/
-double PH_status0_system_enabled_decode(uint8_t value);
+double PH_status_0_system_enabled_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2860,10 +3128,64 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status0_system_enabled_is_in_range(uint8_t value);
+bool PH_status_0_system_enabled_is_in_range(uint8_t value);
/**
- * Pack message Status1.
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_status_0_robo_rio_present_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_status_0_robo_rio_present_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_status_0_robo_rio_present_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_status_0_compressor_config_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_status_0_compressor_config_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_status_0_compressor_config_is_in_range(uint8_t value);
+
+/**
+ * Pack message Status_1.
*
* @param[out] dst_p Buffer to pack the message into.
* @param[in] src_p Data to pack.
@@ -2871,13 +3193,13 @@
*
* @return Size of packed data, or negative error code.
*/
-int PH_status1_pack(
+int PH_status_1_pack(
uint8_t *dst_p,
- const struct PH_status1_t *src_p,
+ const struct PH_status_1_t *src_p,
size_t size);
/**
- * Unpack message Status1.
+ * Unpack message Status_1.
*
* @param[out] dst_p Object to unpack the message into.
* @param[in] src_p Message to unpack.
@@ -2885,8 +3207,8 @@
*
* @return zero(0) or negative error code.
*/
-int PH_status1_unpack(
- struct PH_status1_t *dst_p,
+int PH_status_1_unpack(
+ struct PH_status_1_t *dst_p,
const uint8_t *src_p,
size_t size);
@@ -2897,7 +3219,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_v_bus_encode(double value);
+uint8_t PH_status_1_v_bus_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2906,7 +3228,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_v_bus_decode(uint8_t value);
+double PH_status_1_v_bus_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2915,7 +3237,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_v_bus_is_in_range(uint8_t value);
+bool PH_status_1_v_bus_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2924,7 +3246,7 @@
*
* @return Encoded signal.
*/
-uint16_t PH_status1_solenoid_voltage_encode(double value);
+uint16_t PH_status_1_solenoid_voltage_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2933,7 +3255,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_solenoid_voltage_decode(uint16_t value);
+double PH_status_1_solenoid_voltage_decode(uint16_t value);
/**
* Check that given signal is in allowed range.
@@ -2942,7 +3264,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_solenoid_voltage_is_in_range(uint16_t value);
+bool PH_status_1_solenoid_voltage_is_in_range(uint16_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2951,7 +3273,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_compressor_current_encode(double value);
+uint8_t PH_status_1_compressor_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2960,7 +3282,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_compressor_current_decode(uint8_t value);
+double PH_status_1_compressor_current_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2969,7 +3291,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_compressor_current_is_in_range(uint8_t value);
+bool PH_status_1_compressor_current_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -2978,7 +3300,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_solenoid_current_encode(double value);
+uint8_t PH_status_1_solenoid_current_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -2987,7 +3309,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_solenoid_current_decode(uint8_t value);
+double PH_status_1_solenoid_current_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -2996,7 +3318,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_solenoid_current_is_in_range(uint8_t value);
+bool PH_status_1_solenoid_current_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3005,7 +3327,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_brownout_encode(double value);
+uint8_t PH_status_1_sticky_brownout_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3014,7 +3336,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_brownout_decode(uint8_t value);
+double PH_status_1_sticky_brownout_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3023,7 +3345,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_brownout_is_in_range(uint8_t value);
+bool PH_status_1_sticky_brownout_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3032,7 +3354,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_compressor_over_current_encode(double value);
+uint8_t PH_status_1_sticky_compressor_oc_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3041,7 +3363,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_compressor_over_current_decode(uint8_t value);
+double PH_status_1_sticky_compressor_oc_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3050,7 +3372,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_compressor_over_current_is_in_range(uint8_t value);
+bool PH_status_1_sticky_compressor_oc_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3059,7 +3381,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_compressor_not_present_encode(double value);
+uint8_t PH_status_1_sticky_compressor_open_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3068,7 +3390,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_compressor_not_present_decode(uint8_t value);
+double PH_status_1_sticky_compressor_open_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3077,7 +3399,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_compressor_not_present_is_in_range(uint8_t value);
+bool PH_status_1_sticky_compressor_open_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3086,7 +3408,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_solenoid_over_current_encode(double value);
+uint8_t PH_status_1_sticky_solenoid_oc_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3095,7 +3417,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_solenoid_over_current_decode(uint8_t value);
+double PH_status_1_sticky_solenoid_oc_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3104,7 +3426,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_solenoid_over_current_is_in_range(uint8_t value);
+bool PH_status_1_sticky_solenoid_oc_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3113,7 +3435,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_can_warning_encode(double value);
+uint8_t PH_status_1_sticky_can_warning_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3122,7 +3444,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_can_warning_decode(uint8_t value);
+double PH_status_1_sticky_can_warning_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3131,7 +3453,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_can_warning_is_in_range(uint8_t value);
+bool PH_status_1_sticky_can_warning_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3140,7 +3462,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_can_bus_off_encode(double value);
+uint8_t PH_status_1_sticky_can_bus_off_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3149,7 +3471,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_can_bus_off_decode(uint8_t value);
+double PH_status_1_sticky_can_bus_off_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3158,7 +3480,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_can_bus_off_is_in_range(uint8_t value);
+bool PH_status_1_sticky_can_bus_off_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3167,7 +3489,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_hardware_fault_encode(double value);
+uint8_t PH_status_1_sticky_hardware_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3176,7 +3498,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_hardware_fault_decode(uint8_t value);
+double PH_status_1_sticky_hardware_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3185,7 +3507,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_hardware_fault_is_in_range(uint8_t value);
+bool PH_status_1_sticky_hardware_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3194,7 +3516,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_firmware_fault_encode(double value);
+uint8_t PH_status_1_sticky_firmware_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3203,7 +3525,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_firmware_fault_decode(uint8_t value);
+double PH_status_1_sticky_firmware_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3212,7 +3534,7 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_firmware_fault_is_in_range(uint8_t value);
+bool PH_status_1_sticky_firmware_fault_is_in_range(uint8_t value);
/**
* Encode given signal by applying scaling and offset.
@@ -3221,7 +3543,7 @@
*
* @return Encoded signal.
*/
-uint8_t PH_status1_sticky_has_reset_encode(double value);
+uint8_t PH_status_1_sticky_has_reset_fault_encode(double value);
/**
* Decode given signal by applying scaling and offset.
@@ -3230,7 +3552,7 @@
*
* @return Decoded signal.
*/
-double PH_status1_sticky_has_reset_decode(uint8_t value);
+double PH_status_1_sticky_has_reset_fault_decode(uint8_t value);
/**
* Check that given signal is in allowed range.
@@ -3239,7 +3561,252 @@
*
* @return true if in range, false otherwise.
*/
-bool PH_status1_sticky_has_reset_is_in_range(uint8_t value);
+bool PH_status_1_sticky_has_reset_fault_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_status_1_supply_voltage_5_v_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_status_1_supply_voltage_5_v_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_status_1_supply_voltage_5_v_is_in_range(uint8_t value);
+
+/**
+ * Pack message Clear_Faults.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int PH_clear_faults_pack(
+ uint8_t *dst_p,
+ const struct PH_clear_faults_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Clear_Faults.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int PH_clear_faults_unpack(
+ struct PH_clear_faults_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Pack message Version.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int PH_version_pack(
+ uint8_t *dst_p,
+ const struct PH_version_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Version.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int PH_version_unpack(
+ struct PH_version_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_version_firmware_fix_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_version_firmware_fix_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_version_firmware_fix_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_version_firmware_minor_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_version_firmware_minor_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_version_firmware_minor_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_version_firmware_year_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_version_firmware_year_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_version_firmware_year_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_version_hardware_minor_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_version_hardware_minor_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_version_hardware_minor_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t PH_version_hardware_major_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_version_hardware_major_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_version_hardware_major_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t PH_version_unique_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double PH_version_unique_id_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool PH_version_unique_id_is_in_range(uint32_t value);
#ifdef __cplusplus
diff --git a/hal/src/main/native/cpp/jni/CounterJNI.cpp b/hal/src/main/native/cpp/jni/CounterJNI.cpp
index 0565d5b..6fc12df 100644
--- a/hal/src/main/native/cpp/jni/CounterJNI.cpp
+++ b/hal/src/main/native/cpp/jni/CounterJNI.cpp
@@ -11,6 +11,18 @@
#include "hal/Counter.h"
#include "hal/Errors.h"
+static_assert(HAL_Counter_Mode::HAL_Counter_kTwoPulse ==
+ edu_wpi_first_hal_CounterJNI_TWO_PULSE);
+
+static_assert(HAL_Counter_Mode::HAL_Counter_kSemiperiod ==
+ edu_wpi_first_hal_CounterJNI_SEMI_PERIOD);
+
+static_assert(HAL_Counter_Mode::HAL_Counter_kPulseLength ==
+ edu_wpi_first_hal_CounterJNI_PULSE_LENGTH);
+
+static_assert(HAL_Counter_Mode::HAL_Counter_kExternalDirection ==
+ edu_wpi_first_hal_CounterJNI_EXTERNAL_DIRECTION);
+
using namespace hal;
extern "C" {
diff --git a/hal/src/main/native/cpp/jni/HALUtil.cpp b/hal/src/main/native/cpp/jni/HALUtil.cpp
index 1070085..5d5a958 100644
--- a/hal/src/main/native/cpp/jni/HALUtil.cpp
+++ b/hal/src/main/native/cpp/jni/HALUtil.cpp
@@ -46,6 +46,7 @@
static JException canMessageNotAllowedExCls;
static JException canNotInitializedExCls;
static JException uncleanStatusExCls;
+static JClass powerDistributionVersionCls;
static JClass pwmConfigDataResultCls;
static JClass canStatusCls;
static JClass matchInfoDataCls;
@@ -53,15 +54,19 @@
static JClass canDataCls;
static JClass halValueCls;
static JClass baseStoreCls;
+static JClass revPHVersionCls;
static const JClassInit classes[] = {
+ {"edu/wpi/first/hal/PowerDistributionVersion",
+ &powerDistributionVersionCls},
{"edu/wpi/first/hal/PWMConfigDataResult", &pwmConfigDataResultCls},
{"edu/wpi/first/hal/can/CANStatus", &canStatusCls},
{"edu/wpi/first/hal/MatchInfoData", &matchInfoDataCls},
{"edu/wpi/first/hal/AccumulatorResult", &accumulatorResultCls},
{"edu/wpi/first/hal/CANData", &canDataCls},
{"edu/wpi/first/hal/HALValue", &halValueCls},
- {"edu/wpi/first/hal/DMAJNISample$BaseStore", &baseStoreCls}};
+ {"edu/wpi/first/hal/DMAJNISample$BaseStore", &baseStoreCls},
+ {"edu/wpi/first/hal/REVPHVersion", &revPHVersionCls}};
static const JExceptionInit exceptions[] = {
{"java/lang/IllegalArgumentException", &illegalArgExCls},
@@ -238,6 +243,19 @@
static_cast<jint>(deadbandMinPwm), static_cast<jint>(minPwm));
}
+jobject CreateREVPHVersion(JNIEnv* env, uint32_t firmwareMajor,
+ uint32_t firmwareMinor, uint32_t firmwareFix,
+ uint32_t hardwareMinor, uint32_t hardwareMajor,
+ uint32_t uniqueId) {
+ static jmethodID constructor =
+ env->GetMethodID(revPHVersionCls, "<init>", "(IIIIII)V");
+ return env->NewObject(
+ revPHVersionCls, constructor, static_cast<jint>(firmwareMajor),
+ static_cast<jint>(firmwareMinor), static_cast<jint>(firmwareFix),
+ static_cast<jint>(hardwareMinor), static_cast<jint>(hardwareMajor),
+ static_cast<jint>(uniqueId));
+}
+
void SetCanStatusObject(JNIEnv* env, jobject canStatus,
float percentBusUtilization, uint32_t busOffCount,
uint32_t txFullCount, uint32_t receiveErrorCount,
@@ -318,6 +336,21 @@
return env->NewObject(baseStoreCls, ctor, valueType, index);
}
+jobject CreatePowerDistributionVersion(JNIEnv* env, uint32_t firmwareMajor,
+ uint32_t firmwareMinor,
+ uint32_t firmwareFix,
+ uint32_t hardwareMinor,
+ uint32_t hardwareMajor,
+ uint32_t uniqueId) {
+ static jmethodID constructor =
+ env->GetMethodID(powerDistributionVersionCls, "<init>", "(IIIIII)V");
+ return env->NewObject(
+ powerDistributionVersionCls, constructor,
+ static_cast<jint>(firmwareMajor), static_cast<jint>(firmwareMinor),
+ static_cast<jint>(firmwareFix), static_cast<jint>(hardwareMinor),
+ static_cast<jint>(hardwareMajor), static_cast<jint>(uniqueId));
+}
+
JavaVM* GetJVM() {
return jvm;
}
diff --git a/hal/src/main/native/cpp/jni/HALUtil.h b/hal/src/main/native/cpp/jni/HALUtil.h
index 2afe595..cf3956c 100644
--- a/hal/src/main/native/cpp/jni/HALUtil.h
+++ b/hal/src/main/native/cpp/jni/HALUtil.h
@@ -59,6 +59,11 @@
int32_t deadbandMaxPwm, int32_t centerPwm,
int32_t deadbandMinPwm, int32_t minPwm);
+jobject CreateREVPHVersion(JNIEnv* env, uint32_t firmwareMajor,
+ uint32_t firmwareMinor, uint32_t firmwareFix,
+ uint32_t hardwareMinor, uint32_t hardwareMajor,
+ uint32_t uniqueId);
+
void SetCanStatusObject(JNIEnv* env, jobject canStatus,
float percentBusUtilization, uint32_t busOffCount,
uint32_t txFullCount, uint32_t receiveErrorCount,
@@ -77,6 +82,13 @@
jobject CreateDMABaseStore(JNIEnv* env, jint valueType, jint index);
+jobject CreatePowerDistributionVersion(JNIEnv* env, uint32_t firmwareMajor,
+ uint32_t firmwareMinor,
+ uint32_t firmwareFix,
+ uint32_t hardwareMinor,
+ uint32_t hardwareMajor,
+ uint32_t uniqueId);
+
JavaVM* GetJVM();
} // namespace hal
diff --git a/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp b/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp
index b608458..9d85ea4 100644
--- a/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp
+++ b/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp
@@ -292,4 +292,133 @@
return state;
}
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: getVoltageNoError
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_getVoltageNoError
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ double voltage = HAL_GetPowerDistributionVoltage(handle, &status);
+ return voltage;
+}
+
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: getChannelCurrentNoError
+ * Signature: (II)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_getChannelCurrentNoError
+ (JNIEnv* env, jclass, jint handle, jint channel)
+{
+ int32_t status = 0;
+ double current =
+ HAL_GetPowerDistributionChannelCurrent(handle, channel, &status);
+ return current;
+}
+
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: getTotalCurrentNoError
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_getTotalCurrentNoError
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ double current = HAL_GetPowerDistributionTotalCurrent(handle, &status);
+ return current;
+}
+
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: setSwitchableChannelNoError
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_setSwitchableChannelNoError
+ (JNIEnv* env, jclass, jint handle, jboolean enabled)
+{
+ int32_t status = 0;
+ HAL_SetPowerDistributionSwitchableChannel(handle, enabled, &status);
+}
+
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: getSwitchableChannelNoError
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_getSwitchableChannelNoError
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ auto state = HAL_GetPowerDistributionSwitchableChannel(handle, &status);
+ return state;
+}
+
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: getStickyFaultsNative
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_getStickyFaultsNative
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_PowerDistributionStickyFaults halFaults;
+ std::memset(&halFaults, 0, sizeof(halFaults));
+ HAL_GetPowerDistributionStickyFaults(handle, &halFaults, &status);
+ CheckStatus(env, status, false);
+ jint faults;
+ static_assert(sizeof(faults) == sizeof(halFaults));
+ std::memcpy(&faults, &halFaults, sizeof(faults));
+ return faults;
+}
+
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: getFaultsNative
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_getFaultsNative
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_PowerDistributionFaults halFaults;
+ std::memset(&halFaults, 0, sizeof(halFaults));
+ HAL_GetPowerDistributionFaults(handle, &halFaults, &status);
+ CheckStatus(env, status, false);
+ jint faults;
+ static_assert(sizeof(faults) == sizeof(halFaults));
+ std::memcpy(&faults, &halFaults, sizeof(faults));
+ return faults;
+}
+
+/*
+ * Class: edu_wpi_first_hal_PowerDistributionJNI
+ * Method: getVersion
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_hal_PowerDistributionJNI_getVersion
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_PowerDistributionVersion version;
+ std::memset(&version, 0, sizeof(version));
+ HAL_GetPowerDistributionVersion(handle, &version, &status);
+ CheckStatus(env, status, false);
+ return CreatePowerDistributionVersion(
+ env, version.firmwareMajor, version.firmwareMinor, version.firmwareFix,
+ version.hardwareMinor, version.hardwareMajor, version.uniqueId);
+}
+
} // extern "C"
diff --git a/hal/src/main/native/cpp/jni/REVPHJNI.cpp b/hal/src/main/native/cpp/jni/REVPHJNI.cpp
index 3e99430..c630974 100644
--- a/hal/src/main/native/cpp/jni/REVPHJNI.cpp
+++ b/hal/src/main/native/cpp/jni/REVPHJNI.cpp
@@ -12,6 +12,19 @@
#include "hal/REVPH.h"
#include "hal/handles/HandlesInternal.h"
+static_assert(
+ edu_wpi_first_hal_REVPHJNI_COMPRESSOR_CONFIG_TYPE_DISABLED ==
+ HAL_REVPHCompressorConfigType::HAL_REVPHCompressorConfigType_kDisabled);
+static_assert(
+ edu_wpi_first_hal_REVPHJNI_COMPRESSOR_CONFIG_TYPE_DIGITAL ==
+ HAL_REVPHCompressorConfigType::HAL_REVPHCompressorConfigType_kDigital);
+static_assert(
+ edu_wpi_first_hal_REVPHJNI_COMPRESSOR_CONFIG_TYPE_ANALOG ==
+ HAL_REVPHCompressorConfigType::HAL_REVPHCompressorConfigType_kAnalog);
+static_assert(
+ edu_wpi_first_hal_REVPHJNI_COMPRESSOR_CONFIG_TYPE_HYBRID ==
+ HAL_REVPHCompressorConfigType::HAL_REVPHCompressorConfigType_kHybrid);
+
using namespace hal;
extern "C" {
@@ -73,31 +86,97 @@
/*
* Class: edu_wpi_first_hal_REVPHJNI
- * Method: setClosedLoopControl
- * Signature: (IZ)V
+ * Method: setCompressorConfig
+ * Signature: (IDDZZ)V
*/
JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_REVPHJNI_setClosedLoopControl
- (JNIEnv* env, jclass, jint handle, jboolean enabled)
+Java_edu_wpi_first_hal_REVPHJNI_setCompressorConfig
+ (JNIEnv* env, jclass, jint handle, jdouble minAnalogVoltage,
+ jdouble maxAnalogVoltage, jboolean forceDisable, jboolean useDigital)
{
int32_t status = 0;
- HAL_SetREVPHClosedLoopControl(handle, enabled, &status);
+ HAL_REVPHCompressorConfig config;
+ config.minAnalogVoltage = minAnalogVoltage;
+ config.maxAnalogVoltage = maxAnalogVoltage;
+ config.useDigital = useDigital;
+ config.forceDisable = forceDisable;
+ HAL_SetREVPHCompressorConfig(handle, &config, &status);
CheckStatus(env, status, false);
}
/*
* Class: edu_wpi_first_hal_REVPHJNI
- * Method: getClosedLoopControl
- * Signature: (I)Z
+ * Method: setClosedLoopControlDisabled
+ * Signature: (I)V
*/
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_hal_REVPHJNI_getClosedLoopControl
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_setClosedLoopControlDisabled
(JNIEnv* env, jclass, jint handle)
{
int32_t status = 0;
- auto result = HAL_GetREVPHClosedLoopControl(handle, &status);
+ HAL_SetREVPHClosedLoopControlDisabled(handle, &status);
CheckStatus(env, status, false);
- return result;
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: setClosedLoopControlDigital
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_setClosedLoopControlDigital
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_SetREVPHClosedLoopControlDigital(handle, &status);
+ CheckStatus(env, status, false);
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: setClosedLoopControlAnalog
+ * Signature: (IDD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_setClosedLoopControlAnalog
+ (JNIEnv* env, jclass, jint handle, jdouble minAnalogVoltage,
+ jdouble maxAnalogVoltage)
+{
+ int32_t status = 0;
+ HAL_SetREVPHClosedLoopControlAnalog(handle, minAnalogVoltage,
+ maxAnalogVoltage, &status);
+ CheckStatus(env, status, false);
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: setClosedLoopControlHybrid
+ * Signature: (IDD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_setClosedLoopControlHybrid
+ (JNIEnv* env, jclass, jint handle, jdouble minAnalogVoltage,
+ jdouble maxAnalogVoltage)
+{
+ int32_t status = 0;
+ HAL_SetREVPHClosedLoopControlHybrid(handle, minAnalogVoltage,
+ maxAnalogVoltage, &status);
+ CheckStatus(env, status, false);
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: getCompressorConfig
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_getCompressorConfig
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ auto config = HAL_GetREVPHCompressorConfig(handle, &status);
+ CheckStatus(env, status, false);
+ return static_cast<jint>(config);
}
/*
@@ -117,15 +196,15 @@
/*
* Class: edu_wpi_first_hal_REVPHJNI
- * Method: getAnalogPressure
+ * Method: getAnalogVoltage
* Signature: (II)D
*/
JNIEXPORT jdouble JNICALL
-Java_edu_wpi_first_hal_REVPHJNI_getAnalogPressure
+Java_edu_wpi_first_hal_REVPHJNI_getAnalogVoltage
(JNIEnv* env, jclass, jint handle, jint channel)
{
int32_t status = 0;
- auto result = HAL_GetREVPHAnalogPressure(handle, channel, &status);
+ auto result = HAL_GetREVPHAnalogVoltage(handle, channel, &status);
CheckStatus(env, status, false);
return result;
}
@@ -188,4 +267,137 @@
CheckStatus(env, status, false);
}
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: clearStickyFaults
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_clearStickyFaults
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_ClearREVPHStickyFaults(handle, &status);
+ CheckStatus(env, status, false);
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: getInputVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_getInputVoltage
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ auto voltage = HAL_GetREVPHVoltage(handle, &status);
+ CheckStatus(env, status, false);
+ return voltage;
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: get5VVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_get5VVoltage
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ auto voltage = HAL_GetREVPH5VVoltage(handle, &status);
+ CheckStatus(env, status, false);
+ return voltage;
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: getSolenoidCurrent
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_getSolenoidCurrent
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ auto voltage = HAL_GetREVPHSolenoidCurrent(handle, &status);
+ CheckStatus(env, status, false);
+ return voltage;
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: getSolenoidVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_getSolenoidVoltage
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ auto voltage = HAL_GetREVPHSolenoidVoltage(handle, &status);
+ CheckStatus(env, status, false);
+ return voltage;
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: getStickyFaultsNative
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_getStickyFaultsNative
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_REVPHStickyFaults halFaults;
+ std::memset(&halFaults, 0, sizeof(halFaults));
+ HAL_GetREVPHStickyFaults(handle, &halFaults, &status);
+ CheckStatus(env, status, false);
+ jint faults;
+ static_assert(sizeof(faults) == sizeof(halFaults));
+ std::memcpy(&faults, &halFaults, sizeof(faults));
+ return faults;
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: getFaultsNative
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_getFaultsNative
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_REVPHFaults halFaults;
+ std::memset(&halFaults, 0, sizeof(halFaults));
+ HAL_GetREVPHFaults(handle, &halFaults, &status);
+ CheckStatus(env, status, false);
+ jint faults;
+ static_assert(sizeof(faults) == sizeof(halFaults));
+ std::memcpy(&faults, &halFaults, sizeof(faults));
+ return faults;
+}
+
+/*
+ * Class: edu_wpi_first_hal_REVPHJNI
+ * Method: getVersion
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_hal_REVPHJNI_getVersion
+ (JNIEnv* env, jclass, jint handle)
+{
+ int32_t status = 0;
+ HAL_REVPHVersion version;
+ std::memset(&version, 0, sizeof(version));
+ HAL_GetREVPHVersion(handle, &version, &status);
+ CheckStatus(env, status, false);
+ return CreateREVPHVersion(env, version.firmwareMajor, version.firmwareMinor,
+ version.firmwareFix, version.hardwareMinor,
+ version.hardwareMajor, version.uniqueId);
+}
+
} // extern "C"
diff --git a/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp
index da473de..ca718f5 100644
--- a/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp
+++ b/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp
@@ -166,52 +166,54 @@
/*
* Class: edu_wpi_first_hal_simulation_REVPHDataJNI
- * Method: registerClosedLoopEnabledCallback
+ * Method: registerCompressorConfigTypeCallback
* Signature: (ILjava/lang/Object;Z)I
*/
JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_simulation_REVPHDataJNI_registerClosedLoopEnabledCallback
+Java_edu_wpi_first_hal_simulation_REVPHDataJNI_registerCompressorConfigTypeCallback
(JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
{
- return sim::AllocateCallback(env, index, callback, initialNotify,
- &HALSIM_RegisterREVPHClosedLoopEnabledCallback);
+ return sim::AllocateCallback(
+ env, index, callback, initialNotify,
+ &HALSIM_RegisterREVPHCompressorConfigTypeCallback);
}
/*
* Class: edu_wpi_first_hal_simulation_REVPHDataJNI
- * Method: cancelClosedLoopEnabledCallback
+ * Method: cancelCompressorConfigTypeCallback
* Signature: (II)V
*/
JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_simulation_REVPHDataJNI_cancelClosedLoopEnabledCallback
+Java_edu_wpi_first_hal_simulation_REVPHDataJNI_cancelCompressorConfigTypeCallback
(JNIEnv* env, jclass, jint index, jint handle)
{
return sim::FreeCallback(env, handle, index,
- &HALSIM_CancelREVPHClosedLoopEnabledCallback);
+ &HALSIM_CancelREVPHCompressorConfigTypeCallback);
}
/*
* Class: edu_wpi_first_hal_simulation_REVPHDataJNI
- * Method: getClosedLoopEnabled
- * Signature: (I)Z
+ * Method: getCompressorConfigType
+ * Signature: (I)I
*/
-JNIEXPORT jboolean JNICALL
-Java_edu_wpi_first_hal_simulation_REVPHDataJNI_getClosedLoopEnabled
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_simulation_REVPHDataJNI_getCompressorConfigType
(JNIEnv*, jclass, jint index)
{
- return HALSIM_GetREVPHClosedLoopEnabled(index);
+ return static_cast<jint>(HALSIM_GetREVPHCompressorConfigType(index));
}
/*
* Class: edu_wpi_first_hal_simulation_REVPHDataJNI
- * Method: setClosedLoopEnabled
- * Signature: (IZ)V
+ * Method: setCompressorConfigType
+ * Signature: (II)V
*/
JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_simulation_REVPHDataJNI_setClosedLoopEnabled
- (JNIEnv*, jclass, jint index, jboolean value)
+Java_edu_wpi_first_hal_simulation_REVPHDataJNI_setCompressorConfigType
+ (JNIEnv*, jclass, jint index, jint value)
{
- HALSIM_SetREVPHClosedLoopEnabled(index, value);
+ HALSIM_SetREVPHCompressorConfigType(
+ index, static_cast<HAL_REVPHCompressorConfigType>(value));
}
/*
diff --git a/hal/src/main/native/include/hal/PowerDistribution.h b/hal/src/main/native/include/hal/PowerDistribution.h
index fabb8b7..47cc9b2 100644
--- a/hal/src/main/native/include/hal/PowerDistribution.h
+++ b/hal/src/main/native/include/hal/PowerDistribution.h
@@ -218,6 +218,89 @@
HAL_Bool HAL_GetPowerDistributionSwitchableChannel(
HAL_PowerDistributionHandle handle, int32_t* status);
+struct HAL_PowerDistributionVersion {
+ uint32_t firmwareMajor;
+ uint32_t firmwareMinor;
+ uint32_t firmwareFix;
+ uint32_t hardwareMinor;
+ uint32_t hardwareMajor;
+ uint32_t uniqueId;
+};
+
+struct HAL_PowerDistributionFaults {
+ uint32_t channel0BreakerFault : 1;
+ uint32_t channel1BreakerFault : 1;
+ uint32_t channel2BreakerFault : 1;
+ uint32_t channel3BreakerFault : 1;
+ uint32_t channel4BreakerFault : 1;
+ uint32_t channel5BreakerFault : 1;
+ uint32_t channel6BreakerFault : 1;
+ uint32_t channel7BreakerFault : 1;
+ uint32_t channel8BreakerFault : 1;
+ uint32_t channel9BreakerFault : 1;
+ uint32_t channel10BreakerFault : 1;
+ uint32_t channel11BreakerFault : 1;
+ uint32_t channel12BreakerFault : 1;
+ uint32_t channel13BreakerFault : 1;
+ uint32_t channel14BreakerFault : 1;
+ uint32_t channel15BreakerFault : 1;
+ uint32_t channel16BreakerFault : 1;
+ uint32_t channel17BreakerFault : 1;
+ uint32_t channel18BreakerFault : 1;
+ uint32_t channel19BreakerFault : 1;
+ uint32_t channel20BreakerFault : 1;
+ uint32_t channel21BreakerFault : 1;
+ uint32_t channel22BreakerFault : 1;
+ uint32_t channel23BreakerFault : 1;
+ uint32_t brownout : 1;
+ uint32_t canWarning : 1;
+ uint32_t hardwareFault : 1;
+};
+
+/**
+ * Storage for REV PDH Sticky Faults
+ */
+struct HAL_PowerDistributionStickyFaults {
+ uint32_t channel0BreakerFault : 1;
+ uint32_t channel1BreakerFault : 1;
+ uint32_t channel2BreakerFault : 1;
+ uint32_t channel3BreakerFault : 1;
+ uint32_t channel4BreakerFault : 1;
+ uint32_t channel5BreakerFault : 1;
+ uint32_t channel6BreakerFault : 1;
+ uint32_t channel7BreakerFault : 1;
+ uint32_t channel8BreakerFault : 1;
+ uint32_t channel9BreakerFault : 1;
+ uint32_t channel10BreakerFault : 1;
+ uint32_t channel11BreakerFault : 1;
+ uint32_t channel12BreakerFault : 1;
+ uint32_t channel13BreakerFault : 1;
+ uint32_t channel14BreakerFault : 1;
+ uint32_t channel15BreakerFault : 1;
+ uint32_t channel16BreakerFault : 1;
+ uint32_t channel17BreakerFault : 1;
+ uint32_t channel18BreakerFault : 1;
+ uint32_t channel19BreakerFault : 1;
+ uint32_t channel20BreakerFault : 1;
+ uint32_t channel21BreakerFault : 1;
+ uint32_t channel22BreakerFault : 1;
+ uint32_t channel23BreakerFault : 1;
+ uint32_t brownout : 1;
+ uint32_t canWarning : 1;
+ uint32_t canBusOff : 1;
+ uint32_t hasReset : 1;
+};
+
+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);
+
#ifdef __cplusplus
} // extern "C"
#endif
diff --git a/hal/src/main/native/include/hal/REVPH.h b/hal/src/main/native/include/hal/REVPH.h
index 0cab15e..430c53d 100644
--- a/hal/src/main/native/include/hal/REVPH.h
+++ b/hal/src/main/native/include/hal/REVPH.h
@@ -14,6 +14,79 @@
* @{
*/
+/**
+ * The compressor configuration type
+ */
+HAL_ENUM(HAL_REVPHCompressorConfigType){
+ HAL_REVPHCompressorConfigType_kDisabled = 0,
+ HAL_REVPHCompressorConfigType_kDigital = 1,
+ HAL_REVPHCompressorConfigType_kAnalog = 2,
+ HAL_REVPHCompressorConfigType_kHybrid = 3,
+};
+
+/**
+ * Storage for REV PH Version
+ */
+struct HAL_REVPHVersion {
+ uint32_t firmwareMajor;
+ uint32_t firmwareMinor;
+ uint32_t firmwareFix;
+ uint32_t hardwareMinor;
+ uint32_t hardwareMajor;
+ uint32_t uniqueId;
+};
+
+/**
+ * Storage for compressor config
+ */
+struct HAL_REVPHCompressorConfig {
+ double minAnalogVoltage;
+ double maxAnalogVoltage;
+ HAL_Bool forceDisable;
+ HAL_Bool useDigital;
+};
+
+/**
+ * Storage for REV PH Faults
+ */
+struct HAL_REVPHFaults {
+ uint32_t channel0Fault : 1;
+ uint32_t channel1Fault : 1;
+ uint32_t channel2Fault : 1;
+ uint32_t channel3Fault : 1;
+ uint32_t channel4Fault : 1;
+ uint32_t channel5Fault : 1;
+ uint32_t channel6Fault : 1;
+ uint32_t channel7Fault : 1;
+ uint32_t channel8Fault : 1;
+ uint32_t channel9Fault : 1;
+ uint32_t channel10Fault : 1;
+ uint32_t channel11Fault : 1;
+ uint32_t channel12Fault : 1;
+ uint32_t channel13Fault : 1;
+ uint32_t channel14Fault : 1;
+ uint32_t channel15Fault : 1;
+ uint32_t compressorOverCurrent : 1;
+ uint32_t compressorOpen : 1;
+ uint32_t solenoidOverCurrent : 1;
+ uint32_t brownout : 1;
+ uint32_t canWarning : 1;
+ uint32_t hardwareFault : 1;
+};
+
+/**
+ * Storage for REV PH Sticky Faults
+ */
+struct HAL_REVPHStickyFaults {
+ uint32_t compressorOverCurrent : 1;
+ uint32_t compressorOpen : 1;
+ uint32_t solenoidOverCurrent : 1;
+ uint32_t brownout : 1;
+ uint32_t canWarning : 1;
+ uint32_t canBusOff : 1;
+ uint32_t hasReset : 1;
+};
+
#ifdef __cplusplus
extern "C" {
#endif
@@ -28,13 +101,33 @@
HAL_Bool HAL_CheckREVPHModuleNumber(int32_t module);
HAL_Bool HAL_GetREVPHCompressor(HAL_REVPHHandle handle, int32_t* status);
-void HAL_SetREVPHClosedLoopControl(HAL_REVPHHandle handle, HAL_Bool enabled,
- int32_t* status);
-HAL_Bool HAL_GetREVPHClosedLoopControl(HAL_REVPHHandle handle, int32_t* status);
+void HAL_SetREVPHCompressorConfig(HAL_REVPHHandle handle,
+ const HAL_REVPHCompressorConfig* config,
+ int32_t* status);
+void HAL_SetREVPHClosedLoopControlDisabled(HAL_REVPHHandle handle,
+ int32_t* status);
+void HAL_SetREVPHClosedLoopControlDigital(HAL_REVPHHandle handle,
+ int32_t* status);
+void HAL_SetREVPHClosedLoopControlAnalog(HAL_REVPHHandle handle,
+ double minAnalogVoltage,
+ double maxAnalogVoltage,
+ int32_t* status);
+void HAL_SetREVPHClosedLoopControlHybrid(HAL_REVPHHandle handle,
+ double minAnalogVoltage,
+ double maxAnalogVoltage,
+ int32_t* status);
+HAL_REVPHCompressorConfigType HAL_GetREVPHCompressorConfig(
+ HAL_REVPHHandle handle, int32_t* status);
HAL_Bool HAL_GetREVPHPressureSwitch(HAL_REVPHHandle handle, int32_t* status);
double HAL_GetREVPHCompressorCurrent(HAL_REVPHHandle handle, int32_t* status);
-double HAL_GetREVPHAnalogPressure(HAL_REVPHHandle handle, int32_t channel,
- int32_t* status);
+double HAL_GetREVPHAnalogVoltage(HAL_REVPHHandle handle, int32_t channel,
+ int32_t* status);
+double HAL_GetREVPHVoltage(HAL_REVPHHandle handle, int32_t* status);
+double HAL_GetREVPH5VVoltage(HAL_REVPHHandle handle, int32_t* status);
+double HAL_GetREVPHSolenoidCurrent(HAL_REVPHHandle handle, int32_t* status);
+double HAL_GetREVPHSolenoidVoltage(HAL_REVPHHandle handle, int32_t* status);
+void HAL_GetREVPHVersion(HAL_REVPHHandle handle, HAL_REVPHVersion* version,
+ int32_t* status);
int32_t HAL_GetREVPHSolenoids(HAL_REVPHHandle handle, int32_t* status);
void HAL_SetREVPHSolenoids(HAL_REVPHHandle handle, int32_t mask, int32_t values,
@@ -43,6 +136,15 @@
void HAL_FireREVPHOneShot(HAL_REVPHHandle handle, int32_t index, int32_t durMs,
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);
+
#ifdef __cplusplus
} // extern "C"
#endif
diff --git a/hal/src/main/native/include/hal/Types.h b/hal/src/main/native/include/hal/Types.h
index 6b95447..ac7c748 100644
--- a/hal/src/main/native/include/hal/Types.h
+++ b/hal/src/main/native/include/hal/Types.h
@@ -74,6 +74,11 @@
#ifdef __cplusplus
#define HAL_ENUM(name) enum name : int32_t
+#elif defined(__clang__)
+#define HAL_ENUM(name) \
+ enum name : int32_t; \
+ typedef enum name name; \
+ enum name : int32_t
#else
#define HAL_ENUM(name) \
typedef int32_t name; \
diff --git a/hal/src/main/native/include/hal/simulation/REVPHData.h b/hal/src/main/native/include/hal/simulation/REVPHData.h
index 17e4f2c..a836516 100644
--- a/hal/src/main/native/include/hal/simulation/REVPHData.h
+++ b/hal/src/main/native/include/hal/simulation/REVPHData.h
@@ -4,6 +4,7 @@
#pragma once
+#include "hal/REVPH.h"
#include "hal/Types.h"
#include "hal/simulation/NotifyListener.h"
@@ -39,13 +40,14 @@
HAL_Bool HALSIM_GetREVPHCompressorOn(int32_t index);
void HALSIM_SetREVPHCompressorOn(int32_t index, HAL_Bool compressorOn);
-int32_t HALSIM_RegisterREVPHClosedLoopEnabledCallback(
+int32_t HALSIM_RegisterREVPHCompressorConfigTypeCallback(
int32_t index, HAL_NotifyCallback callback, void* param,
HAL_Bool initialNotify);
-void HALSIM_CancelREVPHClosedLoopEnabledCallback(int32_t index, int32_t uid);
-HAL_Bool HALSIM_GetREVPHClosedLoopEnabled(int32_t index);
-void HALSIM_SetREVPHClosedLoopEnabled(int32_t index,
- HAL_Bool closedLoopEnabled);
+void HALSIM_CancelREVPHCompressorConfigTypeCallback(int32_t index, int32_t uid);
+HAL_REVPHCompressorConfigType HALSIM_GetREVPHCompressorConfigType(
+ int32_t index);
+void HALSIM_SetREVPHCompressorConfigType(
+ int32_t index, HAL_REVPHCompressorConfigType configType);
int32_t HALSIM_RegisterREVPHPressureSwitchCallback(int32_t index,
HAL_NotifyCallback callback,
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