Skip to content

Commit 8cd7233

Browse files
author
Owen
authoredMay 6, 2020
Merge pull request #163 from sparkfun/release-candidate
2 parents d6997ac + f3a2d0a commit 8cd7233

File tree

7 files changed

+96
-50
lines changed

7 files changed

+96
-50
lines changed
 

‎cores/arduino/ard_sup/analog/ap3_analog.cpp

+83-41
Original file line numberDiff line numberDiff line change
@@ -121,15 +121,16 @@ static const uint8_t outcfg_tbl[32][4] =
121121

122122
#define AP3_MAX_ANALOG_WRITE_WIDTH 0x0000FFFF
123123

124-
uint16_t _analogBits = 10; //10-bit by default
125-
uint8_t _analogWriteBits = 8; // 8-bit by default for writes
126-
uint8_t _servoWriteBits = 8; // 8-bit by default for writes
124+
uint16_t _analogBits = 10; //10-bit by default
125+
uint8_t _analogWriteBits = 8; // 8-bit by default for writes
126+
uint8_t _servoWriteBits = 8; // 8-bit by default for writes
127127
static bool ap3_adc_initialized = false; // flag to show if the ADC has been initialized
128128
static uint32_t _analogWriteWidth = 0x0000FFFF;
129129

130130
uint16_t analogRead(uint8_t pinNumber)
131131
{
132-
if(!ap3_adc_initialized){
132+
if (!ap3_adc_initialized)
133+
{
133134
ap3_adc_setup();
134135
ap3_adc_initialized = true;
135136
}
@@ -222,6 +223,35 @@ uint16_t analogRead(uint8_t pinNumber)
222223
}
223224
}
224225

