-
Notifications
You must be signed in to change notification settings - Fork 0
Current sensing #11
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Open
changxu-liu
wants to merge
4
commits into
main
Choose a base branch
from
current_sensor_conversion
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Current sensing #11
Changes from all commits
Commits
Show all changes
4 commits
Select commit
Hold shift + click to select a range
2e98299
current sensing code
changxu-liu 7405b78
fix copy paste errors in current sensing header
changxu-liu 0eed0ca
make initial offset calculation average of multiple samples
changxu-liu a5c8e7d
remove underscore between current sensing
changxu-liu File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
Binary file not shown.
83 changes: 83 additions & 0 deletions
83
firmware/PowerDistributionUnit_Mk1/core/inc/PDU_Mk1_CurrentSensing.h
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,83 @@ | ||
| // PDU_Mk1_CurrentSensing.h | ||
| // ---------------------------------------------------------------------------- | ||
| // Stuff for output current sensing on BBPDU. | ||
|
|
||
| #pragma once | ||
|
|
||
| // INCLUDES ------------------------------------------------------------------- | ||
|
|
||
| #include "stm32xx_hal.h" | ||
|
|
||
| // BBPDU peripherals | ||
| #include "PDU_Mk1.h" | ||
| #include "PDU_Mk1_Pins.h" | ||
|
|
||
| // drivers | ||
| #include "ADS131M08-Q1.h" | ||
| #include "ACS3704x-010B3.h" | ||
|
|
||
| // DEFINES -------------------------------------------------------------------- | ||
|
|
||
| #define CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES 20 // number of samples used for calculating no-current offset | ||
| #define CURRENT_SENSING_OFFSET_CALC_SAMPLE_DELAY_MS 100 // [ms] delay between samples for calculating no-current offset | ||
|
|
||
| // VARIABLE DECLARATIONS ------------------------------------------------------ | ||
|
|
||
| extern SPI_HandleTypeDef hspi2; | ||
| extern SemaphoreHandle_t spi2_mutex; | ||
| extern StaticSemaphore_t spi2_mutex_buffer; | ||
| extern SemaphoreHandle_t spi2_done_sem; | ||
|
|
||
| extern SPI_HandleTypeDef hspi3; | ||
| extern SemaphoreHandle_t spi3_mutex; | ||
| extern StaticSemaphore_t spi3_mutex_buffer; | ||
| extern SemaphoreHandle_t spi3_done_sem; | ||
|
|
||
| extern float currents[PDU_MK1_NUM_CHANNELS]; | ||
| extern float current_adc_v_offset[PDU_MK1_NUM_CHANNELS]; | ||
|
|
||
| // FUNCTIONS ------------------------------------------------------------------ | ||
|
|
||
| /** | ||
| * @brief Initializes current sensing functions (ADCs, initial calibration-TODO). | ||
| * Must be called while all outputs are disabled. | ||
| * @param None | ||
| * @retval bool: true if successful, false otherwise | ||
| */ | ||
| bool PDU_Mk1_CurrentSensing_Init(); | ||
|
|
||
| /** | ||
| * @brief Initializes ADC_SNS1 for current sensing use. | ||
| * @param None | ||
| * @retval ADS131M08Q1 Status (ADS131M08Q1_🙂 if successful) | ||
| */ | ||
| ADS131M08Q1_Status_t PDU_Mk1_Init_ADC_SNS0(); | ||
|
|
||
| /** | ||
| * @brief Initializes ADC_SNS1 for current sensing use. | ||
| * @param None | ||
| * @retval ADS131M08Q1 Status (ADS131M08Q1_🙂 if successful) | ||
| */ | ||
| ADS131M08Q1_Status_t PDU_Mk1_Init_ADC_SNS1(); | ||
|
|
||
| /** | ||
| * @brief Reads current sensing ADCs under zero-current conditions to get offset. | ||
| * Must only be run while all high-side switches are off. | ||
| * @param None | ||
| * @retval bool: true if successful, false otherwise | ||
| */ | ||
| bool PDU_Mk1_CurrentSensing_CollectOffsets(); | ||
|
|
||
| /** | ||
| * @brief Reads sample from current sensing ADCs and calculates current conversion. | ||
| * @param None | ||
| * @retval bool: true if successful, false otherwise | ||
| */ | ||
| bool PDU_Mk1_CurrentSensing_ReadCurrents(); | ||
|
|
||
| /** | ||
| * @brief Returns pointer to array where last currents sample is stored. | ||
| * @param None | ||
| * @retval float pointer to currents array | ||
| */ | ||
| float* PDU_Mk1_CurrentSensing_GetCurrentsPtr(); |
52 changes: 0 additions & 52 deletions
52
firmware/PowerDistributionUnit_Mk1/core/inc/PDU_Mk1_Current_Sensing.h
This file was deleted.
Oops, something went wrong.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,14 +1,14 @@ | ||
| // PDU_Mk1_Current_Sensing.c | ||
| // PDU_Mk1_CurrentSensing.c | ||
|
|
||
| #include "PDU_Mk1_Current_Sensing.h" | ||
| #include "PDU_Mk1_CurrentSensing.h" | ||
|
|
||
| ADS131M08Q1_HandleTypeDef adc_sns1; | ||
| ADS131M08Q1_HandleTypeDef adc_sns0; | ||
|
|
||
| float currents[PDU_MK1_NUM_CHANNELS] = {0}; | ||
| float current_offset[PDU_MK1_NUM_CHANNELS] = {0}; | ||
| float current_adc_v_offset[PDU_MK1_NUM_CHANNELS] = {0}; | ||
|
|
||
| bool PDU_Mk1_Current_Sensing_Init() | ||
| bool PDU_Mk1_CurrentSensing_Init() | ||
| { | ||
| if(PDU_Mk1_Init_ADC_SNS0() != ADS131M08Q1_🙂) | ||
| { | ||
|
|
@@ -20,6 +20,11 @@ bool PDU_Mk1_Current_Sensing_Init() | |
| return false; | ||
| } | ||
|
|
||
| if(PDU_Mk1_CurrentSensing_CollectOffsets() != true) | ||
| { | ||
| return false; | ||
| } | ||
|
|
||
| return true; | ||
| } | ||
|
|
||
|
|
@@ -74,8 +79,72 @@ ADS131M08Q1_Status_t PDU_Mk1_Init_ADC_SNS1() | |
| adc_sns1.config.fsr = ADS131M08Q1_INTERNAL_REFERENCE_V; | ||
| adc_sns1.config.powermode = ADS131M08Q1_CONFIG_POWERMODE_DEFAULT; | ||
|
|
||
| // channel 0 reads about 0.24 V high for some reason (rev A only) | ||
| // adc_sns1.config.ch_configs[0].offset_cal = ADS131M08Q1_CalcOffsetCalRegValue(&adc_sns1, -0.24); | ||
|
|
||
| return ADS131M08Q1_Init(&adc_sns1); | ||
| } | ||
|
|
||
| bool PDU_Mk1_CurrentSensing_CollectOffsets() | ||
|
changxu-liu marked this conversation as resolved.
|
||
| { | ||
| float adc_results_sns0[CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES][ADS131M08Q1_NUM_CHANNELS] = {0}; | ||
| float adc_results_sns1[CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES][ADS131M08Q1_NUM_CHANNELS] = {0}; | ||
|
|
||
| for(uint8_t sample = 0; sample < CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES; sample++) | ||
| { | ||
| if(ADS131M08Q1_ReadConversionResults(&adc_sns0, adc_results_sns0[sample]) != ADS131M08Q1_🙂) | ||
| { | ||
| return false; | ||
| } | ||
|
|
||
| if(ADS131M08Q1_ReadConversionResults(&adc_sns1, adc_results_sns1[sample]) != ADS131M08Q1_🙂) | ||
| { | ||
| return false; | ||
| } | ||
|
|
||
| if(sample != CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES-1) | ||
| { | ||
| vTaskDelay(pdMS_TO_TICKS(CURRENT_SENSING_OFFSET_CALC_SAMPLE_DELAY_MS)); | ||
| } | ||
| } | ||
|
|
||
| for(uint8_t ch = 0; ch < ADS131M08Q1_NUM_CHANNELS; ch++) | ||
| { | ||
| for(uint8_t sample = 0; sample < CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES; sample++) | ||
| { | ||
| current_adc_v_offset[ch] += -1.0*adc_results_sns1[sample][(ADS131M08Q1_NUM_CHANNELS-1)-ch]; | ||
| current_adc_v_offset[ADS131M08Q1_NUM_CHANNELS+ch] += -1.0*adc_results_sns0[sample][(ADS131M08Q1_NUM_CHANNELS-1)-ch]; | ||
|
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. change to -1.0f |
||
| } | ||
|
|
||
| current_adc_v_offset[ch] /= (float) CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES; | ||
| current_adc_v_offset[ADS131M08Q1_NUM_CHANNELS+ch] /= (float) CURRENT_SENSING_OFFSET_CALC_NUMSAMPLES; | ||
| } | ||
|
|
||
| return true; | ||
| } | ||
|
|
||
| bool PDU_Mk1_CurrentSensing_ReadCurrents() | ||
| { | ||
| float adc_results_sns0[ADS131M08Q1_NUM_CHANNELS] = {0}; | ||
| float adc_results_sns1[ADS131M08Q1_NUM_CHANNELS] = {0}; | ||
|
|
||
| if(ADS131M08Q1_ReadConversionResults(&adc_sns0, adc_results_sns0) != ADS131M08Q1_🙂) | ||
| { | ||
| return false; | ||
| } | ||
|
|
||
| if(ADS131M08Q1_ReadConversionResults(&adc_sns1, adc_results_sns1) != ADS131M08Q1_🙂) | ||
| { | ||
| return false; | ||
| } | ||
|
|
||
| for(uint8_t i = 0; i < ADS131M08Q1_NUM_CHANNELS; i++) | ||
| { | ||
| currents[i] = ACS3704x_010B3_Current_Conversion_QVOCentered(adc_results_sns1[(ADS131M08Q1_NUM_CHANNELS-1)-i]+current_adc_v_offset[i]); | ||
| currents[ADS131M08Q1_NUM_CHANNELS+i] = ACS3704x_010B3_Current_Conversion_QVOCentered(adc_results_sns0[(ADS131M08Q1_NUM_CHANNELS-1)-i]+current_adc_v_offset[ADS131M08Q1_NUM_CHANNELS+i]); | ||
| } | ||
|
|
||
| return true; | ||
| } | ||
|
|
||
| float* PDU_Mk1_CurrentSensing_GetCurrentsPtr() | ||
| { | ||
| return currents; | ||
| } | ||
Oops, something went wrong.
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.