Three phase bridge control
Dependents: BLDC_control BLDC_RPM_meter
Diff: ThreePhaseBridge.cpp
- Revision:
- 0:a129854eb4b6
- Child:
- 1:ba7889accd61
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ThreePhaseBridge.cpp Tue Mar 11 15:42:38 2014 +0000 @@ -0,0 +1,109 @@ +#include "ThreePhaseBridge.h" + +int8_t ThreePhaseBridge::stateOrder[6] = {3, 1, 5, 4, 6, 2}; + +ThreePhaseBridge::ThreePhaseBridge( + PinName sw1PinName, PinName sw2PinName, PinName sw3PinName, + PinName sw4PinName, PinName sw5PinName, PinName sw6PinName, + ThreePhaseBridge::ActiveState activeState +) : sw1(sw1PinName), sw3(sw3PinName), sw5(sw5PinName), + sw2(sw2PinName), sw4(sw4PinName), sw6(sw6PinName), + activeState(activeState) +{ + highSide[0] = &sw1; + highSide[1] = &sw3; + highSide[2] = &sw5; + lowSide[0] = &sw2; + lowSide[1] = &sw4; + lowSide[2] = &sw6; + switchesState = 63; + setSwitchesState(0); + state = 0; stateIndex = 5; +} + +void ThreePhaseBridge::setPwmPeriod_us(int32_t period_us) +{ + pwmPeriod_us = period_us; + sw1.period_us(period_us); + sw3.period_us(period_us); + sw5.period_us(period_us); +} + +void ThreePhaseBridge::setPwmPulseWidth_us(int32_t pulseWidth_us) +{ + pwmPulseWidth_us = pulseWidth_us; + sw1.pulsewidth_us(pulseWidth_us); + sw3.pulsewidth_us(pulseWidth_us); + sw5.pulsewidth_us(pulseWidth_us); +} +void ThreePhaseBridge::setHighSideSwitchState(int8_t sw, ThreePhaseBridge::SwitchState state) +{ + state == on ? highSide[sw]->pulsewidth_us(activeState == activeLow ? pwmPeriod_us - pwmPulseWidth_us : pwmPeriod_us) + : highSide[sw]->pulsewidth_us(activeState == activeLow ? 2 * pwmPeriod_us : 0); +} + +void ThreePhaseBridge::setLowSideSwitchState(int8_t sw, ThreePhaseBridge::SwitchState state) +{ + state == on ? *lowSide[sw] = (activeState == activeLow ? 0 : 1) + : *lowSide[sw] = (activeState == activeLow ? 1 : 0); +} + +void ThreePhaseBridge::setSwitchesState(uint8_t newState) +{ + uint8_t turnOff = ~(newState & switchesState) & switchesState; + uint8_t turnOffLow = turnOff & 7; + uint8_t turnOffHigh = turnOff >> 3; + uint8_t turnOn = newState & ~switchesState; + uint8_t turnOnLow = turnOn & 7; + uint8_t turnOnHigh = turnOn >> 3; + for (uint8_t i = 0; i < 3; i++) { + if (turnOffLow & (1 << i)) + setLowSideSwitchState(i, off); + if (turnOffHigh & (1 << i)) + setHighSideSwitchState(i, off); + } + for (uint8_t i = 0; i < 3; i++) { + if (turnOnLow & (1 << i)) + { + setLowSideSwitchState(i, on); + } + if (turnOnHigh & (1 << i)) + setHighSideSwitchState(i, on); + } + switchesState = newState; +} + +void ThreePhaseBridge::setState(int8_t newState) +{ + switch (newState) { + case 1: + setSwitchesState(SW1 | SW6); + break; + case 2: + setSwitchesState(SW3 | SW2); + break; + case 3: + setSwitchesState(SW3 | SW6); + break; + case 4: + setSwitchesState(SW5 | SW4); + break; + case 5: + setSwitchesState(SW1 | SW4); + break; + case 6: + setSwitchesState(SW5 | SW2); + break; + default: + setSwitchesState(0); + break; + } + state = newState; +} + +void ThreePhaseBridge::spin(ThreePhaseBridge::SpinDirection dir) +{ + stateIndex = (6 + stateIndex + dir) % 6; + setState(stateOrder[stateIndex]); +} + \ No newline at end of file