226+
//Returns the internal temperature of the Apollo3
227+
float getInternalTemp()
228+
{
229+
const float fReferenceVoltage = 2.0;
230+
float fADCTempDegreesC = 0.0;
231+
232+
uint16_t internalTemp = analogRead(ADC_INTERNAL_TEMP); //Read internal temp sensor channel
233+
234+
//
235+
// Convert and scale the temperature.
236+
// Temperatures are in Fahrenheit range -40 to 225 degrees.
237+
// Voltage range is 0.825V to 1.283V
238+
// First get the ADC voltage corresponding to temperature.
239+
//
240+
float fADCTempVolts = ((float)internalTemp) * fReferenceVoltage / ((float)(pow(2, _analogBits)));
241+
242+
float fVT[3];
243+
fVT[0] = fADCTempVolts;
244+
fVT[1] = 0.0f;
245+
fVT[2] = -123.456;
246+
uint32_t ui32Retval = am_hal_adc_control(g_ADCHandle, AM_HAL_ADC_REQ_TEMP_CELSIUS_GET, fVT);
247+
if (ui32Retval == AM_HAL_STATUS_SUCCESS)
248+
{
249+
fADCTempDegreesC = fVT[1]; // Get the temperature
250+
}
251+
252+
return (fADCTempDegreesC);
253+
}
254+
225255
//Power down ADC. Comes from adc_lpmode2.c example from Ambiq SDK
226256
bool power_adc_disable()
227257
{
@@ -508,19 +538,21 @@ ap3_err_t ap3_pwm_output(uint8_t pin, uint32_t th, uint32_t fw, uint32_t clk)
508538

509539
// if timer is running wait for timer value to roll over (will indicate that at least one pulse has been emitted)
510540
AM_CRITICAL_BEGIN // critical section when reading / writing config registers
511-
if(*((uint32_t*)CTIMERADDRn(CTIMER, timer, CTRL0)) & (CTIMER_CTRL0_TMRA0EN_Msk | CTIMER_CTRL0_TMRB0EN_Msk)){
541+
if (*((uint32_t *)CTIMERADDRn(CTIMER, timer, CTRL0)) & (CTIMER_CTRL0_TMRA0EN_Msk | CTIMER_CTRL0_TMRB0EN_Msk))
542+
{
512543
uint32_t current = 0;
513544
uint32_t last = 0;
514-
do {
545+
do
546+
{
515547
last = current;
516-
current = am_hal_ctimer_read( timer, segment);
517-
}while(current >= last);
548+
current = am_hal_ctimer_read(timer, segment);
549+
} while (current >= last);
518550
}
519551

520552
AM_CRITICAL_END // end critical section
521553

522-
// clear timer (also stops the timer)
523-
am_hal_ctimer_clear(timer, segment);
554+
// clear timer (also stops the timer)
555+
am_hal_ctimer_clear(timer, segment);
524556

525557
// Configure the repeated pulse mode with our clock source
526558
am_hal_ctimer_config_single(timer,
@@ -538,25 +570,27 @@ ap3_err_t ap3_pwm_output(uint8_t pin, uint32_t th, uint32_t fw, uint32_t clk)
538570
pui32ConfigReg = (uint32_t *)CTIMERADDRn(CTIMER, timer, AUX0);
539571
uint32_t ui32WriteVal = AM_REGVAL(pui32ConfigReg);
540572
uint32_t ui32ConfigVal = (1 << CTIMER_AUX0_TMRA0EN23_Pos); // using CTIMER_AUX0_TMRA0EN23_Pos because for now this number is common to all CTimer instances
541-
volatile uint32_t *pui32CompareRegA = (uint32_t*)CTIMERADDRn(CTIMER, timer, CMPRA0);
542-
volatile uint32_t *pui32CompareRegB = (uint32_t*)CTIMERADDRn(CTIMER, timer, CMPRB0);
543-
uint32_t masterPeriod = (uint32_t)(*(pui32CompareRegA) & CTIMER_CMPRA0_CMPR1A0_Msk) >> CTIMER_CMPRA0_CMPR1A0_Pos;
544-
uint32_t masterRisingTrigger = (uint32_t)(*(pui32CompareRegA) & CTIMER_CMPRA0_CMPR0A0_Msk) >> CTIMER_CMPRA0_CMPR0A0_Pos;
545-
573+
volatile uint32_t *pui32CompareRegA = (uint32_t *)CTIMERADDRn(CTIMER, timer, CMPRA0);
574+
volatile uint32_t *pui32CompareRegB = (uint32_t *)CTIMERADDRn(CTIMER, timer, CMPRB0);
575+
uint32_t masterPeriod = (uint32_t)(*(pui32CompareRegA)&CTIMER_CMPRA0_CMPR1A0_Msk) >> CTIMER_CMPRA0_CMPR1A0_Pos;
576+
uint32_t masterRisingTrigger = (uint32_t)(*(pui32CompareRegA)&CTIMER_CMPRA0_CMPR0A0_Msk) >> CTIMER_CMPRA0_CMPR0A0_Pos;
577+
546578
if (segment == AM_HAL_CTIMER_TIMERB)
547579
{
548580
ui32ConfigVal = ((ui32ConfigVal & 0xFFFF) << 16);
549-
masterPeriod = (uint32_t)(*(pui32CompareRegB) & CTIMER_CMPRB0_CMPR1B0_Msk) >> CTIMER_CMPRB0_CMPR1B0_Pos;
550-
masterRisingTrigger = (uint32_t)(*(pui32CompareRegA) & CTIMER_CMPRB0_CMPR0B0_Msk) >> CTIMER_CMPRB0_CMPR0B0_Pos;
581+
masterPeriod = (uint32_t)(*(pui32CompareRegB)&CTIMER_CMPRB0_CMPR1B0_Msk) >> CTIMER_CMPRB0_CMPR1B0_Pos;
582+
masterRisingTrigger = (uint32_t)(*(pui32CompareRegA)&CTIMER_CMPRB0_CMPR0B0_Msk) >> CTIMER_CMPRB0_CMPR0B0_Pos;
551583
}
552584
ui32WriteVal |= ui32ConfigVal;
553585
AM_REGVAL(pui32ConfigReg) = ui32WriteVal;
554586

555-
if(masterPeriod != fw){
587+
if (masterPeriod != fw)
588+
{
556589
// the master output fw dictates the secondary fw... so if they are different try to change the master while preserving duty cycle
557590
uint32_t masterTH = ((masterPeriod - masterRisingTrigger) * fw) / masterPeriod; // try to compensate in case _analogWriteWidth was changed
558-
if(masterPeriod == 0){ // if masterPeriod was 0 then masterTH will be invalid (divide by 0). This usually means that the master timer output did not have a set duty cycle. This also means the output is probably not configured and so it is okay to choose an arbitrary duty cycle
559-
masterTH = fw - 1;
591+
if (masterPeriod == 0)
592+
{ // if masterPeriod was 0 then masterTH will be invalid (divide by 0). This usually means that the master timer output did not have a set duty cycle. This also means the output is probably not configured and so it is okay to choose an arbitrary duty cycle
593+
masterTH = fw - 1;
560594
}
561595
am_hal_ctimer_period_set(timer, segment, fw, masterTH); // but this overwrites the non-aux compare regs for this timer / segment
562596
// Serial.printf("th = %d, fw = %d, (masterPeriod - masterRisingTrigger) = (%d - %d) = %d\n", th, fw, masterPeriod, masterRisingTrigger, (masterPeriod - masterRisingTrigger));
@@ -570,25 +604,28 @@ ap3_err_t ap3_pwm_output(uint8_t pin, uint32_t th, uint32_t fw, uint32_t clk)
570604
// Try to preserve settings of the secondary output
571605
uint32_t *pui32ConfigReg = NULL;
572606
pui32ConfigReg = (uint32_t *)CTIMERADDRn(CTIMER, timer, AUX0);
573-
volatile uint32_t *pui32CompareRegA = (uint32_t*)CTIMERADDRn(CTIMER, timer, CMPRAUXA0);
574-
volatile uint32_t *pui32CompareRegB = (uint32_t*)CTIMERADDRn(CTIMER, timer, CMPRAUXB0);
575-
uint32_t slavePeriod = (uint32_t)(*(pui32CompareRegA) & CTIMER_CMPRA0_CMPR1A0_Msk) >> CTIMER_CMPRA0_CMPR1A0_Pos;
576-
uint32_t slaveRisingTrigger = (uint32_t)(*(pui32CompareRegA) & CTIMER_CMPRA0_CMPR0A0_Msk) >> CTIMER_CMPRA0_CMPR0A0_Pos;
577-
607+
volatile uint32_t *pui32CompareRegA = (uint32_t *)CTIMERADDRn(CTIMER, timer, CMPRAUXA0);
608+
volatile uint32_t *pui32CompareRegB = (uint32_t *)CTIMERADDRn(CTIMER, timer, CMPRAUXB0);
609+
uint32_t slavePeriod = (uint32_t)(*(pui32CompareRegA)&CTIMER_CMPRA0_CMPR1A0_Msk) >> CTIMER_CMPRA0_CMPR1A0_Pos;
610+
uint32_t slaveRisingTrigger = (uint32_t)(*(pui32CompareRegA)&CTIMER_CMPRA0_CMPR0A0_Msk) >> CTIMER_CMPRA0_CMPR0A0_Pos;
611+
578612
uint32_t auxEnabled = (AM_REGVAL(pui32ConfigReg) & CTIMER_AUX0_TMRA0EN23_Msk);
579-
613+
580614
if (segment == AM_HAL_CTIMER_TIMERB)
581615
{
582616
auxEnabled = (AM_REGVAL(pui32ConfigReg) & (CTIMER_AUX0_TMRA0EN23_Msk << 16));
583-
slavePeriod = (uint32_t)(*(pui32CompareRegB) & CTIMER_CMPRB0_CMPR1B0_Msk) >> CTIMER_CMPRB0_CMPR1B0_Pos;
584-
slaveRisingTrigger = (uint32_t)(*(pui32CompareRegA) & CTIMER_CMPRB0_CMPR0B0_Msk) >> CTIMER_CMPRB0_CMPR0B0_Pos;
617+
slavePeriod = (uint32_t)(*(pui32CompareRegB)&CTIMER_CMPRB0_CMPR1B0_Msk) >> CTIMER_CMPRB0_CMPR1B0_Pos;
618+
slaveRisingTrigger = (uint32_t)(*(pui32CompareRegA)&CTIMER_CMPRB0_CMPR0B0_Msk) >> CTIMER_CMPRB0_CMPR0B0_Pos;
585619
}
586620

587-
if( auxEnabled ){ // if secondary outputs are enabled
588-
if( slavePeriod != fw ){ // and if fw is different from previous slavePeriod
621+
if (auxEnabled)
622+
{ // if secondary outputs are enabled
623+
if (slavePeriod != fw)
624+
{ // and if fw is different from previous slavePeriod
589625
uint32_t slaveTH = ((slavePeriod - slaveRisingTrigger) * fw) / slavePeriod; // try to compensate in case _analogWriteWidth was changed
590-
if(slavePeriod == 0){ // if masterPeriod was 0 then masterTH will be invalid (divide by 0). This usually means that the master timer output did not have a set duty cycle. This also means the output is probably not configured and so it is okay to choose an arbitrary duty cycle
591-
slaveTH = fw - 1;
626+
if (slavePeriod == 0)
627+
{ // if masterPeriod was 0 then masterTH will be invalid (divide by 0). This usually means that the master timer output did not have a set duty cycle. This also means the output is probably not configured and so it is okay to choose an arbitrary duty cycle
628+
slaveTH = fw - 1;
592629
}
593630
am_hal_ctimer_aux_period_set(timer, segment, fw, slaveTH); // but this overwrites the non-aux compare regs for this timer / segment
594631
}
@@ -615,20 +652,25 @@ ap3_err_t analogWriteResolution(uint8_t res)
615652
return AP3_OK;
616653
}
617654

618-
ap3_err_t analogWriteFrameWidth(uint32_t fw){
655+
ap3_err_t analogWriteFrameWidth(uint32_t fw)
656+
{
619657
_analogWriteWidth = fw;
620-
if(_analogWriteWidth > AP3_MAX_ANALOG_WRITE_WIDTH){
658+
if (_analogWriteWidth > AP3_MAX_ANALOG_WRITE_WIDTH)
659+
{
621660
_analogWriteWidth = AP3_MAX_ANALOG_WRITE_WIDTH;
622661
}
623662
return AP3_OK;
624663
}
625664

626-
ap3_err_t analogWriteFrequency(float freq){
665+
ap3_err_t analogWriteFrequency(float freq)
666+
{
627667
_analogWriteWidth = (uint32_t)(12000000 / freq);
628-
if(_analogWriteWidth > AP3_MAX_ANALOG_WRITE_WIDTH){
668+
if (_analogWriteWidth > AP3_MAX_ANALOG_WRITE_WIDTH)
669+
{
629670
return AP3_ERR;
630671
}
631-
if(_analogWriteWidth < 3){
672+
if (_analogWriteWidth < 3)
673+
{
632674
return AP3_ERR;
633675
}
634676
return AP3_OK;
@@ -655,12 +697,12 @@ ap3_err_t servoWriteResolution(uint8_t res)
655697

656698
uint8_t getServoResolution()
657699
{
658-
return(_servoWriteBits);
700+
return (_servoWriteBits);
659701
}
660702

661703
ap3_err_t servoWrite(uint8_t pin, uint32_t val)
662704
{
663-
return(servoWrite(pin, val, 544, 2400)); //Call servoWrite with Arduino default min/max microseconds. See: https://www.arduino.cc/en/Reference/ServoAttach
705+
return (servoWrite(pin, val, 544, 2400)); //Call servoWrite with Arduino default min/max microseconds. See: https://www.arduino.cc/en/Reference/ServoAttach
664706
}
665707

666708
ap3_err_t servoWrite(uint8_t pin, uint32_t val, uint16_t minMicros, uint16_t maxMicros)
@@ -672,9 +714,9 @@ ap3_err_t servoWrite(uint8_t pin, uint32_t val, uint16_t minMicros, uint16_t max
672714
uint32_t fw = 60000; // 20 ms wide frame
673715

674716
//Convert microSeconds to PWM counts.
675-
uint32_t min = minMicros * 3;
717+
uint32_t min = minMicros * 3;
676718
uint32_t max = maxMicros * 3;
677-
719+
678720
uint32_t th = (uint32_t)(((max - min) * val) / fsv) + min;
679721

680722
return ap3_pwm_output(pin, th, fw, clk);

‎cores/arduino/ard_sup/ap3_analog.h

+1
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ ap3_err_t ap3_change_channel(ap3_gpio_pad_t padNumber);
4444
bool power_adc_disable();
4545
uint16_t analogRead(uint8_t pinNumber);
4646
ap3_err_t analogReadResolution(uint8_t bits);
47+
float getInternalTemp();
4748

4849
ap3_err_t ap3_pwm_output(uint8_t pin, uint32_t th, uint32_t fw, uint32_t clk);
4950
ap3_err_t analogWriteResolution(uint8_t res);

‎cores/arduino/ard_sup/gpio/ap3_gpio.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -320,6 +320,7 @@ extern void detachInterrupt(uint8_t pin)
320320
gpio_isr_entries[gpio_num_isr].callback = NULL;
321321
gpio_isr_entries[gpio_num_isr].mode = LOW;
322322
gpio_isr_entries[gpio_num_isr].arg = NULL;
323+
gpio_num_isr--;
323324
}
324325

325326
uint32_t ap3_gpio_enable_interrupts(uint32_t ui32Pin, uint32_t eIntDir)

‎libraries/Examples/examples/Advanced/LowPower/LowPower.ino

+4-1
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,9 @@ void setup()
6363
// These two GPIOs are critical: the TX/RX connections between the Artemis module and the CH340S on the Blackboard
6464
// are prone to backfeeding each other. To stop this from happening, we must reconfigure those pins as GPIOs
6565
// and then disable them completely:
66+
Serial.println("The TX and RX pins need to be disabled to minimize the current draw.");
67+
Serial.println("You should not see any more Serial messages after this...");
68+
delay(100);
6669
am_hal_gpio_pinconfig(48 /* TXO-0 */, g_AM_HAL_GPIO_DISABLE);
6770
am_hal_gpio_pinconfig(49 /* RXI-0 */, g_AM_HAL_GPIO_DISABLE);
6871

@@ -104,4 +107,4 @@ void setup()
104107
void loop()
105108
{
106109
//Do nothing
107-
}
110+
}

‎libraries/Examples/examples/Advanced/LowPower_WithWake/LowPower_WithWake.ino

+4-1
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,9 @@ void setup()
5656
// These two GPIOs are critical: the TX/RX connections between the Artemis module and the CH340S on the Blackboard
5757
// are prone to backfeeding each other. To stop this from happening, we must reconfigure those pins as GPIOs
5858
// and then disable them completely:
59+
Serial.println("The TX and RX pins need to be disabled to minimize the current draw.");
60+
Serial.println("You should not see any more Serial messages after this...");
61+
delay(100);
5962
am_hal_gpio_pinconfig(48 /* TXO-0 */, g_AM_HAL_GPIO_DISABLE);
6063
am_hal_gpio_pinconfig(49 /* RXI-0 */, g_AM_HAL_GPIO_DISABLE);
6164

@@ -140,4 +143,4 @@ extern "C" void am_rtc_isr(void)
140143
delay(100);
141144
digitalWrite(LED_BUILTIN, LOW);
142145
}
143-
}
146+
}

‎libraries/Examples/examples/Example4_analogRead/Example4_analogRead.ino

+1-4
Original file line numberDiff line numberDiff line change
@@ -52,11 +52,8 @@ void loop()
5252
Serial.print(vcc, 2);
5353
Serial.print("V");
5454

55-
int internalTempVoltage = analogRead(ADC_INTERNAL_TEMP); //Read internal temp sensor. 3.8mV/C, +/-3C
56-
double internalTemp = internalTempVoltage * vcc / 16384.0; //Convert internal temp reading to voltage
57-
internalTemp /= 0.0038; //Convert voltage to degrees C
5855
Serial.print("\tinternalTemp: ");
59-
Serial.print(internalTemp, 2);
56+
Serial.print(getInternalTemp(), 2);
6057

6158
int vss = analogRead(ADC_INTERNAL_VSS); //Read internal VSS (should be 0)
6259
Serial.print("\tvss: ");

‎platform.txt

+2-3
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ defines.variant={build.defs}
6363

6464

6565
## Compiler and Toolchain
66-
compiler.path={runtime.tools.arm-none-eabi-gcc-8-2018-q4-major.path}/bin
66+
compiler.path={runtime.tools.arm-none-eabi-gcc-7-2017q4.path}/bin
6767
compiler.cmd.cpp=arm-none-eabi-g++
6868
compiler.cmd.c=arm-none-eabi-gcc
6969
compiler.cmd.S=arm-none-eabi-gcc
@@ -118,8 +118,7 @@ recipe.objcopy.bin.pattern="{compiler.path}/{compiler.cmd.axf2bin}" {compiler.fl
118118
## Compute size
119119
recipe.size.pattern="{compiler.path}/{compiler.cmd.size}" -A "{build.path}/{build.project_name}.axf"
120120
recipe.size.regex=\.text\s+([0-9]+).*
121-
122-
recipe.hooks.objcopy.postobjcopy.0.pattern="{compiler.path}/{compiler.cmd.size}" -A "{build.path}/{build.project_name}.axf"
121+
recipe.size.regex.data=^(?:\.data|\.bss)\s+([0-9]+).*
123122

124123
## Preprocessor
125124
preproc.macros.flags=-w -x c++ -E -CC

0 commit comments

Comments
 (0)
Please sign in to comment.