#635 better names

This commit is contained in:
rusefi 2018-12-25 10:13:00 -05:00
parent 881fad4e59
commit a4efd47ba1
10 changed files with 56 additions and 50 deletions

View File

@ -128,7 +128,7 @@ static void applyAlternatorPinState(PwmConfig *state, int stateIndex) {
efiAssertVoid(CUSTOM_ERR_6643, stateIndex < PWM_PHASE_MAX_COUNT, "invalid stateIndex"); efiAssertVoid(CUSTOM_ERR_6643, stateIndex < PWM_PHASE_MAX_COUNT, "invalid stateIndex");
efiAssertVoid(CUSTOM_IDLE_WAVE_CNT, state->multiWave.waveCount == 1, "invalid idle waveCount"); efiAssertVoid(CUSTOM_IDLE_WAVE_CNT, state->multiWave.waveCount == 1, "invalid idle waveCount");
OutputPin *output = state->outputPins[0]; OutputPin *output = state->outputPins[0];
int value = state->multiWave.waves[0].getState(stateIndex); int value = state->multiWave.getChannelState(/*channelIndex*/0, stateIndex);
/** /**
* 'engine->isAlternatorControlEnabled' would be false is RPM is too low * 'engine->isAlternatorControlEnabled' would be false is RPM is too low
*/ */

View File

@ -30,7 +30,7 @@ void SingleWave::setState(int index, int state) {
} }
void MultiWave::baseConstructor() { void MultiWave::baseConstructor() {
waves = NULL; channels = NULL;
switchTimes = NULL; switchTimes = NULL;
reset(); reset();
} }
@ -44,9 +44,9 @@ MultiWave::MultiWave(float *switchTimes, SingleWave *waves) {
init(switchTimes, waves); init(switchTimes, waves);
} }
void MultiWave::init(float *switchTimes, SingleWave *waves) { void MultiWave::init(float *switchTimes, SingleWave *channels) {
this->switchTimes = switchTimes; this->switchTimes = switchTimes;
this->waves = waves; this->channels = channels;
} }
void MultiWave::reset(void) { void MultiWave::reset(void) {
@ -70,7 +70,7 @@ void MultiWave::checkSwitchTimes(int size) {
} }
int MultiWave::getChannelState(int channelIndex, int phaseIndex) const { int MultiWave::getChannelState(int channelIndex, int phaseIndex) const {
return waves[channelIndex].pinStates[phaseIndex]; return channels[channelIndex].pinStates[phaseIndex];
} }
/** /**

View File

@ -66,10 +66,10 @@ public:
int findInsertionAngle(float angle, int size) const; int findInsertionAngle(float angle, int size) const;
/** /**
* Number of signal wires * Number of signal channels
*/ */
int waveCount; int waveCount;
SingleWave *waves; SingleWave *channels;
//private: //private:
/** /**
* values in the (0..1] range which refer to points within the period at at which pin state should be changed * values in the (0..1] range which refer to points within the period at at which pin state should be changed

View File

@ -446,7 +446,7 @@ static void applyIdleSolenoidPinState(PwmConfig *state, int stateIndex) {
efiAssertVoid(CUSTOM_ERR_6645, stateIndex < PWM_PHASE_MAX_COUNT, "invalid stateIndex"); efiAssertVoid(CUSTOM_ERR_6645, stateIndex < PWM_PHASE_MAX_COUNT, "invalid stateIndex");
efiAssertVoid(CUSTOM_ERR_6646, state->multiWave.waveCount == 1, "invalid idle waveCount"); efiAssertVoid(CUSTOM_ERR_6646, state->multiWave.waveCount == 1, "invalid idle waveCount");
OutputPin *output = state->outputPins[0]; OutputPin *output = state->outputPins[0];
int value = state->multiWave.waves[0].pinStates[stateIndex]; int value = state->multiWave.getChannelState(/*channelIndex*/0, stateIndex);
if (!value /* always allow turning solenoid off */ || if (!value /* always allow turning solenoid off */ ||
(GET_RPM() != 0 || timeToStopIdleTest != 0) /* do not run solenoid unless engine is spinning or bench testing in progress */ (GET_RPM() != 0 || timeToStopIdleTest != 0) /* do not run solenoid unless engine is spinning or bench testing in progress */
) { ) {

View File

@ -230,10 +230,11 @@ void copyPwmParameters(PwmConfig *state, int phaseCount, float *switchTimes, int
for (int phaseIndex = 0; phaseIndex < phaseCount; phaseIndex++) { for (int phaseIndex = 0; phaseIndex < phaseCount; phaseIndex++) {
state->multiWave.setSwitchTime(phaseIndex, switchTimes[phaseIndex]); state->multiWave.setSwitchTime(phaseIndex, switchTimes[phaseIndex]);
for (int waveIndex = 0; waveIndex < waveCount; waveIndex++) { for (int channelIndex = 0; channelIndex < waveCount; channelIndex++) {
// print("output switch time index (%d/%d) at %.2f to %d\r\n", phaseIndex,waveIndex, // print("output switch time index (%d/%d) at %.2f to %d\r\n", phaseIndex, channelIndex,
// switchTimes[phaseIndex], pinStates[waveIndex][phaseIndex]); // switchTimes[phaseIndex], pinStates[waveIndex][phaseIndex]);
state->multiWave.waves[waveIndex].pinStates[phaseIndex] = pinStates[waveIndex][phaseIndex]; int value = pinStates[channelIndex][phaseIndex];
state->multiWave.channels[channelIndex].setState(phaseIndex, value);
} }
} }
if (state->mode == PM_NORMAL) { if (state->mode == PM_NORMAL) {
@ -310,9 +311,9 @@ void startSimplePwmExt(SimplePwm *state, const char *msg, brain_pin_e brainPin,
void applyPinState(PwmConfig *state, int stateIndex) { void applyPinState(PwmConfig *state, int stateIndex) {
efiAssertVoid(CUSTOM_ERR_6663, stateIndex < PWM_PHASE_MAX_COUNT, "invalid stateIndex"); efiAssertVoid(CUSTOM_ERR_6663, stateIndex < PWM_PHASE_MAX_COUNT, "invalid stateIndex");
efiAssertVoid(CUSTOM_ERR_6664, state->multiWave.waveCount <= PWM_PHASE_MAX_WAVE_PER_PWM, "invalid waveCount"); efiAssertVoid(CUSTOM_ERR_6664, state->multiWave.waveCount <= PWM_PHASE_MAX_WAVE_PER_PWM, "invalid waveCount");
for (int waveIndex = 0; waveIndex < state->multiWave.waveCount; waveIndex++) { for (int channelIndex = 0; channelIndex < state->multiWave.waveCount; channelIndex++) {
OutputPin *output = state->outputPins[waveIndex]; OutputPin *output = state->outputPins[channelIndex];
int value = state->multiWave.waves[waveIndex].pinStates[stateIndex]; int value = state->multiWave.getChannelState(channelIndex, stateIndex);
output->setValue(value); output->setValue(value);
} }
} }

View File

@ -10,10 +10,10 @@
#define S24 (720.0f / 24 / 2) #define S24 (720.0f / 24 / 2)
static float addAccordPair(TriggerShape *s, float sb, trigger_wheel_e const waveIndex DECLARE_ENGINE_PARAMETER_SUFFIX) { static float addAccordPair(TriggerShape *s, float sb, trigger_wheel_e const channelIndex DECLARE_ENGINE_PARAMETER_SUFFIX) {
s->addEvent2(sb, waveIndex, TV_RISE PASS_ENGINE_PARAMETER_SUFFIX); s->addEvent2(sb, channelIndex, TV_RISE PASS_ENGINE_PARAMETER_SUFFIX);
sb += S24; sb += S24;
s->addEvent2(sb, waveIndex, TV_FALL PASS_ENGINE_PARAMETER_SUFFIX); s->addEvent2(sb, channelIndex, TV_FALL PASS_ENGINE_PARAMETER_SUFFIX);
sb += S24; sb += S24;
return sb; return sb;

View File

@ -36,14 +36,14 @@ EXTERN_ENGINE
void TriggerEmulatorHelper::handleEmulatorCallback(PwmConfig *state, int stateIndex) { void TriggerEmulatorHelper::handleEmulatorCallback(PwmConfig *state, int stateIndex) {
int prevIndex = (stateIndex + state->phaseCount - 1) % state->phaseCount; int prevIndex = (stateIndex + state->phaseCount - 1) % state->phaseCount;
bool primaryWheelState = state->multiWave.waves[0].pinStates[prevIndex]; bool primaryWheelState = state->multiWave.getChannelState(/* channelIndex*/ 0, /*phaseIndex*/prevIndex);
int newPrimaryWheelState = state->multiWave.waves[0].pinStates[stateIndex]; int newPrimaryWheelState = state->multiWave.getChannelState(/* channelIndex*/ 0, /*phaseIndex*/stateIndex);
bool secondaryWheelState = state->multiWave.waves[1].pinStates[prevIndex]; bool secondaryWheelState = state->multiWave.getChannelState(/* channelIndex*/ 1, /*phaseIndex*/prevIndex);
int newSecondaryWheelState = state->multiWave.waves[1].pinStates[stateIndex]; int newSecondaryWheelState = state->multiWave.getChannelState(/* channelIndex*/ 1, /*phaseIndex*/stateIndex);
bool thirdWheelState = state->multiWave.waves[2].pinStates[prevIndex]; bool thirdWheelState = state->multiWave.getChannelState(/* channelIndex*/ 2, /*phaseIndex*/prevIndex);
int new3rdWheelState = state->multiWave.waves[2].pinStates[stateIndex]; int new3rdWheelState = state->multiWave.getChannelState(/* channelIndex*/ 2, /*phaseIndex*/stateIndex);
// todo: code duplication with TriggerStimulatorHelper::feedSimulatedEvent? // todo: code duplication with TriggerStimulatorHelper::feedSimulatedEvent?
@ -122,8 +122,10 @@ static void updateTriggerShapeIfNeeded(PwmConfig *state) {
TriggerShape *s = &engine->triggerCentral.triggerShape; TriggerShape *s = &engine->triggerCentral.triggerShape;
pin_state_t *pinStates[PWM_PHASE_MAX_WAVE_PER_PWM] = { s->wave.waves[0].pinStates, s->wave.waves[1].pinStates, pin_state_t *pinStates[PWM_PHASE_MAX_WAVE_PER_PWM] = {
s->wave.waves[2].pinStates }; s->wave.channels[0].pinStates,
s->wave.channels[1].pinStates,
s->wave.channels[2].pinStates };
copyPwmParameters(state, s->getSize(), s->wave.switchTimes, PWM_PHASE_MAX_WAVE_PER_PWM, pinStates); copyPwmParameters(state, s->getSize(), s->wave.switchTimes, PWM_PHASE_MAX_WAVE_PER_PWM, pinStates);
state->safe.periodNt = -1; // this would cause loop re-initialization state->safe.periodNt = -1; // this would cause loop re-initialization
} }
@ -163,8 +165,10 @@ void initTriggerEmulatorLogic(Logging *sharedLogger) {
TriggerShape *s = &engine->triggerCentral.triggerShape; TriggerShape *s = &engine->triggerCentral.triggerShape;
setTriggerEmulatorRPM(engineConfiguration->bc.triggerSimulatorFrequency PASS_ENGINE_PARAMETER_SUFFIX); setTriggerEmulatorRPM(engineConfiguration->bc.triggerSimulatorFrequency PASS_ENGINE_PARAMETER_SUFFIX);
pin_state_t *pinStates[PWM_PHASE_MAX_WAVE_PER_PWM] = { s->wave.waves[0].pinStates, s->wave.waves[1].pinStates, pin_state_t *pinStates[PWM_PHASE_MAX_WAVE_PER_PWM] = {
s->wave.waves[2].pinStates }; s->wave.channels[0].pinStates,
s->wave.channels[1].pinStates,
s->wave.channels[2].pinStates };
triggerSignal.weComplexInit("position sensor", s->getSize(), s->wave.switchTimes, PWM_PHASE_MAX_WAVE_PER_PWM, triggerSignal.weComplexInit("position sensor", s->getSize(), s->wave.switchTimes, PWM_PHASE_MAX_WAVE_PER_PWM,
pinStates, updateTriggerShapeIfNeeded, emulatorApplyPinState); pinStates, updateTriggerShapeIfNeeded, emulatorApplyPinState);

View File

@ -32,8 +32,8 @@ EXTERN_ENGINE;
trigger_shape_helper::trigger_shape_helper() { trigger_shape_helper::trigger_shape_helper() {
memset(&pinStates, 0, sizeof(pinStates)); memset(&pinStates, 0, sizeof(pinStates));
for (int i = 0; i < TRIGGER_CHANNEL_COUNT; i++) { for (int channelIndex = 0; channelIndex < TRIGGER_CHANNEL_COUNT; channelIndex++) {
waves[i].init(pinStates[i]); channels[channelIndex].init(pinStates[channelIndex]);
} }
} }
@ -41,7 +41,7 @@ TriggerShape::TriggerShape() :
wave(switchTimesBuffer, NULL) { wave(switchTimesBuffer, NULL) {
version = 0; version = 0;
initialize(OM_NONE, false); initialize(OM_NONE, false);
wave.waves = h.waves; wave.channels = h.channels;
memset(triggerIndexByAngle, 0, sizeof(triggerIndexByAngle)); memset(triggerIndexByAngle, 0, sizeof(triggerIndexByAngle));
} }
@ -280,9 +280,9 @@ angle_t TriggerShape::getAngle(int index) const {
return getCycleDuration() * crankCycle + getSwitchAngle(remainder); return getCycleDuration() * crankCycle + getSwitchAngle(remainder);
} }
void TriggerShape::addEvent3(angle_t angle, trigger_wheel_e const waveIndex, trigger_value_e const stateParam, float filterLeft, float filterRight DECLARE_ENGINE_PARAMETER_SUFFIX) { void TriggerShape::addEvent3(angle_t angle, trigger_wheel_e const channelIndex, trigger_value_e const stateParam, float filterLeft, float filterRight DECLARE_ENGINE_PARAMETER_SUFFIX) {
if (angle > filterLeft && angle < filterRight) if (angle > filterLeft && angle < filterRight)
addEvent2(angle, waveIndex, stateParam PASS_ENGINE_PARAMETER_SUFFIX); addEvent2(angle, channelIndex, stateParam PASS_ENGINE_PARAMETER_SUFFIX);
} }
operation_mode_e TriggerShape::getOperationMode() { operation_mode_e TriggerShape::getOperationMode() {
@ -296,7 +296,7 @@ extern bool printTriggerDebug;
void TriggerShape::calculateExpectedEventCounts(bool useOnlyRisingEdgeForTrigger) { void TriggerShape::calculateExpectedEventCounts(bool useOnlyRisingEdgeForTrigger) {
// todo: move the following logic from below here // todo: move the following logic from below here
// if (!useOnlyRisingEdgeForTrigger || stateParam == TV_RISE) { // if (!useOnlyRisingEdgeForTrigger || stateParam == TV_RISE) {
// expectedEventCount[waveIndex]++; // expectedEventCount[channelIndex]++;
// } // }
} }
@ -304,25 +304,25 @@ void TriggerShape::calculateExpectedEventCounts(bool useOnlyRisingEdgeForTrigger
/** /**
* Deprecated - see https://github.com/rusefi/rusefi/issues/635 * Deprecated - see https://github.com/rusefi/rusefi/issues/635
*/ */
void TriggerShape::addEvent2(angle_t angle, trigger_wheel_e const waveIndex, trigger_value_e const stateParam DECLARE_ENGINE_PARAMETER_SUFFIX) { void TriggerShape::addEvent2(angle_t angle, trigger_wheel_e const channelIndex, trigger_value_e const stateParam DECLARE_ENGINE_PARAMETER_SUFFIX) {
/** /**
* While '720' value works perfectly it has not much sense for crank sensor-only scenario. * While '720' value works perfectly it has not much sense for crank sensor-only scenario.
*/ */
addEvent(engineConfiguration->useOnlyRisingEdgeForTrigger, angle / getEngineCycle(operationMode), waveIndex, stateParam); addEvent(engineConfiguration->useOnlyRisingEdgeForTrigger, angle / getEngineCycle(operationMode), channelIndex, stateParam);
} }
// todo: the whole 'useOnlyRisingEdgeForTrigger' parameter and logic should not be here // todo: the whole 'useOnlyRisingEdgeForTrigger' parameter and logic should not be here
// todo: see calculateExpectedEventCounts // todo: see calculateExpectedEventCounts
// related calculation should be done once trigger is initialized outside of trigger shape scope // related calculation should be done once trigger is initialized outside of trigger shape scope
void TriggerShape::addEvent(bool useOnlyRisingEdgeForTrigger, angle_t angle, trigger_wheel_e const waveIndex, trigger_value_e const stateParam) { void TriggerShape::addEvent(bool useOnlyRisingEdgeForTrigger, angle_t angle, trigger_wheel_e const channelIndex, trigger_value_e const stateParam) {
efiAssertVoid(CUSTOM_OMODE_UNDEF, operationMode != OM_NONE, "operationMode not set"); efiAssertVoid(CUSTOM_OMODE_UNDEF, operationMode != OM_NONE, "operationMode not set");
efiAssertVoid(CUSTOM_ERR_6598, waveIndex!= T_SECONDARY || needSecondTriggerInput, "secondary needed or not?"); efiAssertVoid(CUSTOM_ERR_6598, channelIndex!= T_SECONDARY || needSecondTriggerInput, "secondary needed or not?");
#if EFI_UNIT_TEST || defined(__DOXYGEN__) #if EFI_UNIT_TEST || defined(__DOXYGEN__)
if (printTriggerDebug) { if (printTriggerDebug) {
printf("addEvent2 %.2f i=%d r/f=%d\r\n", angle, waveIndex, stateParam); printf("addEvent2 %.2f i=%d r/f=%d\r\n", angle, channelIndex, stateParam);
} }
#endif #endif
@ -334,13 +334,13 @@ void TriggerShape::addEvent(bool useOnlyRisingEdgeForTrigger, angle_t angle, tri
} }
#if EFI_UNIT_TEST || defined(__DOXYGEN__) #if EFI_UNIT_TEST || defined(__DOXYGEN__)
int signal = waveIndex * 1000 + stateParam; int signal = channelIndex * 1000 + stateParam;
triggerSignals[privateTriggerDefinitionSize] = signal; triggerSignals[privateTriggerDefinitionSize] = signal;
#endif #endif
if (!useOnlyRisingEdgeForTrigger || stateParam == TV_RISE) { if (!useOnlyRisingEdgeForTrigger || stateParam == TV_RISE) {
expectedEventCount[waveIndex]++; expectedEventCount[channelIndex]++;
} }
efiAssertVoid(CUSTOM_ERR_6599, angle > 0, "angle should be positive"); efiAssertVoid(CUSTOM_ERR_6599, angle > 0, "angle should be positive");
@ -355,19 +355,19 @@ void TriggerShape::addEvent(bool useOnlyRisingEdgeForTrigger, angle_t angle, tri
if (privateTriggerDefinitionSize == 0) { if (privateTriggerDefinitionSize == 0) {
privateTriggerDefinitionSize = 1; privateTriggerDefinitionSize = 1;
for (int i = 0; i < PWM_PHASE_MAX_WAVE_PER_PWM; i++) { for (int i = 0; i < PWM_PHASE_MAX_WAVE_PER_PWM; i++) {
SingleWave *wave = &this->wave.waves[i]; SingleWave *wave = &this->wave.channels[i];
if (wave->pinStates == NULL) { if (wave->pinStates == NULL) {
warning(CUSTOM_ERR_STATE_NULL, "wave pinStates is NULL"); warning(CUSTOM_ERR_STATE_NULL, "wave pinStates is NULL");
shapeDefinitionError = true; shapeDefinitionError = true;
return; return;
} }
wave->pinStates[0] = initialState[i]; wave->setState(/* channelIndex */ 0, /* value */ initialState[i]);
} }
isFrontEvent[0] = TV_RISE == stateParam; isFrontEvent[0] = TV_RISE == stateParam;
wave.setSwitchTime(0, angle); wave.setSwitchTime(0, angle);
wave.waves[waveIndex].setState(0, state); wave.channels[channelIndex].setState(/* channelIndex */ 0, /* value */ state);
return; return;
} }
@ -402,10 +402,11 @@ void TriggerShape::addEvent(bool useOnlyRisingEdgeForTrigger, angle_t angle, tri
privateTriggerDefinitionSize++; privateTriggerDefinitionSize++;
for (int i = 0; i < PWM_PHASE_MAX_WAVE_PER_PWM; i++) { for (int i = 0; i < PWM_PHASE_MAX_WAVE_PER_PWM; i++) {
wave.waves[i].pinStates[index] = wave.getChannelState(i, index - 1); int value = wave.getChannelState(/* channelIndex */i, index - 1);
wave.channels[i].setState(index, value);
} }
wave.setSwitchTime(index, angle); wave.setSwitchTime(index, angle);
wave.waves[waveIndex].setState(index, state); wave.channels[channelIndex].setState(index, state);
} }
angle_t TriggerShape::getSwitchAngle(int index) const { angle_t TriggerShape::getSwitchAngle(int index) const {

View File

@ -37,7 +37,7 @@ class trigger_shape_helper {
public: public:
trigger_shape_helper(); trigger_shape_helper();
SingleWave waves[TRIGGER_CHANNEL_COUNT]; SingleWave channels[TRIGGER_CHANNEL_COUNT];
private: private:
pin_state_t pinStates[TRIGGER_CHANNEL_COUNT][PWM_PHASE_MAX_COUNT]; pin_state_t pinStates[TRIGGER_CHANNEL_COUNT][PWM_PHASE_MAX_COUNT];
}; };
@ -175,10 +175,10 @@ public:
*/ */
int privateTriggerDefinitionSize; int privateTriggerDefinitionSize;
void addEvent(bool useOnlyRisingEdgeForTrigger, angle_t angle, trigger_wheel_e const waveIndex, trigger_value_e const state); void addEvent(bool useOnlyRisingEdgeForTrigger, angle_t angle, trigger_wheel_e const channelIndex, trigger_value_e const state);
void addEvent2(angle_t angle, trigger_wheel_e const waveIndex, trigger_value_e const state DECLARE_ENGINE_PARAMETER_SUFFIX); void addEvent2(angle_t angle, trigger_wheel_e const channelIndex, trigger_value_e const state DECLARE_ENGINE_PARAMETER_SUFFIX);
void addEvent3(angle_t angle, trigger_wheel_e const waveIndex, trigger_value_e const stateParam, float filterLeft, float filterRight DECLARE_ENGINE_PARAMETER_SUFFIX); void addEvent3(angle_t angle, trigger_wheel_e const channelIndex, trigger_value_e const stateParam, float filterLeft, float filterRight DECLARE_ENGINE_PARAMETER_SUFFIX);
operation_mode_e getOperationMode(); operation_mode_e getOperationMode();
void initialize(operation_mode_e operationMode, bool needSecondTriggerInput); void initialize(operation_mode_e operationMode, bool needSecondTriggerInput);

View File

@ -20,7 +20,7 @@ static int expectedTimeOfNextEvent;
static int pinValue = -1; static int pinValue = -1;
static void testApplyPinState(PwmConfig *state, int stateIndex) { static void testApplyPinState(PwmConfig *state, int stateIndex) {
pinValue = state->multiWave.waves[0].pinStates[stateIndex]; pinValue = state->multiWave.getChannelState(/*channelIndex*/0, stateIndex);
printf("PWM_test: setPinValue=%d @ timeNow=%d\r\n", pinValue, timeNowUs); printf("PWM_test: setPinValue=%d @ timeNow=%d\r\n", pinValue, timeNowUs);
} }