mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[hal] Remove over current fault HAL functions from REV PDH (#3526)
This commit is contained in:
committed by
GitHub
parent
aa3848b2c8
commit
82eef8d5ee
@@ -611,16 +611,6 @@ HAL_Bool HAL_REV_CheckPDHBrownout(HAL_REVPDHHandle handle, int32_t* status) {
|
||||
return PDH_status4_brownout_decode(statusFrame.brownout);
|
||||
}
|
||||
|
||||
HAL_Bool HAL_REV_CheckPDHOverCurrent(HAL_REVPDHHandle handle, int32_t* status) {
|
||||
PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
|
||||
|
||||
if (*status != 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return PDH_status4_over_current_decode(statusFrame.over_current);
|
||||
}
|
||||
|
||||
HAL_Bool HAL_REV_CheckPDHCANWarning(HAL_REVPDHHandle handle, int32_t* status) {
|
||||
PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
|
||||
|
||||
@@ -653,18 +643,6 @@ HAL_Bool HAL_REV_CheckPDHStickyBrownout(HAL_REVPDHHandle handle,
|
||||
return PDH_status4_sticky_brownout_decode(statusFrame.sticky_brownout);
|
||||
}
|
||||
|
||||
HAL_Bool HAL_REV_CheckPDHStickyOverCurrent(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_over_current_decode(
|
||||
statusFrame.sticky_over_current);
|
||||
}
|
||||
|
||||
HAL_Bool HAL_REV_CheckPDHStickyCANWarning(HAL_REVPDHHandle handle,
|
||||
int32_t* status) {
|
||||
PDH_status4_t statusFrame = HAL_REV_GetPDHStatus4(handle, status);
|
||||
|
||||
@@ -160,18 +160,6 @@ HAL_Bool HAL_REV_IsPDHEnabled(HAL_REVPDHHandle handle, int32_t* status);
|
||||
*/
|
||||
HAL_Bool HAL_REV_CheckPDHBrownout(HAL_REVPDHHandle handle, int32_t* status);
|
||||
|
||||
/**
|
||||
* Checks if the system current on a PDH device is currently exceeding the max
|
||||
* system current.
|
||||
*
|
||||
* NOTE: Not implemented in firmware as of 2021-04-23.
|
||||
*
|
||||
* @param handle PDH handle
|
||||
*
|
||||
* @return 1 if the PDH is over max current; 0 otherwise
|
||||
*/
|
||||
HAL_Bool HAL_REV_CheckPDHOverCurrent(HAL_REVPDHHandle handle, int32_t* status);
|
||||
|
||||
/**
|
||||
* Checks if the CAN RX or TX error levels on a PDH device have exceeded the
|
||||
* warning threshold.
|
||||
@@ -211,19 +199,6 @@ HAL_Bool HAL_REV_CheckPDHHardwareFault(HAL_REVPDHHandle handle,
|
||||
HAL_Bool HAL_REV_CheckPDHStickyBrownout(HAL_REVPDHHandle handle,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Checks if the system current on a PDH device has exceeded the maximum system
|
||||
* current.
|
||||
*
|
||||
* NOTE: Not implemented in firmware as of 2021-04-23.
|
||||
*
|
||||
* @param handle PDH handle
|
||||
*
|
||||
* @return 1 if the device has been over current; 0 otherwise
|
||||
*/
|
||||
HAL_Bool HAL_REV_CheckPDHStickyOverCurrent(HAL_REVPDHHandle handle,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Checks if the CAN RX or TX error levels on a PDH device have exceeded the
|
||||
* warning threshold.
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* This file was generated by cantools version 36.2.0 Fri Jul 9 14:22:19 2021.
|
||||
* This file was generated by cantools version
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
@@ -1164,14 +1164,14 @@ int PDH_status4_pack(
|
||||
dst_p[0] |= pack_left_shift_u16(src_p->v_bus, 0u, 0xffu);
|
||||
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->rsvd, 5u, 0xe0u);
|
||||
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->over_current, 1u, 0x02u);
|
||||
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->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->sticky_over_current, 6u, 0x40u);
|
||||
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[3] |= pack_left_shift_u8(src_p->sticky_hardware_fault, 1u, 0x02u);
|
||||
@@ -1198,14 +1198,14 @@ int PDH_status4_unpack(
|
||||
dst_p->v_bus = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
|
||||
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->rsvd = unpack_right_shift_u8(src_p[1], 5u, 0xe0u);
|
||||
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->over_current = unpack_right_shift_u8(src_p[2], 1u, 0x02u);
|
||||
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->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->sticky_over_current = unpack_right_shift_u8(src_p[2], 6u, 0x40u);
|
||||
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_hardware_fault = unpack_right_shift_u8(src_p[3], 1u, 0x02u);
|
||||
@@ -1250,17 +1250,17 @@ bool PDH_status4_system_enable_is_in_range(uint8_t value)
|
||||
return (value <= 1u);
|
||||
}
|
||||
|
||||
uint8_t PDH_status4_rsvd_encode(double value)
|
||||
uint8_t PDH_status4_rsvd0_encode(double value)
|
||||
{
|
||||
return (uint8_t)(value);
|
||||
}
|
||||
|
||||
double PDH_status4_rsvd_decode(uint8_t value)
|
||||
double PDH_status4_rsvd0_decode(uint8_t value)
|
||||
{
|
||||
return ((double)value);
|
||||
}
|
||||
|
||||
bool PDH_status4_rsvd_is_in_range(uint8_t value)
|
||||
bool PDH_status4_rsvd0_is_in_range(uint8_t value)
|
||||
{
|
||||
return (value <= 7u);
|
||||
}
|
||||
@@ -1280,17 +1280,17 @@ bool PDH_status4_brownout_is_in_range(uint8_t value)
|
||||
return (value <= 1u);
|
||||
}
|
||||
|
||||
uint8_t PDH_status4_over_current_encode(double value)
|
||||
uint8_t PDH_status4_rsvd1_encode(double value)
|
||||
{
|
||||
return (uint8_t)(value);
|
||||
}
|
||||
|
||||
double PDH_status4_over_current_decode(uint8_t value)
|
||||
double PDH_status4_rsvd1_decode(uint8_t value)
|
||||
{
|
||||
return ((double)value);
|
||||
}
|
||||
|
||||
bool PDH_status4_over_current_is_in_range(uint8_t value)
|
||||
bool PDH_status4_rsvd1_is_in_range(uint8_t value)
|
||||
{
|
||||
return (value <= 1u);
|
||||
}
|
||||
@@ -1355,17 +1355,17 @@ bool PDH_status4_sticky_brownout_is_in_range(uint8_t value)
|
||||
return (value <= 1u);
|
||||
}
|
||||
|
||||
uint8_t PDH_status4_sticky_over_current_encode(double value)
|
||||
uint8_t PDH_status4_rsvd2_encode(double value)
|
||||
{
|
||||
return (uint8_t)(value);
|
||||
}
|
||||
|
||||
double PDH_status4_sticky_over_current_decode(uint8_t value)
|
||||
double PDH_status4_rsvd2_decode(uint8_t value)
|
||||
{
|
||||
return ((double)value);
|
||||
}
|
||||
|
||||
bool PDH_status4_sticky_over_current_is_in_range(uint8_t value)
|
||||
bool PDH_status4_rsvd2_is_in_range(uint8_t value)
|
||||
{
|
||||
return (value <= 1u);
|
||||
}
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* This file was generated by cantools version 36.2.0 Fri Jul 9 14:22:19 2021.
|
||||
* This file was generated by cantools version
|
||||
*/
|
||||
|
||||
#ifndef PDH_H
|
||||
@@ -510,7 +510,7 @@ struct PDH_status4_t {
|
||||
* Scale: 1
|
||||
* Offset: 0
|
||||
*/
|
||||
uint8_t rsvd : 3;
|
||||
uint8_t rsvd0 : 3;
|
||||
|
||||
/**
|
||||
* Range: 0..1 (0..1 -)
|
||||
@@ -524,7 +524,7 @@ struct PDH_status4_t {
|
||||
* Scale: 1
|
||||
* Offset: 0
|
||||
*/
|
||||
uint8_t over_current : 1;
|
||||
uint8_t rsvd1 : 1;
|
||||
|
||||
/**
|
||||
* Range: 0..1 (0..1 -)
|
||||
@@ -559,7 +559,7 @@ struct PDH_status4_t {
|
||||
* Scale: 1
|
||||
* Offset: 0
|
||||
*/
|
||||
uint8_t sticky_over_current : 1;
|
||||
uint8_t rsvd2 : 1;
|
||||
|
||||
/**
|
||||
* Range: 0..1 (0..1 -)
|
||||
@@ -2320,7 +2320,7 @@ bool PDH_status4_system_enable_is_in_range(uint8_t value);
|
||||
*
|
||||
* @return Encoded signal.
|
||||
*/
|
||||
uint8_t PDH_status4_rsvd_encode(double value);
|
||||
uint8_t PDH_status4_rsvd0_encode(double value);
|
||||
|
||||
/**
|
||||
* Decode given signal by applying scaling and offset.
|
||||
@@ -2329,7 +2329,7 @@ uint8_t PDH_status4_rsvd_encode(double value);
|
||||
*
|
||||
* @return Decoded signal.
|
||||
*/
|
||||
double PDH_status4_rsvd_decode(uint8_t value);
|
||||
double PDH_status4_rsvd0_decode(uint8_t value);
|
||||
|
||||
/**
|
||||
* Check that given signal is in allowed range.
|
||||
@@ -2338,7 +2338,7 @@ double PDH_status4_rsvd_decode(uint8_t value);
|
||||
*
|
||||
* @return true if in range, false otherwise.
|
||||
*/
|
||||
bool PDH_status4_rsvd_is_in_range(uint8_t value);
|
||||
bool PDH_status4_rsvd0_is_in_range(uint8_t value);
|
||||
|
||||
/**
|
||||
* Encode given signal by applying scaling and offset.
|
||||
@@ -2374,7 +2374,7 @@ bool PDH_status4_brownout_is_in_range(uint8_t value);
|
||||
*
|
||||
* @return Encoded signal.
|
||||
*/
|
||||
uint8_t PDH_status4_over_current_encode(double value);
|
||||
uint8_t PDH_status4_rsvd1_encode(double value);
|
||||
|
||||
/**
|
||||
* Decode given signal by applying scaling and offset.
|
||||
@@ -2383,7 +2383,7 @@ uint8_t PDH_status4_over_current_encode(double value);
|
||||
*
|
||||
* @return Decoded signal.
|
||||
*/
|
||||
double PDH_status4_over_current_decode(uint8_t value);
|
||||
double PDH_status4_rsvd1_decode(uint8_t value);
|
||||
|
||||
/**
|
||||
* Check that given signal is in allowed range.
|
||||
@@ -2392,7 +2392,7 @@ double PDH_status4_over_current_decode(uint8_t value);
|
||||
*
|
||||
* @return true if in range, false otherwise.
|
||||
*/
|
||||
bool PDH_status4_over_current_is_in_range(uint8_t value);
|
||||
bool PDH_status4_rsvd1_is_in_range(uint8_t value);
|
||||
|
||||
/**
|
||||
* Encode given signal by applying scaling and offset.
|
||||
@@ -2509,7 +2509,7 @@ bool PDH_status4_sticky_brownout_is_in_range(uint8_t value);
|
||||
*
|
||||
* @return Encoded signal.
|
||||
*/
|
||||
uint8_t PDH_status4_sticky_over_current_encode(double value);
|
||||
uint8_t PDH_status4_rsvd2_encode(double value);
|
||||
|
||||
/**
|
||||
* Decode given signal by applying scaling and offset.
|
||||
@@ -2518,7 +2518,7 @@ uint8_t PDH_status4_sticky_over_current_encode(double value);
|
||||
*
|
||||
* @return Decoded signal.
|
||||
*/
|
||||
double PDH_status4_sticky_over_current_decode(uint8_t value);
|
||||
double PDH_status4_rsvd2_decode(uint8_t value);
|
||||
|
||||
/**
|
||||
* Check that given signal is in allowed range.
|
||||
@@ -2527,7 +2527,7 @@ double PDH_status4_sticky_over_current_decode(uint8_t value);
|
||||
*
|
||||
* @return true if in range, false otherwise.
|
||||
*/
|
||||
bool PDH_status4_sticky_over_current_is_in_range(uint8_t value);
|
||||
bool PDH_status4_rsvd2_is_in_range(uint8_t value);
|
||||
|
||||
/**
|
||||
* Encode given signal by applying scaling and offset.
|
||||
|
||||
Reference in New Issue
Block a user