Index: firmware/App/Controllers/BloodFlow.c =================================================================== diff -u -r8466e63f95f65a3ffb18c3af85ac99328e41167b -rb9eccdfcf1727112664b85977a16a18811b9fde7 --- firmware/App/Controllers/BloodFlow.c (.../BloodFlow.c) (revision 8466e63f95f65a3ffb18c3af85ac99328e41167b) +++ firmware/App/Controllers/BloodFlow.c (.../BloodFlow.c) (revision b9eccdfcf1727112664b85977a16a18811b9fde7) @@ -1,21 +1,21 @@ /************************************************************************** * -* Copyright (c) 2019-2020 Diality Inc. - All Rights Reserved. +* Copyright (c) 2019-2021 Diality Inc. - All Rights Reserved. * * THIS CODE MAY NOT BE COPIED OR REPRODUCED IN ANY FORM, IN PART OR IN * WHOLE, WITHOUT THE EXPLICIT PERMISSION OF THE COPYRIGHT OWNER. * -* @file BloodFlow.c +* @file BloodFlow.c * -* @author (last) Sean Nash -* @date (last) 13-Oct-2020 +* @author (last) Dara Navaei +* @date (last) 06-Nov-2021 * -* @author (original) Sean Nash -* @date (original) 07-Nov-2019 +* @author (original) Sean Nash +* @date (original) 07-Nov-2019 * ***************************************************************************/ -#include +#include // Used for fabs() and pow() functions #include "can.h" #include "etpwm.h" @@ -50,79 +50,80 @@ #define MIN_BLOOD_PUMP_PWM_DUTY_CYCLE 0.10 ///< Controller will error if PWM duty cycle < 10%, so set min to 10% #define BP_CONTROL_INTERVAL_SEC 10 ///< Blood pump control interval (in seconds). + /// Interval (ms/task time) at which the blood pump is controlled. -static const U32 BP_CONTROL_INTERVAL = ( BP_CONTROL_INTERVAL_SEC * MS_PER_SECOND / TASK_GENERAL_INTERVAL ); +static const U32 BP_CONTROL_INTERVAL = ( BP_CONTROL_INTERVAL_SEC * MS_PER_SECOND / TASK_GENERAL_INTERVAL ); + #define BP_P_COEFFICIENT 0.0001 ///< P term for blood pump control #define BP_I_COEFFICIENT 0.00075 ///< I term for blood pump control #define BP_HOME_RATE 100 ///< Target pump speed (in estimate mL/min) for homing. -#define BP_HOME_TIMEOUT_MS 10000 ///< Maximum time allowed for homing to complete (in ms). +#define BP_HOME_TIMEOUT_MS 10000 ///< Maximum time (in ms) allowed for homing to complete. +#define BP_MAX_ROTOR_HALL_INTERVAL_MS 20000 ///< Maximum time (in ms) allowed between rotor hall sensor detects (50 mL/min worst case). + /// Interval (ms/task time) at which the blood pump speed is calculated (every 40 ms). -#define BP_SPEED_CALC_INTERVAL ( 40 / TASK_PRIORITY_INTERVAL ) +#define BP_SPEED_CALC_INTERVAL ( 40 / TASK_PRIORITY_INTERVAL ) + /// Number of hall sensor counts kept in buffer to hold last 1 second of count data. #define BP_SPEED_CALC_BUFFER_LEN ( MS_PER_SECOND / BP_SPEED_CALC_INTERVAL / TASK_PRIORITY_INTERVAL ) + #define BP_MAX_ROTOR_SPEED_RPM 100.0 ///< Maximum rotor speed allowed for blood pump. #define BP_MAX_FLOW_RATE 1320.0 ///< Maximum measured BP flow rate allowed. #define BP_MIN_FLOW_RATE -1320.0 ///< Minimum measured BP flow rate allowed. -#define BP_MAX_FLOW_VS_SPEED_DIFF_RPM 200.0 ///< Maximum difference between measured speed and speed implied by measured flow. #define BP_MAX_MOTOR_SPEED_WHILE_OFF_RPM 100.0 ///< Maximum motor speed (RPM) while motor is commanded off. #define BP_MAX_ROTOR_VS_MOTOR_DIFF_RPM 5.0 ///< Maximum difference in speed between motor and rotor (in rotor RPM). #define BP_MAX_MOTOR_SPEED_ERROR_RPM 300.0 ///< Maximum difference in speed between measured and commanded RPM. -/// Persist time (task intervals) for flow vs. motor speed error condition. +#define BP_MAX_FLOW_VS_SPEED_DIFF_RPM 200.0 ///< Maximum difference between measured speed and speed implied by measured flow. + +/// Persist time (task intervals) for flow vs. motor speed error condition. static const U32 BP_FLOW_VS_SPEED_PERSIST = ( 5 * MS_PER_SECOND ); /// Persist time (task intervals) for motor off error condition. static const U32 BP_OFF_ERROR_PERSIST = ( 5 * MS_PER_SECOND ); /// Persist time (task intervals) motor speed error condition. static const U32 BP_MOTOR_SPEED_ERROR_PERSIST = ( 5 * MS_PER_SECOND ); /// Persist time (task intervals) rotor speed error condition. -static const U32 BP_ROTOR_SPEED_ERROR_PERSIST = ( 12 * MS_PER_SECOND ); +static const U32 BP_ROTOR_SPEED_ERROR_PERSIST = ( 22 * MS_PER_SECOND ); /// Persist time (task intervals) pump direction error condition. static const U32 BP_DIRECTION_ERROR_PERSIST = ( 250 ); /// Persist time period blood pump rotor speed too fast error condition. static const U32 BP_MAX_ROTOR_SPEED_ERROR_PERSIST = ( 1 * MS_PER_SECOND ); /// Persist time (task intervals) blood flow rate out of range error condition. static const U32 BP_MAX_FLOW_RATE_OUT_OF_RANGE_PERSIST = ((1 * MS_PER_SECOND) / TASK_PRIORITY_INTERVAL); -#define BP_MAX_CURR_WHEN_STOPPED_MA 150.0 ///< Motor controller current should not exceed this when pump should be stopped -#define BP_MAX_CURR_WHEN_RUNNING_MA 2000.0 ///< Motor controller current should not exceed this when pump should be running -#define BP_MAX_CURR_ERROR_DURATION_MS 2000 ///< Motor controller current errors persisting beyond this duration will trigger an alarm +#define BP_MAX_CURR_WHEN_STOPPED_MA 150.0 ///< Motor controller current should not exceed this when pump should be stopped. +#define BP_MAX_CURR_WHEN_RUNNING_MA 2000.0 ///< Motor controller current should not exceed this when pump should be running. +#define BP_MAX_CURR_ERROR_DURATION_MS 2000 ///< Motor controller current errors persisting beyond this duration will trigger an alarm. -#define BP_SPEED_ADC_TO_RPM_FACTOR 1.751752 ///< Conversion factor from ADC counts to RPM for blood pump motor -#define BP_MOTOR_RPM_TO_PWM_DC_FACTOR 0.000238 ///< ~42 BP motor RPM = 1% PWM duty cycle -#define BP_CURRENT_ADC_TO_MA_FACTOR 3.002 ///< Conversion factor from ADC counts to mA for blood pump motor +#define BP_SPEED_ADC_TO_RPM_FACTOR 1.751752 ///< Conversion factor from ADC counts to RPM for blood pump motor. +#define BP_MOTOR_RPM_TO_PWM_DC_FACTOR 0.000238 ///< ~42 BP motor RPM = 1% PWM duty cycle. +#define BP_CURRENT_ADC_TO_MA_FACTOR 3.002 ///< Conversion factor from ADC counts to mA for blood pump motor. -#define BP_REV_PER_LITER 150.0 ///< Rotor revolutions per liter +#define BP_REV_PER_LITER 146.84 ///< Rotor revolutions per liter. +#define BP_ML_PER_ROTOR_REV 6.81 ///< Milliliters per rotor revolusion. #define BP_ML_PER_MIN_TO_PUMP_RPM_FACTOR ( BP_REV_PER_LITER / ML_PER_LITER ) ///< Conversion factor from mL/min to motor RPM. -#define BP_GEAR_RATIO 32.0 ///< Blood pump motor to blood pump gear ratio -#define BP_PWM_ZERO_OFFSET 0.1 ///< 10% PWM duty cycle = zero speed +#define BP_GEAR_RATIO 32.0 ///< Blood pump motor to blood pump gear ratio. +#define BP_PWM_ZERO_OFFSET 0.1 ///< 10 pct PWM duty cycle = zero speed. + /// Conversion macro from mL/min to estimated PWM duty cycle %. #define BP_PWM_FROM_ML_PER_MIN(rate) ( (rate) * BP_ML_PER_MIN_TO_PUMP_RPM_FACTOR * BP_GEAR_RATIO * BP_MOTOR_RPM_TO_PWM_DC_FACTOR + BP_PWM_ZERO_OFFSET ) /// Conversion from PWM duty cycle % to commanded pump motor speed. #define BP_PWM_TO_MOTOR_SPEED_RPM(pwm) ( ((pwm) - BP_PWM_ZERO_OFFSET) * 4000.0 ) -#define BLOODPUMP_ADC_FULL_SCALE_V 3.0 ///< BP analog signals are 0-3V (while int. ADC ref may be different) +#define BLOODPUMP_ADC_FULL_SCALE_V 3.0 ///< BP analog signals are 0-3V (while int. ADC ref may be different). #define BLOODPUMP_ADC_ZERO 1998 ///< Blood pump ADC channel zero offset. /// Macro converts 12 bit ADC value to signed 16-bit value. #define SIGN_FROM_12_BIT_VALUE(v) ( (S16)(v) - (S16)BLOODPUMP_ADC_ZERO ) -/// Measured blood flow is filtered w/ moving average -#define SIZE_OF_ROLLING_AVG ( ( MS_PER_SECOND / TASK_PRIORITY_INTERVAL ) * 10 ) -/// Blood flow sensor signal strength low alarm persistence. -#define FLOW_SIG_STRGTH_ALARM_PERSIST ( BP_CONTROL_INTERVAL_SEC * MS_PER_SECOND ) -#define MIN_FLOW_SIG_STRENGTH 0.9 ///< Minimum flow sensor signal strength (90%). +/// Measured blood flow is filtered w/ moving average. +#define SIZE_OF_ROLLING_AVG ( ( MS_PER_SECOND / TASK_PRIORITY_INTERVAL ) * 1 ) -/// Blood flow fast read timeout alarm persistence. -#define BLOOD_FLOW_FAST_READ_TO_PERSIST 100 -/// Blood flow slow read timeout alarm persistence. -#define BLOOD_FLOW_SLOW_READ_TO_PERSIST ( MS_PER_SECOND * 3 ) -/// Blood flow comm error persistence. -#define BLOOD_FLOW_COMM_ERROR_PERSIST MS_PER_SECOND - -#define BFM_SENSOR_CONNECTED_STATUS 0x00 ///< Blood flow meter connected status. -#define BFM_SENSOR_PARAM_CORRUPT_STATUS 0x07 ///< Blood flow meter NVM parameter status. - #define PUMP_DIR_ERROR_COUNT_MASK 0x3F ///< Bit mask for pump direction error counter. + +#define BP_FLOW_ALPHA_Y_INTERCEPT 1.218 ///< Y intercept used for alpha flow coefficient calculation. +#define BP_FLOW_WEAR_A_TERM 0.000000007474 ///< A term used for wear portion of alpha flow coefficient. +#define BP_FLOW_WEAR_B_TERM 0.0006053 ///< B term used for wear portion of alpha flow coefficient. +#define BP_MAX_ROTOR_COUNT_FOR_WEAR 25000 ///< Maximum rotor count for determining wear of the cartridge (negligible affect beyond this threshold). /// Enumeration of blood pump controller states. typedef enum BloodPump_States @@ -166,18 +167,25 @@ /// Interval (in task intervals) at which to publish blood flow data to CAN bus. static OVERRIDE_U32_T bloodFlowDataPublishInterval = { BLOOD_FLOW_DATA_PUB_INTERVAL, BLOOD_FLOW_DATA_PUB_INTERVAL, BLOOD_FLOW_DATA_PUB_INTERVAL, 0 }; -static S32 targetBloodFlowRate = 0; ///< Requested blood flow rate -static OVERRIDE_F32_T measuredBloodFlowRate = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood flow rate -static OVERRIDE_F32_T bloodPumpRotorSpeedRPM = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump rotor speed -static OVERRIDE_F32_T bloodPumpSpeedRPM = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump motor speed -static OVERRIDE_F32_T adcBloodPumpMCSpeedRPM = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump motor controller speed -static OVERRIDE_F32_T adcBloodPumpMCCurrentmA = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump motor controller current -static OVERRIDE_F32_T bloodFlowSignalStrength = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood flow signal strength (%) +static S32 targetBloodFlowRate = 0; ///< Requested blood flow rate. +static OVERRIDE_F32_T measuredBloodFlowRate = { 0.0, 0.0, 0.0, 0 }; ///< Measured (calculated now) blood flow rate. +static OVERRIDE_F32_T bloodPumpRotorSpeedRPM = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump rotor speed. +static OVERRIDE_F32_T bloodPumpSpeedRPM = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump motor speed. +static OVERRIDE_F32_T adcBloodPumpMCSpeedRPM = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump motor controller speed. +static OVERRIDE_F32_T adcBloodPumpMCCurrentmA = { 0.0, 0.0, 0.0, 0 }; ///< Measured blood pump motor controller current. +static U08 lastBloodPumpDirectionCount = 0; ///< Previous pump direction error count reported by FPGA. + +static F32 rpmReadings[ SIZE_OF_ROLLING_AVG ]; ///< Holds RPM samples for a rolling average. +static U32 rpmReadingsIdx = 0; ///< Index for next sample in rolling average array. +static F32 rpmReadingsTotal = 0.0; ///< Rolling total - used to calc average. +static U32 rpmReadingsCount = 0; ///< Number of samples in RPM rolling average buffer. +static F32 filteredBloodPumpSpeed = 0.0; ///< Filtered blood pump speed used in blood flow estimation. + static U32 bpControlTimerCounter = 0; ///< Determines when to perform control on blood flow static U32 bpRotorRevStartTime = 0; ///< Blood pump rotor rotation start time (in ms) -static U32 bloodPumpRotorCounter = 0; ///< Running counter for blood pump rotor revolutions +static OVERRIDE_U32_T bloodPumpRotorCounter = { 0, 0, 0, 0 }; ///< Running counter for blood pump rotor revolutions static BOOL bpStopAtHomePosition = FALSE; ///< Stop blood pump at next home position static U32 bpHomeStartTime = 0; ///< When did blood pump home command begin? (in ms) @@ -186,17 +194,6 @@ static U32 bpMotorSpeedCalcIdx = 0; ///< Index into 1 second buffer of motor speed hall sensor counts static U32 bpMotorSpeedCalcTimerCtr = 0; ///< Counter determines interval for calculating blood pump motor speed from hall sensor count. -static F32 flowReadings[ SIZE_OF_ROLLING_AVG ]; ///< Holds flow samples for a rolling average. -static U32 flowReadingsIdx = 0; ///< Index for next sample in rolling average array. -static F32 flowReadingsTotal = 0.0; ///< Rolling total - used to calc average. -static U32 flowReadingsCount = 0; ///< Number of samples in flow rolling average buffer. - -static U08 lastBloodFlowFastPacketReadCtr = 0; ///< Previous read counter for the blood flow fast packets. -static U08 lastBloodFlowSlowPacketReadCtr = 0; ///< Previous read counter for the blood flow slow packets. -static U08 lastBloodPumpDirectionCount = 0; ///< Previous pump direction error count reported by FPGA. -static U08 lastBloodFlowCommErrorCount = 0; ///< Previous BP flow sensor comm error count. -static HD_FLOW_SENSORS_CAL_RECORD_T bloodFlowCalRecord; ///< Blood flow sensor calibration record. - // ********** private function prototypes ********** static BLOOD_PUMP_STATE_T handleBloodPumpOffState( void ); @@ -208,17 +205,17 @@ static void releaseBloodPumpStop( void ); static void setBloodPumpDirection( MOTOR_DIR_T dir ); static void publishBloodFlowData( void ); -static void resetBloodFlowMovingAverage( void ); -static void filterBloodFlowReadings( F32 flow ); static void updateBloodPumpSpeedAndDirectionFromHallSensors( void ); static void checkBloodPumpRotor( void ); static void checkBloodPumpDirection( void ); static void checkBloodPumpSpeeds( void ); -static void checkBloodPumpFlowAgainstSpeed( void ); static void checkBloodPumpMCCurrent( void ); -static void checkBloodFlowSensorSignalStrength( void ); -static BOOL processCalibrationData( void ); - +static void checkBloodPumpFlowRate( void ); + +static F32 calcBloodFlow( void ); +static void resetBloodPumpRPMMovingAverage( void ); +static void filterBloodPumpRPMReadings( F32 rpm ); + /*********************************************************************//** * @brief * The initBloodFlow function initializes the BloodFlow module. @@ -233,33 +230,30 @@ stopBloodPump(); setBloodPumpDirection( MOTOR_DIR_FORWARD ); - // Zero rolling flow average buffer - resetBloodFlowMovingAverage(); + // Zero rolling pump speed average buffer + resetBloodPumpRPMMovingAverage(); // Zero motor hall sensors counts buffer bpMotorSpeedCalcIdx = 0; for ( i = 0; i < BP_SPEED_CALC_BUFFER_LEN; i++ ) { bpLastMotorHallSensorCounts[ i ] = 0; } + resetBloodPumpRotorCount(); // Initialize blood flow PI controller initializePIController( PI_CONTROLLER_ID_BLOOD_FLOW, MIN_BLOOD_PUMP_PWM_DUTY_CYCLE, BP_P_COEFFICIENT, BP_I_COEFFICIENT, MIN_BLOOD_PUMP_PWM_DUTY_CYCLE, MAX_BLOOD_PUMP_PWM_DUTY_CYCLE ); // Initialize persistent alarm for flow sensor - initPersistentAlarm( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK, 0, BP_FLOW_VS_SPEED_PERSIST ); initPersistentAlarm( ALARM_ID_BLOOD_PUMP_OFF_CHECK, 0, BP_OFF_ERROR_PERSIST ); initPersistentAlarm( ALARM_ID_BLOOD_PUMP_MOTOR_SPEED_CHECK, 0, BP_MOTOR_SPEED_ERROR_PERSIST ); initPersistentAlarm( ALARM_ID_BLOOD_PUMP_ROTOR_SPEED_CHECK, 0, BP_ROTOR_SPEED_ERROR_PERSIST ); initPersistentAlarm( ALARM_ID_BLOOD_PUMP_MC_DIRECTION_CHECK, 0, BP_DIRECTION_ERROR_PERSIST ); initPersistentAlarm( ALARM_ID_BLOOD_PUMP_ROTOR_SPEED_TOO_HIGH, 0, BP_MAX_ROTOR_SPEED_ERROR_PERSIST ); initPersistentAlarm( ALARM_ID_BLOOD_PUMP_MC_CURRENT_CHECK, 0, BP_MAX_CURR_ERROR_DURATION_MS ); - initPersistentAlarm( ALARM_ID_BLOOD_FLOW_SIGNAL_STRENGTH_TOO_LOW, FLOW_SIG_STRGTH_ALARM_PERSIST, FLOW_SIG_STRGTH_ALARM_PERSIST ); - initPersistentAlarm( ALARM_ID_HD_BP_FLOW_READ_TIMEOUT_ERROR, 0, BLOOD_FLOW_FAST_READ_TO_PERSIST ); - initPersistentAlarm( ALARM_ID_HD_BP_FLOW_SLOW_READ_TIMEOUT_ERROR, 0, BLOOD_FLOW_SLOW_READ_TO_PERSIST ); - initPersistentAlarm( ALARM_ID_HD_BP_FLOW_SENSOR_ERROR, 0, BLOOD_FLOW_COMM_ERROR_PERSIST ); + initPersistentAlarm( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK, 0, BP_FLOW_VS_SPEED_PERSIST ); initPersistentAlarm( ALARM_ID_HD_BLOOD_FLOW_OUT_OF_RANGE, 0, BP_MAX_FLOW_RATE_OUT_OF_RANGE_PERSIST ); } @@ -286,7 +280,7 @@ if ( flowRate <= MAX_SET_BLOOD_FLOW_RATE ) #endif { - resetBloodFlowMovingAverage(); + resetBloodPumpRPMMovingAverage(); targetBloodFlowRate = ( dir == MOTOR_DIR_FORWARD ? (S32)flowRate : (S32)flowRate * -1 ); bloodPumpDirection = dir; bloodPumpControlMode = mode; @@ -300,13 +294,15 @@ { bloodPumpState = BLOOD_PUMP_RAMPING_DOWN_STATE; } - break; + break; + case BLOOD_PUMP_RAMPING_DOWN_STATE: // See if we need to reverse direction of ramp if ( bloodPumpPWMDutyCyclePct > bloodPumpPWMDutyCyclePctSet ) { bloodPumpState = BLOOD_PUMP_RAMPING_UP_STATE; } - break; + break; + case BLOOD_PUMP_CONTROL_TO_TARGET_STATE: // Start ramp to new target in appropriate direction if ( bloodPumpPWMDutyCyclePctSet > bloodPumpPWMDutyCyclePct ) { @@ -316,7 +312,8 @@ { bloodPumpState = BLOOD_PUMP_RAMPING_UP_STATE; } - break; + break; + default: // Ok - not all states need to be handled here break; @@ -334,6 +331,32 @@ return result; } +/*********************************************************************//** + * @brief + * The calcBloodFlow function calculates an estimated blood flow rate from + * blood pump speed, arterial pressure and tubing wear (measured from count + * of rotor revolutions since cartridge install). + * @details Inputs: bloodPumpRotorCounter, arterial pressure + * @details Outputs: none + * @return calculated blood flow rate (mL/min) + *************************************************************************/ +static F32 calcBloodFlow( void ) +{ + F32 artPres = getLongFilteredArterialPressure(); + F32 rotSpd = filteredBloodPumpSpeed / BP_GEAR_RATIO; +#ifndef WORN_OUT_CARTRIDGE + U32 r = getBloodPumpRotorCount(); + U32 rotCnt = CAP( r, BP_MAX_ROTOR_COUNT_FOR_WEAR ); +#else + U32 rotCnt = BP_MAX_ROTOR_COUNT_FOR_WEAR; +#endif + F32 wear = BP_FLOW_WEAR_A_TERM * (F32)rotCnt + BP_FLOW_WEAR_B_TERM; + F32 alpha = wear * artPres + BP_FLOW_ALPHA_Y_INTERCEPT; + F32 flow = alpha * BP_ML_PER_ROTOR_REV * rotSpd; + + return flow; +} + /*********************************************************************//** * @brief * The signalBloodPumpHardStop function stops the blood pump immediately. @@ -357,7 +380,7 @@ * hall sensor detection. Calculates rotor speed (in RPM). Stops pump if * there is a pending request to home the pump. * @details Inputs: bpRotorRevStartTime, bpStopAtHomePosition - * @details Outputs: bpRotorRevStartTime, bloodPumpRotorSpeedRPM + * @details Outputs: bpRotorRevStartTime, bloodPumpRotorSpeedRPM, bloodPumpRotorCounter * @return none *************************************************************************/ void signalBloodPumpRotorHallSensor( void ) @@ -366,7 +389,7 @@ U32 deltaTime = calcTimeBetween( bpRotorRevStartTime, rotTime ); // Increment rotor counter - bloodPumpRotorCounter++; + bloodPumpRotorCounter.data++; // Calculate rotor speed (in RPM) bloodPumpRotorSpeedRPM.data = ( 1.0 / (F32)deltaTime ) * (F32)MS_PER_SECOND * (F32)SEC_PER_MIN; @@ -424,7 +447,14 @@ *************************************************************************/ U32 getBloodPumpRotorCount( void ) { - return bloodPumpRotorCounter; + U32 result = bloodPumpRotorCounter.data; + + if ( OVERRIDE_KEY == bloodPumpRotorCounter.override ) + { + result = bloodPumpRotorCounter.ovData; + } + + return result; } /*********************************************************************//** @@ -438,6 +468,20 @@ BOOL isBloodPumpRunning( void ) { return isBloodPumpOn; +} + +/*********************************************************************//** + * @brief + * The resetBloodPumpRotorCount function resets the blood pump rotor counter + * that is a proxy for cartridge wear. Call this function after a new cartridge + * has been installed. + * @details Inputs: none + * @details Outputs: bloodPumpRotorCounter + * @return none + *************************************************************************/ +void resetBloodPumpRotorCount( void ) +{ + bloodPumpRotorCounter.data = 0; } /*********************************************************************//** @@ -450,61 +494,15 @@ *************************************************************************/ void execBloodFlowMonitor( void ) { - // Check if a new calibration is available - if ( TRUE == isNewCalibrationRecordAvailable() ) - { - // Get the new calibration data and check its validity - processCalibrationData(); - } - HD_OP_MODE_T opMode = getCurrentOperationMode(); U16 bpRPM = getIntADCReading( INT_ADC_BLOOD_PUMP_SPEED ); U16 bpmA = getIntADCReading( INT_ADC_BLOOD_PUMP_MOTOR_CURRENT ); - U08 fpReadCtr = getFPGABloodFlowFastPacketReadCounter(); - U08 spReadCtr = getFPGABloodFlowSlowPacketReadCounter(); - U08 flowErrorCtr = getFPGABloodFlowErrorCounter(); - U08 flowStatus = getFPGABloodFlowMeterStatus(); - F32 fpgaBloodFlow = getFPGABloodFlow(); - F32 bpFlow = pow(fpgaBloodFlow, 4) * bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].fourthOrderCoeff + - pow(fpgaBloodFlow, 3) * bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].thirdOrderCoeff + - pow(fpgaBloodFlow, 2) * bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].secondOrderCoeff + - fpgaBloodFlow * bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].gain + - bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].offset; - -#ifndef DISABLE_PUMP_FLOW_CHECKS - if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_HD_BP_FLOW_SENSOR_ERROR, ( flowErrorCtr != lastBloodFlowCommErrorCount ) ) ) - { - activateAlarmNoData( ALARM_ID_HD_BP_FLOW_SENSOR_ERROR ); - } - if ( flowStatus != BFM_SENSOR_CONNECTED_STATUS ) - { - SET_ALARM_WITH_1_U32_DATA( ALARM_ID_HD_BLOOD_FLOW_STATUS_SELF_TEST_FAILURE, (U32)flowStatus ); - } - lastBloodFlowCommErrorCount = flowErrorCtr; -#endif - -#ifndef DISABLE_FPGA_COUNTER_CHECKS - // Check for stale flow reading - if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_HD_BP_FLOW_READ_TIMEOUT_ERROR, ( fpReadCtr == lastBloodFlowFastPacketReadCtr ) ) ) - { - activateAlarmNoData( ALARM_ID_HD_BP_FLOW_READ_TIMEOUT_ERROR ); - } - if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_HD_BP_FLOW_SLOW_READ_TIMEOUT_ERROR, ( spReadCtr == lastBloodFlowSlowPacketReadCtr ) ) ) - { - activateAlarmNoData( ALARM_ID_HD_BP_FLOW_SLOW_READ_TIMEOUT_ERROR ); - } -#endif - - // Record flow read counters for next time around - lastBloodFlowFastPacketReadCtr = fpReadCtr; - lastBloodFlowSlowPacketReadCtr = spReadCtr; - adcBloodPumpMCSpeedRPM.data = (F32)(SIGN_FROM_12_BIT_VALUE(bpRPM)) * BP_SPEED_ADC_TO_RPM_FACTOR; adcBloodPumpMCCurrentmA.data = (F32)(SIGN_FROM_12_BIT_VALUE(bpmA)) * BP_CURRENT_ADC_TO_MA_FACTOR; - bloodFlowSignalStrength.data = getFPGABloodFlowSignalStrength(); - filterBloodFlowReadings( bpFlow ); + filterBloodPumpRPMReadings( getMeasuredBloodPumpMCSpeed() ); + measuredBloodFlowRate.data = calcBloodFlow(); // Pressure and rotor speed already filtered as inputs to calc, so no need to filter flow any further // Calculate blood pump motor speed/direction from hall sensor count updateBloodPumpSpeedAndDirectionFromHallSensors(); @@ -518,11 +516,9 @@ checkBloodPumpMCCurrent(); // Check pump speeds and flow checkBloodPumpSpeeds(); - checkBloodPumpFlowAgainstSpeed(); + checkBloodPumpFlowRate(); // Check for home position, zero/low speed checkBloodPumpRotor(); - // Check flow sensor signal strength - checkBloodFlowSensorSignalStrength(); } // Publish blood flow data on interval @@ -613,7 +609,7 @@ // Have we reached end of ramp up? else if ( bloodPumpPWMDutyCyclePctSet >= bloodPumpPWMDutyCyclePct ) { - resetBloodFlowMovingAverage(); + resetBloodPumpRPMMovingAverage(); bloodPumpPWMDutyCyclePctSet = bloodPumpPWMDutyCyclePct; resetPIController( PI_CONTROLLER_ID_BLOOD_FLOW, bloodPumpPWMDutyCyclePctSet ); bloodPumpControlModeSet = bloodPumpControlMode; @@ -652,7 +648,7 @@ // Have we reached end of ramp down? else if ( bloodPumpPWMDutyCyclePctSet <= bloodPumpPWMDutyCyclePct ) { - resetBloodFlowMovingAverage(); + resetBloodPumpRPMMovingAverage(); bloodPumpPWMDutyCyclePctSet = bloodPumpPWMDutyCyclePct; resetPIController( PI_CONTROLLER_ID_BLOOD_FLOW, bloodPumpPWMDutyCyclePctSet ); bloodPumpControlModeSet = bloodPumpControlMode; @@ -769,6 +765,18 @@ SET_ALARM_WITH_2_U32_DATA( ALARM_ID_HD_SOFTWARE_FAULT, SW_FAULT_ID_BLOOD_FLOW_INVALID_BLOOD_PUMP_DIRECTION, dir ) break; } +} + +/*********************************************************************//** + * @brief + * The getTargetBloodFlowRate function gets the target blood flow rate. + * @details Inputs: targetBloodFlowRate + * @details Outputs: none + * @return the current target blood flow rate (in mL/min). + *************************************************************************/ +S32 getTargetBloodFlowRate( void ) +{ + return targetBloodFlowRate; } /*********************************************************************//** @@ -791,26 +799,6 @@ return result; } -/*********************************************************************//** - * @brief - * The getMeasuredBloodFlowSignalStrength function gets the measured blood flow - * signal strength. - * @details Inputs: bloodFlowSignalStrength - * @details Outputs: none - * @return the current blood flow signal strength (in %). - *************************************************************************/ -F32 getMeasuredBloodFlowSignalStrength( void ) -{ - F32 result = bloodFlowSignalStrength.data; - - if ( OVERRIDE_KEY == bloodFlowSignalStrength.override ) - { - result = bloodFlowSignalStrength.ovData; - } - - return result; -} - /*********************************************************************//** * @brief * The getMeasuredBloodPumpRotorSpeed function gets the measured blood flow @@ -914,55 +902,52 @@ payload.measMCSpd = getMeasuredBloodPumpMCSpeed(); payload.measMCCurr = getMeasuredBloodPumpMCCurrent(); payload.pwmDC = bloodPumpPWMDutyCyclePctSet * FRACTION_TO_PERCENT_FACTOR; - payload.flowSigStrength = getMeasuredBloodFlowSignalStrength() * FRACTION_TO_PERCENT_FACTOR; - broadcastBloodFlowData( &payload ); + payload.rotorCount = getBloodPumpRotorCount(); + broadcastData( MSG_ID_BLOOD_FLOW_DATA, COMM_BUFFER_OUT_CAN_HD_BROADCAST, (U08*)&payload, sizeof( BLOOD_PUMP_STATUS_PAYLOAD_T ) ); bloodFlowDataPublicationTimerCounter = 0; } } +/*********************************************************************//** + * @brief + * The resetBloodPumpRPMMovingAverage function re-initializes the pump speed + * moving average sample buffer. + * @details Inputs: none + * @details Outputs: rpmReadingsTotal, rpmReadingsIdx, rpmReadingsCount all set to zero. + * @return none + *************************************************************************/ +static void resetBloodPumpRPMMovingAverage( void ) +{ + rpmReadingsIdx = 0; + rpmReadingsCount = 0; + rpmReadingsTotal = 0.0; + filteredBloodPumpSpeed = 0.0; +} + +/*********************************************************************//** + * @brief + * The filterBloodPumpRPMReadings function adds a new pump speed sample to + * the filter. + * @details Inputs: none + * @details Outputs: rpmReadings[], rpmReadingsIdx, rpmReadingsCount, rpmReadingsTotal + * @param rpm newest blood pump speed (in RPM) sample to add to filter + * @return none + *************************************************************************/ +static void filterBloodPumpRPMReadings( F32 rpm ) +{ + if ( rpmReadingsCount >= SIZE_OF_ROLLING_AVG ) + { + rpmReadingsTotal -= rpmReadings[ rpmReadingsIdx ]; + } + rpmReadings[ rpmReadingsIdx ] = rpm; + rpmReadingsTotal += rpm; + rpmReadingsIdx = INC_WRAP( rpmReadingsIdx, 0, SIZE_OF_ROLLING_AVG - 1 ); + rpmReadingsCount = INC_CAP( rpmReadingsCount, SIZE_OF_ROLLING_AVG ); + filteredBloodPumpSpeed = rpmReadingsTotal / (F32)rpmReadingsCount; +} + /*********************************************************************//** * @brief - * The resetBloodFlowMovingAverage function re-initializes the blood flow - * moving average sample buffer. - * @details Inputs: none - * @details Outputs: flowReadingsTotal, flowReadingsIdx, flowReadingsCount all set to zero. - * @return none - *************************************************************************/ -static void resetBloodFlowMovingAverage( void ) -{ - flowReadingsIdx = 0; - flowReadingsCount = 0; - flowReadingsTotal = 0.0; - bpControlTimerCounter = 0; -} - -/*********************************************************************//** - * @brief - * The filterBloodFlowReadings function adds a new flow sample to the filter. - * @details Inputs: none - * @details Outputs: flowReadings[], flowReadingsIdx, flowReadingsCount, flowReadingsTotal - * @param flow newest blood flow sample - * @return none - *************************************************************************/ -static void filterBloodFlowReadings( F32 flow ) -{ -#ifndef RAW_FLOW_SENSOR_DATA - if ( flowReadingsCount >= SIZE_OF_ROLLING_AVG ) - { - flowReadingsTotal -= flowReadings[ flowReadingsIdx ]; - } - flowReadings[ flowReadingsIdx ] = flow; - flowReadingsTotal += flow; - flowReadingsIdx = INC_WRAP( flowReadingsIdx, 0, SIZE_OF_ROLLING_AVG - 1 ); - flowReadingsCount = INC_CAP( flowReadingsCount, SIZE_OF_ROLLING_AVG ); - measuredBloodFlowRate.data = flowReadingsTotal / (F32)flowReadingsCount; -#else - measuredBloodFlowRate.data = flow; -#endif -} - -/*********************************************************************//** - * @brief * The updateBloodPumpSpeedAndDirectionFromHallSensors function calculates * the blood pump motor speed and direction from hall sensor counter on * a 1 second interval. @@ -996,7 +981,7 @@ // Keep a running 32-bit edge count used for safety check on volume in some functions delta = u16BiDiffWithWrap( last, bpMotorHallSensorCount ); - bloodPumpMotorEdgeCount += (U16)delta; + bloodPumpMotorEdgeCount += ( delta >= 0 ? (U16)delta : 0 ); // Update last count for next time bpLastMotorHallSensorCounts[ nextIdx ] = bpMotorHallSensorCount; @@ -1033,7 +1018,7 @@ } // If pump is stopped or running very slowly, set rotor speed to zero - if ( TRUE == didTimeout( bpRotorRevStartTime, BP_HOME_TIMEOUT_MS ) ) + if ( TRUE == didTimeout( bpRotorRevStartTime, BP_MAX_ROTOR_HALL_INTERVAL_MS ) ) { bloodPumpRotorSpeedRPM.data = 0.0; } @@ -1055,13 +1040,14 @@ BOOL isDirIncorrect; U08 dirErrorCnt = getFPGABloodPumpHallSensorStatus() & PUMP_DIR_ERROR_COUNT_MASK; +#ifndef DISABLE_PUMP_DIRECTION_CHECKS // Check pump direction error count if ( lastBloodPumpDirectionCount != dirErrorCnt ) { lastBloodPumpDirectionCount = dirErrorCnt; SET_ALARM_WITH_1_U32_DATA( ALARM_ID_HD_PUMP_DIRECTION_STATUS_ERROR, (U32)HD_PUMP_BLOOD_PUMP ) } - +#endif bpMCDir = ( getMeasuredBloodPumpMCSpeed() >= 0.0 ? MOTOR_DIR_FORWARD : MOTOR_DIR_REVERSE ); bpDir = ( getMeasuredBloodPumpSpeed() >= 0.0 ? MOTOR_DIR_FORWARD : MOTOR_DIR_REVERSE ); @@ -1149,52 +1135,10 @@ /*********************************************************************//** * @brief - * The checkBloodPumpFlowAgainstSpeed function checks the measured blood flow - * against the implied flow of the measured pump speed when in treatment mode - * and controlling to target flow. If a sufficient difference persists, a - * flow vs. motor speed check error is triggered. - * @details Inputs: measuredBloodFlowRate, bloodPumpSpeedRPM - * @details Outputs: alarm may be triggered - * @return none - *************************************************************************/ -static void checkBloodPumpFlowAgainstSpeed( void ) -{ - F32 flow = getMeasuredBloodFlowRate(); - - // Range check on measure BP flow rate. -#ifndef DISABLE_PUMP_FLOW_CHECKS - if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_HD_BLOOD_FLOW_OUT_OF_RANGE, ( flow > BP_MAX_FLOW_RATE ) || ( flow < BP_MIN_FLOW_RATE ) ) ) - { - SET_ALARM_WITH_1_F32_DATA( ALARM_ID_HD_BLOOD_FLOW_OUT_OF_RANGE, flow ); - } -#endif - - // Flow vs. speed check only performed while in treatment mode and while we are in control to target state - if ( ( MODE_TREA == getCurrentOperationMode() ) && ( BLOOD_PUMP_CONTROL_TO_TARGET_STATE == bloodPumpState ) ) - { - F32 speed = getMeasuredBloodPumpSpeed(); - F32 impliedSpeed = ( flow / (F32)ML_PER_LITER ) * BP_REV_PER_LITER * BP_GEAR_RATIO; - F32 delta = fabs( speed - impliedSpeed ); - - if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK, delta > BP_MAX_FLOW_VS_SPEED_DIFF_RPM ) ) - { -#ifndef DISABLE_PUMP_SPEED_CHECKS - SET_ALARM_WITH_2_F32_DATA( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK, flow, speed ); -#endif - } - } - else - { - resetPersistentAlarmTimer( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK ); - } -} - -/*********************************************************************//** - * @brief * The checkBloodPumpMCCurrent function checks the measured MC current vs. * the set state of the blood pump (stopped or running). - * @details Inputs: - * @details Outputs: + * @details Inputs: BP motor controller measured current. + * @details Outputs: Alarm triggered it current too high. * @return none *************************************************************************/ static void checkBloodPumpMCCurrent( void ) @@ -1205,7 +1149,7 @@ // Check blood pump current during running state BOOL const isRunningMCCurrentBad = ( BLOOD_PUMP_OFF_STATE != bloodPumpState ) && ( bpCurr > BP_MAX_CURR_WHEN_RUNNING_MA ); - if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK, isOffMCCurrentBad || isRunningMCCurrentBad ) ) + if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_BLOOD_PUMP_MC_CURRENT_CHECK, isOffMCCurrentBad || isRunningMCCurrentBad ) ) { #ifndef DISABLE_MOTOR_CURRENT_CHECKS SET_ALARM_WITH_1_F32_DATA( ALARM_ID_BLOOD_PUMP_MC_CURRENT_CHECK, bpCurr ); @@ -1215,76 +1159,41 @@ /*********************************************************************//** * @brief - * The checkBloodFlowSensorSignalStrength function checks the measured blood - * flow sensor signal strength is sufficient for accurate flow sensing. - * @details Inputs: - * @details Outputs: + * The checkBloodPumpFlowRate function checks the measured blood flow rate + * is in range. + * @details Inputs: measuredBloodFlowRate + * @details Outputs: alarm may be triggered * @return none *************************************************************************/ -static void checkBloodFlowSensorSignalStrength( void ) +static void checkBloodPumpFlowRate( void ) { #ifndef DISABLE_PUMP_FLOW_CHECKS - HD_OP_MODE_T opMode = getCurrentOperationMode(); + F32 flow = getMeasuredBloodFlowRate(); - // Check flow sensor signal strength when appropriate TODO - in pre-treatment, must be far enough along for fluid to be in tubing - if ( MODE_TREA == opMode || ( MODE_PRET == opMode && FALSE ) ) + // Range check on measure BP flow rate. + if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_HD_BLOOD_FLOW_OUT_OF_RANGE, ( flow > BP_MAX_FLOW_RATE ) || ( flow < BP_MIN_FLOW_RATE ) ) ) { - F32 sigStrength = getMeasuredBloodFlowSignalStrength(); - BOOL outOfRange = ( sigStrength < MIN_FLOW_SIG_STRENGTH ? TRUE : FALSE ); + SET_ALARM_WITH_1_F32_DATA( ALARM_ID_HD_BLOOD_FLOW_OUT_OF_RANGE, flow ); + } - if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_BLOOD_FLOW_SIGNAL_STRENGTH_TOO_LOW, outOfRange ) ) + // Flow vs. speed check only performed while in treatment mode and while we are in control to target state + if ( ( MODE_TREA == getCurrentOperationMode() ) && ( BLOOD_PUMP_CONTROL_TO_TARGET_STATE == bloodPumpState ) ) + { + F32 speed = getMeasuredBloodPumpSpeed(); + F32 impliedSpeed = ( (F32)targetBloodFlowRate / (F32)ML_PER_LITER ) * BP_REV_PER_LITER * BP_GEAR_RATIO; + F32 delta = fabs( speed - impliedSpeed ); + + if ( TRUE == isPersistentAlarmTriggered( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK, delta > BP_MAX_FLOW_VS_SPEED_DIFF_RPM ) ) { - SET_ALARM_WITH_2_F32_DATA( ALARM_ID_BLOOD_FLOW_SIGNAL_STRENGTH_TOO_LOW, sigStrength, MIN_FLOW_SIG_STRENGTH ); + SET_ALARM_WITH_2_F32_DATA( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK, flow, speed ); } } -#endif -} - -/*********************************************************************//** - * @brief - * The processCalibrationData function gets the calibration data and makes - * sure it is valid by checking the calibration date. The calibration date - * should not be 0. - * @details Inputs: none - * @details Outputs: bloodFlowCalRecord - * @return TRUE if the calibration record is valid, otherwise FALSE - *************************************************************************/ -static BOOL processCalibrationData( void ) -{ - BOOL status = TRUE; - - // Get the calibration record from NVDataMgmt - HD_FLOW_SENSORS_CAL_RECORD_T calData = getHDFlowSensorsCalibrationRecord(); - - // Check if the calibration data that was received from NVDataMgmt is legitimate - // The calibration date item should not be zero. If the calibration date is 0, - // then the blood flow sensors data is not stored in the NV memory or it was corrupted. - if ( 0 == calData.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].calibrationTime ) + else { -#ifndef SKIP_CAL_CHECK - activateAlarmNoData( ALARM_ID_HD_BLOOD_FLOW_INVALID_CAL_RECORD ); - status = FALSE; -#endif + resetPersistentAlarmTimer( ALARM_ID_BLOOD_PUMP_FLOW_VS_MOTOR_SPEED_CHECK ); } - - // The calibration data was valid, update the local copy - bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].fourthOrderCoeff = - calData.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].fourthOrderCoeff; - - bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].thirdOrderCoeff = - calData.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].thirdOrderCoeff; - - bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].secondOrderCoeff = - calData.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].secondOrderCoeff; - - bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].gain = - calData.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].gain; - - bloodFlowCalRecord.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].offset = - calData.hdFlowSensors[ CAL_DATA_HD_BLOOD_FLOW_SENSOR ].offset; - - return status; -} +#endif +} /*********************************************************************//** * @brief @@ -1295,28 +1204,10 @@ * @return the current state of the BloodFlow self-test. *************************************************************************/ SELF_TEST_STATUS_T execBloodFlowTest( void ) -{ - SELF_TEST_STATUS_T result = SELF_TEST_STATUS_IN_PROGRESS; - U08 const bfmStatus = getFPGABloodFlowMeterStatus(); +{ + SELF_TEST_STATUS_T result = SELF_TEST_STATUS_PASSED; - // Retrieve blood flow sensor calibration data and check for sensor connected status - if ( BFM_SENSOR_PARAM_CORRUPT_STATUS != bfmStatus ) - { - BOOL calStatus = processCalibrationData(); - - if ( TRUE == calStatus ) - { - result = SELF_TEST_STATUS_PASSED; - } - else - { - result = SELF_TEST_STATUS_FAILED; - } - } - else - { - SET_ALARM_WITH_1_U32_DATA( ALARM_ID_HD_BLOOD_FLOW_STATUS_SELF_TEST_FAILURE, (U32)bfmStatus ); - } + // TODO - anything to test here? return result; } @@ -1637,44 +1528,44 @@ /*********************************************************************//** * @brief - * The testSetMeasuredBloodFlowSignalStrengthOverride function overrides the measured - * blood flow signal strength. + * The testSetBloodPumpRotorCountOverride function overrides the blood pump + * rotor counter value. * @details Inputs: none - * @details Outputs: bloodFlowSignalStrength - * @param value override measured blood flow signal strength (in %) + * @details Outputs: bloodPumpRotorCounter + * @param value override blood pump rotor counter value * @return TRUE if override successful, FALSE if not *************************************************************************/ -BOOL testSetMeasuredBloodFlowSignalStrengthOverride( F32 value ) +BOOL testSetBloodPumpRotorCountOverride( U32 value ) { BOOL result = FALSE; if ( TRUE == isTestingActivated() ) { result = TRUE; - bloodFlowSignalStrength.ovData = value / 100.0; - bloodFlowSignalStrength.override = OVERRIDE_KEY; + bloodPumpRotorCounter.ovData = value; + bloodPumpRotorCounter.override = OVERRIDE_KEY; } return result; } /*********************************************************************//** * @brief - * The testResetMeasuredBloodFlowSignalStrengthOverride function resets the override - * of the measured blood flow signal strength. + * The testResetBloodPumpRotorCountOverride function resets the override + * of the blood pump rotor counter. * @details Inputs: none - * @details Outputs: bloodFlowSignalStrength + * @details Outputs: bloodPumpRotorCounter * @return TRUE if reset successful, FALSE if not *************************************************************************/ -BOOL testResetMeasuredBloodFlowSignalStrengthOverride( void ) +BOOL testResetBloodPumpRotorCountOverride( void ) { BOOL result = FALSE; if ( TRUE == isTestingActivated() ) { result = TRUE; - bloodFlowSignalStrength.override = OVERRIDE_RESET; - bloodFlowSignalStrength.ovData = bloodFlowSignalStrength.ovInitData; + bloodPumpRotorCounter.override = OVERRIDE_RESET; + bloodPumpRotorCounter.ovData = bloodPumpRotorCounter.ovInitData; } return result;