static void Config_PWM(void) { ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOB); ROM_GPIOPinConfigure(GPIO_PB6_T0CCP0); ROM_GPIOPinConfigure(GPIO_PB2_T3CCP0); ROM_GPIOPinTypeTimer(GPIO_PORTB_BASE, GPIO_PIN_2 | GPIO_PIN_6); // Configure timer ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER0); ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER3); ROM_TimerConfigure(TIMER0_BASE, TIMER_CFG_SPLIT_PAIR | TIMER_CFG_A_PWM); ROM_TimerLoadSet(TIMER0_BASE, TIMER_A, DEFAULT); ROM_TimerMatchSet(TIMER0_BASE, TIMER_A, DEFAULT); // PWM ROM_TimerEnable(TIMER0_BASE, TIMER_A); ROM_TimerConfigure(TIMER3_BASE, TIMER_CFG_SPLIT_PAIR | TIMER_CFG_A_PWM); ROM_TimerLoadSet(TIMER3_BASE, TIMER_A, DEFAULT); ROM_TimerMatchSet(TIMER3_BASE, TIMER_A, DEFAULT); // PWM ROM_TimerControlLevel(TIMER3_BASE, TIMER_A, true); ROM_TimerEnable(TIMER3_BASE, TIMER_A); ROM_SysCtlPeripheralEnable(DRV_ENABLE_LEFT_CHN_PERIPHERAL); ROM_SysCtlPeripheralEnable(DRV_ENABLE_RIGHT_CHN_PERIPHERAL); ROM_GPIOPinTypeGPIOOutput(DRV_ENABLE_LEFT_CHN_PORT, DRV_ENABLE_LEFT_CHN_PIN); ROM_GPIOPinTypeGPIOOutput(DRV_ENABLE_RIGHT_CHN_PORT, DRV_ENABLE_RIGHT_CHN_PIN); ROM_GPIOPinWrite(DRV_ENABLE_LEFT_CHN_PORT, DRV_ENABLE_LEFT_CHN_PIN, 0); ROM_GPIOPinWrite(DRV_ENABLE_RIGHT_CHN_PORT, DRV_ENABLE_RIGHT_CHN_PIN, 0); }
void buzzer_setsound(uint32_t ulFrequency) { uint32_t ulPeriod; if (ulFrequency == 0) { ROM_TimerLoadSet(BUZZER_TIMER, BUZZER_TIMER_CHANNEL, ROM_SysCtlClockGet()); ROM_TimerMatchSet(BUZZER_TIMER, BUZZER_TIMER_CHANNEL, ROM_SysCtlClockGet()); } else { ulPeriod = ROM_SysCtlClockGet() / ulFrequency; ROM_TimerLoadSet(BUZZER_TIMER, BUZZER_TIMER_CHANNEL, ulPeriod); ROM_TimerMatchSet(BUZZER_TIMER, BUZZER_TIMER_CHANNEL, ulPeriod / 2); } }
void PWMWrite(uint8_t pin, uint32_t analog_res, uint32_t duty, unsigned int freq) { if (duty == 0) { pinMode(pin, OUTPUT); digitalWrite(pin, LOW); } else if (duty >= analog_res) { pinMode(pin, OUTPUT); digitalWrite(pin, HIGH); } else { uint8_t bit = digitalPinToBitMask(pin); // get pin bit uint8_t port = digitalPinToPort(pin); // get pin port uint8_t timer = digitalPinToTimer(pin); uint32_t portBase = (uint32_t) portBASERegister(port); uint32_t offset = timerToOffset(timer); uint32_t timerBase = getTimerBase(offset); uint32_t timerAB = TIMER_A << timerToAB(timer); if (port == NOT_A_PORT) return; // pin on timer? uint32_t periodPWM = ROM_SysCtlClockGet()/freq; enableTimerPeriph(offset); ROM_GPIOPinConfigure(timerToPinConfig(timer)); ROM_GPIOPinTypeTimer((long unsigned int) portBase, bit); // // Configure for half-width mode, allowing timers A and B to // operate independently // HWREG(timerBase + TIMER_O_CFG) = 0x04; if(timerAB == TIMER_A) { HWREG(timerBase + TIMER_O_CTL) &= ~TIMER_CTL_TAEN; HWREG(timerBase + TIMER_O_TAMR) = PWM_MODE; } else { HWREG(timerBase + TIMER_O_CTL) &= ~TIMER_CTL_TBEN; HWREG(timerBase + TIMER_O_TBMR) = PWM_MODE; } ROM_TimerLoadSet(timerBase, timerAB, periodPWM); ROM_TimerMatchSet(timerBase, timerAB, (analog_res-duty)*periodPWM/analog_res); // // If using a 16-bit timer, with a periodPWM > 0xFFFF, // need to use a prescaler // if((offset < WTIMER0) && (periodPWM > 0xFFFF)) { ROM_TimerPrescaleSet(timerBase, timerAB, (periodPWM & 0xFFFF0000) >> 16); ROM_TimerPrescaleMatchSet(timerBase, timerAB, (((analog_res-duty)*periodPWM/analog_res) & 0xFFFF0000) >> 16); } ROM_TimerEnable(timerBase, timerAB); }
//***************************************************************************** // //! Initializes the sound driver. //! //! \param ui32SysClock is the frequency of the system clock. //! //! This function initializes the sound driver, preparing it to output sound //! data to the speaker. //! //! The system clock should be as high as possible; lower clock rates reduces //! the quality of the produced sound. For the best quality sound, the system //! should be clocked at 120 MHz. //! //! \note In order for the sound driver to function properly, the sound driver //! interrupt handler (SoundIntHandler()) must be installed into the vector //! table for the timer 5 subtimer A interrupt. //! //! \return None. // //***************************************************************************** void SoundInit(uint32_t ui32SysClock) { // // Enable the peripherals used by the sound driver. // ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER5); // // Compute the PWM period based on the system clock. // g_sSoundState.ui32Period = ui32SysClock / 64000; // // Set the default volume. // g_sSoundState.i32Volume = 255; // // Configure the timer to run in PWM mode. // if((HWREG(TIMER5_BASE + TIMER_O_CTL) & TIMER_CTL_TBEN) == 0) { ROM_TimerConfigure(TIMER5_BASE, (TIMER_CFG_SPLIT_PAIR | TIMER_CFG_A_PWM | TIMER_CFG_B_PERIODIC)); } ROM_TimerLoadSet(TIMER5_BASE, TIMER_A, g_sSoundState.ui32Period - 1); ROM_TimerMatchSet(TIMER5_BASE, TIMER_A, g_sSoundState.ui32Period); ROM_TimerControlLevel(TIMER5_BASE, TIMER_A, true); // // Update the timer values on timeouts and not immediately. // TimerUpdateMode(TIMER5_BASE, TIMER_A, TIMER_UP_LOAD_TIMEOUT | TIMER_UP_MATCH_TIMEOUT); // // Configure the timer to generate an interrupt at every time-out event. // ROM_TimerIntEnable(TIMER5_BASE, TIMER_CAPA_EVENT); // // Enable the timer. At this point, the timer generates an interrupt // every 15.625 us. // ROM_TimerEnable(TIMER5_BASE, TIMER_A); ROM_IntEnable(INT_TIMER5A); // // Clear the sound flags. // g_sSoundState.ui32Flags = 0; }
void SetPWM(uint32_t ulBaseAddr, uint32_t ulTimer, uint32_t ulFrequency, int32_t ucDutyCycle) { uint32_t ulPeriod; ulPeriod = ROM_SysCtlClockGet() / ulFrequency; ROM_TimerLoadSet(ulBaseAddr, ulTimer, ulPeriod); if (ucDutyCycle > 70) ucDutyCycle = 70; else if (ucDutyCycle < -70) ucDutyCycle = -70; ROM_TimerMatchSet(ulBaseAddr, ulTimer, (100 + ucDutyCycle) * ulPeriod / 200 - 1); }
//***************************************************************************** // //! Set the output color. //! //! \param pui32RGBColor points to a three element array representing the //! relative intensity of each color. Red is element 0, Green is element 1, //! Blue is element 2. 0x0000 is off. 0xFFFF is fully on. //! //! This function should be called by the application to set the color //! of the RGB LED. //! //! \return None. // //***************************************************************************** void RGBColorSet(volatile uint32_t * pui32RGBColor) { uint32_t ui32Color[3]; uint32_t ui32Index; for(ui32Index=0; ui32Index < 3; ui32Index++) { g_ui32Colors[ui32Index] = pui32RGBColor[ui32Index]; ui32Color[ui32Index] = (uint32_t) (((float) pui32RGBColor[ui32Index]) * g_fIntensity + 0.5f); if(ui32Color[ui32Index] > 0xFFFF) { ui32Color[ui32Index] = 0xFFFF; } } ROM_TimerMatchSet(RED_TIMER_BASE, RED_TIMER, ui32Color[RED]); ROM_TimerMatchSet(GREEN_TIMER_BASE, GREEN_TIMER, ui32Color[GREEN]); ROM_TimerMatchSet(BLUE_TIMER_BASE, BLUE_TIMER, ui32Color[BLUE]); }
void buzzer_init(void) { BUZZER_GPIO_PERIPHERAL_ENABLE(); BUZZER_TIMER_PERIPHERAL_ENABLE(); ROM_GPIOPinConfigure(BUZZER_TIMER_PIN_AF); ROM_GPIOPinTypeTimer(BUZZER_PORT, BUZZER_PIN); ROM_TimerConfigure(BUZZER_TIMER, TIMER_CFG_SPLIT_PAIR | TIMER_CFG_A_PWM); // ROM_TimerPrescaleSet(BUZZER_TIMER, BUZZER_TIMER_CHANNEL, 10); ROM_TimerLoadSet(BUZZER_TIMER, BUZZER_TIMER_CHANNEL, ROM_SysCtlClockGet()); ROM_TimerMatchSet(BUZZER_TIMER, BUZZER_TIMER_CHANNEL, ROM_SysCtlClockGet()); // PWM ROM_TimerEnable(BUZZER_TIMER, BUZZER_TIMER_CHANNEL); }
/* Two way PWM speed control. If speed is >0 then motor runs forward. Else if speed is < 0 then motor runs backward */ void Motor::speed(signed int motor_speed) { if (motor_speed == 0) motor_speed = 1; if (motor_speed > 0) { ROM_GPIOPinWrite(this->motor_dir_port, this->motor_dir_pin, this->motor_dir_pin); } else { ROM_GPIOPinWrite(this->motor_dir_port, this->motor_dir_pin, 0); } motor_speed = abs(motor_speed); if (motor_speed > this->analog_res) motor_speed = this->analog_res - 1; this->duty = motor_speed; ROM_TimerLoadSet(this->timerBase, this->timerAB, this->periodPWM); ROM_TimerMatchSet(this->timerBase, this->timerAB, (this->analog_res - this->duty) * this->periodPWM / this->analog_res); }
//***************************************************************************** // // This example application demonstrates the use of the timers to generate // periodic interrupts. // //***************************************************************************** int main(void) { #if defined(TARGET_IS_TM4C129_RA0) || \ defined(TARGET_IS_TM4C129_RA1) || \ defined(TARGET_IS_TM4C129_RA2) uint32_t ui32SysClock; #endif // // Enable lazy stacking for interrupt handlers. This allows floating-point // instructions to be used within interrupt handlers, but at the expense of // extra stack usage. // ROM_FPULazyStackingEnable(); // // Set the clocking to run directly from the crystal. // TODO: Set the system clock appropriately for your application. // #if defined(TARGET_IS_TM4C129_RA0) || \ defined(TARGET_IS_TM4C129_RA1) || \ defined(TARGET_IS_TM4C129_RA2) ui32SysClock = SysCtlClockFreqSet((SYSCTL_XTAL_25MHZ | SYSCTL_OSC_MAIN | SYSCTL_USE_OSC), 25000000); #else ROM_SysCtlClockSet(SYSCTL_SYSDIV_1 | SYSCTL_USE_OSC | SYSCTL_OSC_MAIN | SYSCTL_XTAL_16MHZ); #endif // // Initialize the display on the board. This is not directly related // to the timer operation but makes it easier to see what's going on // when you run this on an EK-LM4F232 board. // // TODO: Remove or replace this call with something appropriate for // your hardware. // InitDisplay(); // // Enable the peripherals used by this example. // // TODO: Update this depending upon the general purpose timer and // CCP pin you intend using. // ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER4); ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOM); // // Configure PM0 as the CCP0 pin for timer 4. // // TODO: This is set up to use GPIO PM0 which can be configured // as the CCP0 pin for Timer4 and also happens to be attached to // a switch on the EK-LM4F232 board. Change this configuration to // correspond to the correct pin for your application. // ROM_GPIOPinTypeTimer(GPIO_PORTM_BASE, GPIO_PIN_0); GPIOPinConfigure(GPIO_PM0_T4CCP0); // // Set the pin to use the internal pull-up. // // TODO: Remove or replace this call to correspond to the wiring // of the CCP pin you are using. If your board has an external // pull-up or pull-down, this will not be required. // MAP_GPIOPadConfigSet(GPIO_PORTM_BASE, GPIO_PIN_0, GPIO_STRENGTH_2MA, GPIO_PIN_TYPE_STD_WPU); // // Enable processor interrupts. // ROM_IntMasterEnable(); // // Configure the timers in downward edge count mode. // // TODO: Modify this to configure the specific general purpose // timer you are using. The timer choice is intimately tied to // the pin whose edges you want to capture because specific CCP // pins are connected to specific timers. // ROM_TimerConfigure(TIMER4_BASE, (TIMER_CFG_SPLIT_PAIR | TIMER_CFG_A_CAP_COUNT)); ROM_TimerControlEvent(TIMER4_BASE, TIMER_A, TIMER_EVENT_POS_EDGE); ROM_TimerLoadSet(TIMER4_BASE, TIMER_A, 9); ROM_TimerMatchSet(TIMER4_BASE, TIMER_A, 0); // // Setup the interrupt for the edge capture timer. Note that we // use the capture match interrupt and NOT the timeout interrupt! // // TODO: Modify to enable the specific timer you are using. // ROM_IntEnable(INT_TIMER4A); ROM_TimerIntEnable(TIMER4_BASE, TIMER_CAPA_MATCH); // // Enable the timer. // // TODO: Modify to enable the specific timer you are using. // ROM_TimerEnable(TIMER4_BASE, TIMER_A); // // At this point, the timer will count down every time a positive // edge is detected on the relevant pin. When the count reaches // 0, the timer count reloads, the interrupt fires and the timer // is disabled. The ISR can then restart the timer if required. // MainLoopRun(); }
//***************************************************************************** // //! Starts playback of a sound stream. //! //! \param pi16Buffer is a pointer to the buffer that contains the sound to //! play. //! \param ui32Length is the length of the buffer in samples. This should be //! a multiple of two. //! \param ui32Rate is the sound playback rate; valid values are 8000, 16000, //! 32000, and 64000. //! \param pfnCallback is the callback function that is called when either half //! of the sound buffer has been played. //! //! This function starts the playback of a sound stream contained in an //! audio ping-pong buffer. The buffer is played repeatedly until //! SoundStop() is called. Playback of the sound stream begins //! immediately, so the buffer should be pre-filled with the initial sound //! data prior to calling this function. //! //! \return Returns \b true if playback was started and \b false if it could //! not be started (because something is already playing). // //***************************************************************************** bool SoundStart(int16_t *pi16Buffer, uint32_t ui32Length, uint32_t ui32Rate, void (*pfnCallback)(uint32_t ui32Half)) { // // Return without playing the buffer if something is already playing. // if(g_sSoundState.ui32Flags) { return(false); } // // Set the sample rate flag. // if(ui32Rate == 8000) { HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_8KHZ) = 1; } else if(ui32Rate == 16000) { HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_16KHZ) = 1; } else if(ui32Rate == 32000) { HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_32KHZ) = 1; } else if(ui32Rate == 64000) { HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_64KHZ) = 1; } else { return(false); } // // Enable the speaker amp. // ROM_GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_4, GPIO_PIN_4); // // Save the pointer to the buffer. // g_sSoundState.pi16Buffer = pi16Buffer; g_sSoundState.ui32Length = ui32Length; // // Save the pointer to the callback function. // g_sSoundState.pfnCallback = pfnCallback; // // Start playback from the beginning of the buffer. // g_sSoundState.ui32Offset = 0; // // Initialize the sample buffer with silence. // g_sSoundState.pi16Samples[0] = 0; g_sSoundState.pi16Samples[1] = 0; // // Start playback of the stream. // HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_STARTUP) = 1; HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_PLAY) = 1; // // Set the step for the startup ramp. // g_sSoundState.i32Step = 1; // // Enable the timer interrupt. // ROM_TimerMatchSet(TIMER5_BASE, TIMER_A, 1); // // Success. // return(true); }
//***************************************************************************** // //! Handles the TIMER5A interrupt. //! //! This function responds to the TIMER5A interrupt, updating the duty cycle of //! the output waveform in order to produce sound. It is the application's //! responsibility to ensure that this function is called in response to the //! TIMER5A interrupt, typically by installing it in the vector table as the //! handler for the TIMER5A interrupt. //! //! \return None. // //***************************************************************************** void SoundIntHandler(void) { int32_t i32DutyCycle; // // If there is an adjustment to be made, the apply it and set allow the // update to be done on the next load. // if(g_sSoundState.i32RateAdjust) { g_sSoundState.ui32Period += g_sSoundState.i32RateAdjust; g_sSoundState.i32RateAdjust = 0; TimerLoadSet(TIMER5_BASE, TIMER_A, g_sSoundState.ui32Period); } // // Clear the timer interrupt. // ROM_TimerIntClear(TIMER5_BASE, TIMER_CAPA_EVENT); // // See if the startup ramp is in progress. // if(HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_STARTUP)) { // // Increment the ramp count. // g_sSoundState.i32Step++; // // Increase the pulse width of the output by one clock. // ROM_TimerMatchSet(TIMER5_BASE, TIMER_A, g_sSoundState.i32Step); // // See if this was the last step of the ramp. // if(g_sSoundState.i32Step >= (g_sSoundState.ui32Period / 2)) { // // Indicate that the startup ramp has completed. // HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_STARTUP) = 0; // // Set the step back to zero for the start of audio playback. // g_sSoundState.i32Step = 0; } // // There is nothing further to be done. // return; } // // See if the shutdown ramp is in progress. // if(HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_SHUTDOWN)) { // // See if this was the last step of the ramp. // if(g_sSoundState.i32Step == 1) { // // Disable the output signals. // ROM_TimerMatchSet(TIMER5_BASE, TIMER_A, g_sSoundState.ui32Period); // // Clear the sound flags. // g_sSoundState.ui32Flags = 0; // // Disable the speaker amp. // ROM_GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_4, 0); } else { // // Decrement the ramp count. // g_sSoundState.i32Step--; // // Decrease the pulse width of the output by one clock. // ROM_TimerMatchSet(TIMER5_BASE, TIMER_A, g_sSoundState.i32Step); } // // There is nothing further to be done. // return; } // // Compute the value of the PCM sample based on the blended average of the // previous and current samples. It should be noted that linear // interpolation does not produce the best results with sound (it produces // a significant amount of harmonic aliasing) but it is fast. // i32DutyCycle = (((g_sSoundState.pi16Samples[0] * (8 - g_sSoundState.i32Step)) + (g_sSoundState.pi16Samples[1] * g_sSoundState.i32Step)) / 8); // // Adjust the magnitude of the sample based on the current volume. Since a // multiplicative volume control is implemented, the volume value // results in nearly linear volume adjustment if it is squared. // i32DutyCycle = (((i32DutyCycle * g_sSoundState.i32Volume * g_sSoundState.i32Volume) / 65536) + 32768); // // Set the PWM duty cycle based on this PCM sample. // i32DutyCycle = (g_sSoundState.ui32Period * i32DutyCycle) / 65536; ROM_TimerMatchSet(TIMER5_BASE, TIMER_A, i32DutyCycle); // // Increment the sound step based on the sample rate. // if(HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_8KHZ)) { g_sSoundState.i32Step = (g_sSoundState.i32Step + 1) & 7; } else if(HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_16KHZ)) { g_sSoundState.i32Step = (g_sSoundState.i32Step + 2) & 7; } else if(HWREGBITW(&g_sSoundState.ui32Flags, SOUND_FLAG_32KHZ)) { g_sSoundState.i32Step = (g_sSoundState.i32Step + 4) & 7; } // // See if the next sample has been reached. // if(g_sSoundState.i32Step == 0) { // // Copy the current sample to the previous sample. // g_sSoundState.pi16Samples[0] = g_sSoundState.pi16Samples[1]; // // Get the next sample from the buffer. // g_sSoundState.pi16Samples[1] = g_sSoundState.pi16Buffer[g_sSoundState.ui32Offset]; // // Increment the buffer pointer. // g_sSoundState.ui32Offset++; if(g_sSoundState.ui32Offset == g_sSoundState.ui32Length) { g_sSoundState.ui32Offset = 0; } // // Call the callback function if one of the half-buffers has been // consumed. // if(g_sSoundState.pfnCallback) { if(g_sSoundState.ui32Offset == 0) { g_sSoundState.pfnCallback(1); } else if(g_sSoundState.ui32Offset == (g_sSoundState.ui32Length / 2)) { g_sSoundState.pfnCallback(0); } } } }
/* * Motor constructor - frequency, PWM pin and Dir pin. * Sets which wires should control the motor. */ Motor::Motor(int pwm_frequency, int motor_pwm_pin, int motor_dir_pin) { this->frequency = pwm_frequency; // the PWM frequency this->direction = 0; // motor direction this->duty = 1; // pwm duty mimimun is 1. Strop the motor this->analog_res = 256; // One byte resolution : 0 - 255 // Tiva Launchpad pins for the motor control connection: this->motor_pwm_pin = motor_pwm_pin; this->motor_dir_pin = motor_dir_pin; //-------------- setup the pins on the microcontroller: ------------ pinMode(this->motor_dir_pin, OUTPUT); uint8_t bit = digitalPinToBitMask(this->motor_dir_pin); // get pin bit uint8_t port = digitalPinToPort(this->motor_dir_pin); // get pin port this->motor_dir_port = (uint32_t) portBASERegister(port); this->motor_dir_pin = bit; //---------------------------------------------------------- bit = digitalPinToBitMask(this->motor_pwm_pin); // get pin bit port = digitalPinToPort(this->motor_pwm_pin); // get pin port uint8_t timer = digitalPinToTimer(this->motor_pwm_pin); uint32_t portBase = (uint32_t) portBASERegister(port); uint32_t offset = timerToOffset(timer); this->timerBase = getTimerBase(offset); this->timerAB = TIMER_A << timerToAB(timer); if (port == NOT_A_PORT) return; // pin on timer? #ifdef __TM4C1294NCPDT__ this->periodPWM = F_CPU/this->frequency; #else this->periodPWM = SysCtlClockGet() / this->frequency; #endif if (offset > TIMER3) { ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_WTIMER0 + offset - 4); } else { ROM_SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER0 + offset); } ROM_GPIOPinConfigure(timerToPinConfig(timer)); ROM_GPIOPinTypeTimer((long unsigned int) portBase, bit); // // Configure for half-width mode, allowing timers A and B to // operate independently // HWREG(this->timerBase + TIMER_O_CFG) = 0x04; if (this->timerAB == TIMER_A) { HWREG(this->timerBase + TIMER_O_CTL) &= ~TIMER_CTL_TAEN; HWREG(this->timerBase + TIMER_O_TAMR) = PWM_MODE; } else { HWREG(this->timerBase + TIMER_O_CTL) &= ~TIMER_CTL_TBEN; HWREG(this->timerBase + TIMER_O_TBMR) = PWM_MODE; } ROM_TimerLoadSet(this->timerBase, this->timerAB, this->periodPWM); ROM_TimerMatchSet(this->timerBase, this->timerAB,(this->analog_res - this->duty) * this->periodPWM / this->analog_res); ROM_TimerEnable(this->timerBase, this->timerAB); this->initialized = true; }