auto-sync

This commit is contained in:
rusEfi 2015-01-13 07:04:00 -06:00
parent c951cf27a9
commit d2451ff2a2
31 changed files with 91 additions and 144 deletions

View File

@ -1,17 +0,0 @@
/**
* @file ec2.h
*
* this is a mess because some code is still in C and some is
* already in C++. trigger structure is C++
* TODO: rename? merge? Do something with this file
*
* @date Apr 26, 2014
* @author Andrey Belomutskiy, (c) 2012-2015
*/
#ifndef EC2_H_
#define EC2_H_
#endif /* EC2_H_ */

View File

@ -96,13 +96,13 @@ public:
/**
* ignition dwell duration as crankshaft angle
*/
float dwellAngle;
float advance;
angle_t dwellAngle;
angle_t advance;
bool_t clutchUpState;
bool_t clutchDownState;
trigger_shape_s triggerShape;
TriggerShape triggerShape;
float angleExtra[IGNITION_PIN_COUNT];
io_pin_e ignitionPin[IGNITION_PIN_COUNT];

View File

@ -79,20 +79,7 @@ const char* getConfigurationName(engine_type_e engineType) {
return NULL;
}
}
/*
const char * ignitionModeToString(ignition_mode_e mode) {
switch (mode) {
case IM_ONE_COIL:
return "single";
case IM_INDIVIDUAL_COILS:
return "individual";
case IM_WASTED_SPARK:
return "wasted";
default:
return "unexpected";
}
}
*/
const char * pinModeToString(pin_output_mode_e mode) {
switch (mode) {
case OM_DEFAULT:
@ -107,19 +94,3 @@ const char * pinModeToString(pin_output_mode_e mode) {
return "unexpected";
}
}
/*
const char * algorithmToString(engine_load_mode_e mode) {
switch(mode) {
case LM_ALPHA_N:
return "Alpha-N";
case LM_MAF:
return "Maf";
case LM_MAP:
return "pMap";
case LM_SPEED_DENSITY:
return "SD";
default:
return "unexpected";
}
}
*/

View File

@ -11,8 +11,6 @@
#include "rusefi_enums.h"
const char* getConfigurationName(engine_type_e engineType);
const char * pinModeToString(pin_output_mode_e mode);
const char * ignitionModeToString(ignition_mode_e mode);
const char * algorithmToString(engine_load_mode_e mode);
#endif /* ENUM_STRINGS_H_ */

View File

@ -23,11 +23,11 @@ public:
* That's trigger event index
*/
uint32_t eventIndex;
float eventAngle;
angle_t eventAngle;
/**
* Angle offset from the trigger event
*/
float angleOffset;
angle_t angleOffset;
};
typedef struct {

View File

@ -23,7 +23,7 @@ public:
int *pinStates;
};
class trigger_shape_s;
class TriggerShape;
class multi_wave_s {
public:
@ -53,7 +53,7 @@ public:
};
void checkSwitchTimes2(int size, float *switchTimes);
void configureHondaAccordCD(trigger_shape_s *s, bool with3rdSignal);
void configureHondaAccordCDDip(trigger_shape_s *s);
void configureHondaAccordCD(TriggerShape *s, bool with3rdSignal);
void configureHondaAccordCDDip(TriggerShape *s);
#endif /* EFI_WAVE_H_ */

View File

@ -96,7 +96,7 @@ void setSingleCoilDwell(engine_configuration_s *engineConfiguration) {
#if EFI_ENGINE_CONTROL || defined(__DOXYGEN__)
OutputSignalList injectonSignals CCM_OPTIONAL;
void initializeIgnitionActions(float advance, float dwellAngle, IgnitionEventList *list DECLARE_ENGINE_PARAMETER_S) {
void initializeIgnitionActions(angle_t advance, angle_t dwellAngle, IgnitionEventList *list DECLARE_ENGINE_PARAMETER_S) {
efiAssertVoid(engineConfiguration->cylindersCount > 0, "cylindersCount");
list->reset();
@ -135,7 +135,7 @@ void FuelSchedule::registerInjectionEvent(io_pin_e pin, float angle, bool_t isSi
ev->isSimultanious = isSimultanious;
efiAssertVoid(TRIGGER_SHAPE(getSize()) > 0, "uninitialized trigger_shape_s");
efiAssertVoid(TRIGGER_SHAPE(getSize()) > 0, "uninitialized TriggerShape");
ev->actuator = actuator;
@ -252,13 +252,12 @@ static int findAngleIndex(float angleOffset DECLARE_ENGINE_PARAMETER_S) {
}
}
void findTriggerPosition(event_trigger_position_s *position, float angleOffset DECLARE_ENGINE_PARAMETER_S) {
void findTriggerPosition(event_trigger_position_s *position, angle_t angleOffset DECLARE_ENGINE_PARAMETER_S) {
angleOffset += CONFIG(globalTriggerAngleOffset);
fixAngle(angleOffset);
int index = triggerIndexByAngle[(int)angleOffset];
float eventAngle = TRIGGER_SHAPE(eventAngles[index]);
angle_t eventAngle = TRIGGER_SHAPE(eventAngles[index]);
if (angleOffset < eventAngle) {
firmwareError("angle constraint violation in registerActuatorEventExt(): %f/%f", angleOffset, eventAngle);
return;

View File

@ -25,7 +25,7 @@ void findTriggerPosition(
int isInjectionEnabled(engine_configuration_s *engineConfiguration);
void initializeIgnitionActions(float advance, float dwellAngle,
void initializeIgnitionActions(angle_t advance, angle_t dwellAngle,
IgnitionEventList *list DECLARE_ENGINE_PARAMETER_S);
/**

View File

@ -67,13 +67,13 @@ extern board_configuration_s *boardConfiguration;
static void printOutputs(engine_configuration_s *engineConfiguration) {
// engine_configuration2_s *engineConfiguration2
scheduleMsg(&logger, "injectionPins: mode %s", pinModeToString(boardConfiguration->injectionPinMode));
scheduleMsg(&logger, "injectionPins: mode %s", getPin_output_mode_e(boardConfiguration->injectionPinMode));
for (int i = 0; i < engineConfiguration->cylindersCount; i++) {
brain_pin_e brainPin = boardConfiguration->injectionPins[i];
scheduleMsg(&logger, "injection #%d @ %s", (1 + i), hwPortname(brainPin));
}
scheduleMsg(&logger, "ignitionPins: mode %s", pinModeToString(boardConfiguration->ignitionPinMode));
scheduleMsg(&logger, "ignitionPins: mode %s", getPin_output_mode_e(boardConfiguration->ignitionPinMode));
for (int i = 0; i < engineConfiguration->cylindersCount; i++) {
brain_pin_e brainPin = boardConfiguration->ignitionPins[i];
scheduleMsg(&logger, "ignition #%d @ %s", (1 + i), hwPortname(brainPin));
@ -82,7 +82,7 @@ static void printOutputs(engine_configuration_s *engineConfiguration) {
scheduleMsg(&logger, "idlePin: mode %s @ %s freq=%d", getPin_output_mode_e(boardConfiguration->idleValvePinMode),
hwPortname(boardConfiguration->idleValvePin), boardConfiguration->idleSolenoidFrequency);
scheduleMsg(&logger, "malfunctionIndicatorn: %s mode=%s", hwPortname(boardConfiguration->malfunctionIndicatorPin),
pinModeToString(boardConfiguration->malfunctionIndicatorPinMode));
getPin_output_mode_e(boardConfiguration->malfunctionIndicatorPinMode));
scheduleMsg(&logger, "fuelPumpPin: mode %s @ %s", getPin_output_mode_e(boardConfiguration->fuelPumpPinMode),
hwPortname(boardConfiguration->fuelPumpPin));

View File

@ -7,7 +7,7 @@
#include "trigger_bmw.h"
static inline float addPair(trigger_shape_s *s, float a, float w) {
static inline float addPair(TriggerShape *s, float a, float w) {
s->addEvent(a, T_SECONDARY, TV_HIGH);
a += w;
s->addEvent(a, T_SECONDARY, TV_LOW);
@ -15,7 +15,7 @@ static inline float addPair(trigger_shape_s *s, float a, float w) {
return a;
}
void configureMiniCooperTriggerShape(trigger_shape_s *s) {
void configureMiniCooperTriggerShape(TriggerShape *s) {
s->reset(FOUR_STROKE_CAM_SENSOR);

View File

@ -9,6 +9,6 @@
#include "engine.h"
void configureMiniCooperTriggerShape(trigger_shape_s *s);
void configureMiniCooperTriggerShape(TriggerShape *s);
#endif /* TRIGGER_BMW_H_ */

View File

@ -209,7 +209,7 @@ EXTERN_ENGINE;
static void triggerShapeInfo(Engine *engine) {
#if EFI_PROD_CODE || EFI_SIMULATOR
trigger_shape_s *s = &engine->triggerShape;
TriggerShape *s = &engine->triggerShape;
for (int i = 0; i < s->getSize(); i++) {
scheduleMsg(&logger, "event %d %f", i, s->eventAngles[i]);
}
@ -226,7 +226,7 @@ extern uint32_t maxEventQueueTime;
void triggerInfo(Engine *engine) {
#if (EFI_PROD_CODE || EFI_SIMULATOR) || defined(__DOXYGEN__)
trigger_shape_s *ts = &engine->triggerShape;
TriggerShape *ts = &engine->triggerShape;
scheduleMsg(&logger, "Template %s (%d) trigger %s (%d)",
getConfigurationName(engineConfiguration->engineType),
@ -267,16 +267,16 @@ void triggerInfo(Engine *engine) {
scheduleMsg(&logger, "primary trigger simulator: %s %s freq=%d",
hwPortname(boardConfiguration->triggerSimulatorPins[0]),
pinModeToString(boardConfiguration->triggerSimulatorPinModes[0]),
getPin_output_mode_e(boardConfiguration->triggerSimulatorPinModes[0]),
boardConfiguration->triggerSimulatorFrequency);
scheduleMsg(&logger, "secondary trigger simulator: %s %s phase=%d",
hwPortname(boardConfiguration->triggerSimulatorPins[1]),
pinModeToString(boardConfiguration->triggerSimulatorPinModes[1]), triggerSignal.safe.phaseIndex);
getPin_output_mode_e(boardConfiguration->triggerSimulatorPinModes[1]), triggerSignal.safe.phaseIndex);
scheduleMsg(&logger, "3rd trigger simulator: %s %s", hwPortname(boardConfiguration->triggerSimulatorPins[2]),
pinModeToString(boardConfiguration->triggerSimulatorPinModes[2]));
getPin_output_mode_e(boardConfiguration->triggerSimulatorPinModes[2]));
scheduleMsg(&logger, "trigger error extra LED: %s %s", hwPortname(boardConfiguration->triggerErrorPin),
pinModeToString(boardConfiguration->triggerErrorPinMode));
getPin_output_mode_e(boardConfiguration->triggerErrorPinMode));
scheduleMsg(&logger, "primary trigger input: %s", hwPortname(boardConfiguration->triggerInputPins[0]));
scheduleMsg(&logger, "secondary trigger input: %s", hwPortname(boardConfiguration->triggerInputPins[1]));

View File

@ -7,7 +7,7 @@
#include "trigger_chrysler.h"
void configureNeon2003TriggerShape(trigger_shape_s *s) {
void configureNeon2003TriggerShape(TriggerShape *s) {
s->reset(FOUR_STROKE_CAM_SENSOR);
// voodoo magic - we always need 720 at the end
@ -42,7 +42,7 @@ void configureNeon2003TriggerShape(trigger_shape_s *s) {
s->addEvent(base + 710, T_PRIMARY, TV_LOW);
}
void configureNeon1995TriggerShape(trigger_shape_s *s) {
void configureNeon1995TriggerShape(TriggerShape *s) {
s->reset(FOUR_STROKE_CAM_SENSOR);
setTriggerSynchronizationGap(s, 0.72);

View File

@ -12,7 +12,7 @@
#define CHRYSLER_NGC_GAP 2.9135
void configureNeon1995TriggerShape(trigger_shape_s *s);
void configureNeon2003TriggerShape(trigger_shape_s *s);
void configureNeon1995TriggerShape(TriggerShape *s);
void configureNeon2003TriggerShape(TriggerShape *s);
#endif /* TRIGGER_CHRYSLER_H_ */

View File

@ -228,9 +228,9 @@ void TriggerState::decodeTriggerEvent(trigger_event_e const signal, uint64_t now
toothed_previous_time = nowNt;
}
static void initializeSkippedToothTriggerShape(trigger_shape_s *s, int totalTeethCount, int skippedCount,
static void initializeSkippedToothTriggerShape(TriggerShape *s, int totalTeethCount, int skippedCount,
operation_mode_e operationMode) {
efiAssertVoid(s != NULL, "trigger_shape_s is NULL");
efiAssertVoid(s != NULL, "TriggerShape is NULL");
s->reset(operationMode);
float toothWidth = 0.5;
@ -247,7 +247,7 @@ static void initializeSkippedToothTriggerShape(trigger_shape_s *s, int totalTeet
s->addEvent(720, T_PRIMARY, TV_LOW);
}
void initializeSkippedToothTriggerShapeExt(trigger_shape_s *s, int totalTeethCount, int skippedCount,
void initializeSkippedToothTriggerShapeExt(TriggerShape *s, int totalTeethCount, int skippedCount,
operation_mode_e operationMode) {
efiAssertVoid(totalTeethCount > 0, "totalTeethCount is zero");
@ -264,7 +264,7 @@ void initializeTriggerShape(Logging *logger, engine_configuration_s const *engin
scheduleMsg(logger, "initializeTriggerShape()");
#endif
const trigger_config_s *triggerConfig = &engineConfiguration->triggerConfig;
trigger_shape_s *triggerShape = &engine->triggerShape;
TriggerShape *triggerShape = &engine->triggerShape;
setTriggerSynchronizationGap(triggerShape, 2);
triggerShape->useRiseEdge = true;
@ -351,7 +351,7 @@ TriggerStimulatorHelper::TriggerStimulatorHelper() {
thirdWheelState = false;
}
void TriggerStimulatorHelper::nextStep(TriggerState *state, trigger_shape_s * shape, int i,
void TriggerStimulatorHelper::nextStep(TriggerState *state, TriggerShape * shape, int i,
trigger_config_s const*triggerConfig DECLARE_ENGINE_PARAMETER_S) {
int stateIndex = i % shape->getSize();
@ -389,7 +389,7 @@ static void onFindIndex(TriggerState *state) {
}
}
static uint32_t doFindTrigger(TriggerStimulatorHelper *helper, trigger_shape_s * shape,
static uint32_t doFindTrigger(TriggerStimulatorHelper *helper, TriggerShape * shape,
trigger_config_s const*triggerConfig, TriggerState *state DECLARE_ENGINE_PARAMETER_S) {
for (int i = 0; i < 4 * PWM_PHASE_MAX_COUNT; i++) {
helper->nextStep(state, shape, i, triggerConfig PASS_ENGINE_PARAMETER);
@ -405,9 +405,9 @@ static uint32_t doFindTrigger(TriggerStimulatorHelper *helper, trigger_shape_s *
* Trigger shape is defined in a way which is convenient for trigger shape definition
* On the other hand, trigger decoder indexing begins from synchronization event.
*
* This function finds the index of synchronization event within trigger_shape_s
* This function finds the index of synchronization event within TriggerShape
*/
uint32_t findTriggerZeroEventIndex(trigger_shape_s * shape, trigger_config_s const*triggerConfig
uint32_t findTriggerZeroEventIndex(TriggerShape * shape, trigger_config_s const*triggerConfig
DECLARE_ENGINE_PARAMETER_S) {
TriggerState state;

View File

@ -59,7 +59,7 @@ private:
void clear();
/**
* Number of actual events within current trigger cycle
* see trigger_shape_s
* see TriggerShape
*/
uint32_t eventCount[PWM_PHASE_MAX_WAVE_PER_PWM];
trigger_event_e curSignal;
@ -76,15 +76,15 @@ private:
class TriggerStimulatorHelper {
public:
TriggerStimulatorHelper();
void nextStep(TriggerState *state, trigger_shape_s * shape, int i, trigger_config_s const*triggerConfig DECLARE_ENGINE_PARAMETER_S);
void nextStep(TriggerState *state, TriggerShape * shape, int i, trigger_config_s const*triggerConfig DECLARE_ENGINE_PARAMETER_S);
private:
bool primaryWheelState;
bool secondaryWheelState;
bool thirdWheelState;
};
void initializeSkippedToothTriggerShapeExt(trigger_shape_s *s, int totalTeethCount, int skippedCount, operation_mode_e operationMode);
uint32_t findTriggerZeroEventIndex(trigger_shape_s * shape, trigger_config_s const*triggerConfig DECLARE_ENGINE_PARAMETER_S);
void initializeSkippedToothTriggerShapeExt(TriggerShape *s, int totalTeethCount, int skippedCount, operation_mode_e operationMode);
uint32_t findTriggerZeroEventIndex(TriggerShape * shape, trigger_config_s const*triggerConfig DECLARE_ENGINE_PARAMETER_S);
class Engine;

View File

@ -95,7 +95,7 @@ static void updateTriggerShapeIfNeeded(PwmConfig *state) {
applyNonPersistentConfiguration(&logger, engine);
trigger_shape_s *s = &engine->triggerShape;
TriggerShape *s = &engine->triggerShape;
int *pinStates[PWM_PHASE_MAX_WAVE_PER_PWM] = { s->wave.waves[0].pinStates, s->wave.waves[1].pinStates,
s->wave.waves[2].pinStates };
copyPwmParameters(state, s->getSize(), s->wave.switchTimes, PWM_PHASE_MAX_WAVE_PER_PWM, pinStates);
@ -135,7 +135,7 @@ static void resumeStimulator(Engine *engine) {
void initTriggerEmulatorLogic(Engine *engine) {
initLogging(&logger, "position sensor(s) emulator");
trigger_shape_s *s = &engine->triggerShape;
TriggerShape *s = &engine->triggerShape;
setTriggerEmulatorRPM(engineConfiguration->bc.triggerSimulatorFrequency, engine);
int *pinStates[PWM_PHASE_MAX_WAVE_PER_PWM] = { s->wave.waves[0].pinStates, s->wave.waves[1].pinStates,
s->wave.waves[2].pinStates };

View File

@ -7,7 +7,7 @@
#include "trigger_gm.h"
void configureGmTriggerShape(trigger_shape_s *s) {
void configureGmTriggerShape(TriggerShape *s) {
s->reset(FOUR_STROKE_CAM_SENSOR);
// all angles are x2 here - so, 5 degree width is 10

View File

@ -10,6 +10,6 @@
#include "trigger_structure.h"
void configureGmTriggerShape(trigger_shape_s *s);
void configureGmTriggerShape(TriggerShape *s);
#endif /* TRIGGER_GM_H_ */

View File

@ -20,7 +20,7 @@
#include "trigger_mazda.h"
void initializeMazdaMiataNaShape(trigger_shape_s *s) {
void initializeMazdaMiataNaShape(TriggerShape *s) {
s->reset(FOUR_STROKE_CAM_SENSOR);
setTriggerSynchronizationGap(s, MIATA_NA_GAP);
s->useRiseEdge = false;
@ -47,7 +47,7 @@ void initializeMazdaMiataNaShape(trigger_shape_s *s) {
s->addEvent(720.0f, T_PRIMARY, TV_LOW);
}
void initializeMazdaMiataNbShape(trigger_shape_s *s) {
void initializeMazdaMiataNbShape(TriggerShape *s) {
setTriggerSynchronizationGap(s, 0.11f);
s->useRiseEdge = false;
@ -85,7 +85,7 @@ void initializeMazdaMiataNbShape(trigger_shape_s *s) {
s->addEvent(720.0f, T_PRIMARY, TV_LOW);
}
void configureMazdaProtegeLx(trigger_shape_s *s) {
void configureMazdaProtegeLx(TriggerShape *s) {
// todo: move to into configuration definition s->needSecondTriggerInput = FALSE;

View File

@ -13,8 +13,8 @@
#define MIATA_NA_GAP 1.4930f
void initializeMazdaMiataNaShape(trigger_shape_s *s);
void initializeMazdaMiataNbShape(trigger_shape_s *s);
void configureMazdaProtegeLx(trigger_shape_s *s);
void initializeMazdaMiataNaShape(TriggerShape *s);
void initializeMazdaMiataNbShape(TriggerShape *s);
void configureMazdaProtegeLx(TriggerShape *s);
#endif /* TRIGGER_MAZDA_H_ */

View File

@ -7,7 +7,7 @@
#include "trigger_mitsubishi.h"
void configureFordAspireTriggerShape(trigger_shape_s * s) {
void configureFordAspireTriggerShape(TriggerShape * s) {
s->isSynchronizationNeeded = false;
s->reset(FOUR_STROKE_CAM_SENSOR);
@ -28,7 +28,7 @@ void configureFordAspireTriggerShape(trigger_shape_s * s) {
s->addEvent(720, T_PRIMARY, TV_LOW);
}
void initializeMitsubishi4g18(trigger_shape_s *s) {
void initializeMitsubishi4g18(TriggerShape *s) {
s->reset(FOUR_STROKE_CAM_SENSOR);
s->useRiseEdge = false;

View File

@ -9,7 +9,7 @@
#include "trigger_structure.h"
void initializeMitsubishi4g18(trigger_shape_s *s);
void configureFordAspireTriggerShape(trigger_shape_s * s);
void initializeMitsubishi4g18(TriggerShape *s);
void configureFordAspireTriggerShape(TriggerShape * s);
#endif /* TRIGGER_MITSUBISHI_H_ */

View File

@ -32,7 +32,7 @@ trigger_shape_helper::trigger_shape_helper() {
}
}
trigger_shape_s::trigger_shape_s() :
TriggerShape::TriggerShape() :
wave(switchTimesBuffer, NULL) {
reset(OM_NONE);
wave.waves = h.waves;
@ -42,20 +42,20 @@ trigger_shape_s::trigger_shape_s() :
invertOnAdd = false;
}
int trigger_shape_s::getSize() const {
int TriggerShape::getSize() const {
return size;
}
int trigger_shape_s::getTriggerShapeSynchPointIndex() {
int TriggerShape::getTriggerShapeSynchPointIndex() {
return triggerShapeSynchPointIndex;
}
void trigger_shape_s::calculateTriggerSynchPoint(engine_configuration_s *engineConfiguration, Engine *engine) {
void TriggerShape::calculateTriggerSynchPoint(engine_configuration_s *engineConfiguration, Engine *engine) {
trigger_config_s const*triggerConfig = &engineConfiguration->triggerConfig;
setTriggerShapeSynchPointIndex(engineConfiguration, findTriggerZeroEventIndex(this, triggerConfig PASS_ENGINE_PARAMETER), engine);
}
void trigger_shape_s::setTriggerShapeSynchPointIndex(engine_configuration_s *engineConfiguration, int triggerShapeSynchPointIndex, Engine *engine) {
void TriggerShape::setTriggerShapeSynchPointIndex(engine_configuration_s *engineConfiguration, int triggerShapeSynchPointIndex, Engine *engine) {
this->triggerShapeSynchPointIndex = triggerShapeSynchPointIndex;
engine->engineCycleEventCount = getLength();
@ -74,7 +74,7 @@ void trigger_shape_s::setTriggerShapeSynchPointIndex(engine_configuration_s *eng
}
}
void trigger_shape_s::reset(operation_mode_e operationMode) {
void TriggerShape::reset(operation_mode_e operationMode) {
this->operationMode = operationMode;
size = 0;
triggerShapeSynchPointIndex = 0;
@ -150,11 +150,11 @@ void TriggerState::clear() {
* Trigger event count equals engine cycle event count if we have a cam sensor.
* Two trigger cycles make one engine cycle in case of a four stroke engine If we only have a cranksensor.
*/
uint32_t trigger_shape_s::getLength() const {
uint32_t TriggerShape::getLength() const {
return operationMode == FOUR_STROKE_CAM_SENSOR ? getSize() : 2 * getSize();
}
float trigger_shape_s::getAngle(int index) const {
float TriggerShape::getAngle(int index) const {
if (operationMode == FOUR_STROKE_CAM_SENSOR) {
return getSwitchAngle(index);
}
@ -173,7 +173,7 @@ float trigger_shape_s::getAngle(int index) const {
}
}
void trigger_shape_s::addEvent(float angle, trigger_wheel_e const waveIndex, trigger_value_e const stateParam) {
void TriggerShape::addEvent(float angle, trigger_wheel_e const waveIndex, trigger_value_e const stateParam) {
efiAssertVoid(operationMode != OM_NONE, "operationMode not set");
trigger_value_e state;
@ -246,11 +246,11 @@ void trigger_shape_s::addEvent(float angle, trigger_wheel_e const waveIndex, tri
wave.waves[waveIndex].pinStates[index] = state;
}
int trigger_shape_s::getCycleDuration() const {
int TriggerShape::getCycleDuration() const {
return (operationMode == FOUR_STROKE_CAM_SENSOR) ? 720 : 360;
}
float trigger_shape_s::getSwitchAngle(int index) const {
float TriggerShape::getSwitchAngle(int index) const {
return getCycleDuration() * wave.getSwitchTime(index);
}
@ -258,7 +258,7 @@ void multi_wave_s::checkSwitchTimes(int size) {
checkSwitchTimes2(size, switchTimes);
}
void setToothedWheelConfiguration(trigger_shape_s *s, int total, int skipped,
void setToothedWheelConfiguration(TriggerShape *s, int total, int skipped,
engine_configuration_s const *engineConfiguration) {
s->isSynchronizationNeeded = (skipped != 0);
@ -271,19 +271,19 @@ void setToothedWheelConfiguration(trigger_shape_s *s, int total, int skipped,
getOperationMode(engineConfiguration));
}
void setTriggerSynchronizationGap2(trigger_shape_s *s, float syncGapFrom, float syncRatioTo) {
void setTriggerSynchronizationGap2(TriggerShape *s, float syncGapFrom, float syncRatioTo) {
s->isSynchronizationNeeded = true;
s->syncRatioFrom = syncGapFrom;
s->syncRatioTo = syncRatioTo;
}
void setTriggerSynchronizationGap(trigger_shape_s *s, float synchGap) {
void setTriggerSynchronizationGap(TriggerShape *s, float synchGap) {
setTriggerSynchronizationGap2(s, synchGap * 0.75f, synchGap * 1.25f);
}
#define S24 (720.0f / 24 / 2)
static float addAccordPair(trigger_shape_s *s, float sb) {
static float addAccordPair(TriggerShape *s, float sb) {
s->addEvent(sb, T_SECONDARY, TV_HIGH);
sb += S24;
s->addEvent(sb, T_SECONDARY, TV_LOW);
@ -293,7 +293,7 @@ static float addAccordPair(trigger_shape_s *s, float sb) {
}
#define DIP 7.5f
static float addAccordPair3(trigger_shape_s *s, float sb) {
static float addAccordPair3(TriggerShape *s, float sb) {
sb += DIP;
s->addEvent(sb, T_CHANNEL_3, TV_HIGH);
sb += DIP;
@ -306,7 +306,7 @@ static float addAccordPair3(trigger_shape_s *s, float sb) {
* Thank you Dip!
* http://forum.pgmfi.org/viewtopic.php?f=2&t=15570start=210#p139007
*/
void configureHondaAccordCDDip(trigger_shape_s *s) {
void configureHondaAccordCDDip(TriggerShape *s) {
s->reset(FOUR_STROKE_CAM_SENSOR);
s->initialState[T_SECONDARY] = TV_HIGH;
@ -369,7 +369,7 @@ void configureHondaAccordCDDip(trigger_shape_s *s) {
s->isSynchronizationNeeded = false;
}
void configureHondaAccordCD(trigger_shape_s *s, bool with3rdSignal) {
void configureHondaAccordCD(TriggerShape *s, bool with3rdSignal) {
s->reset(FOUR_STROKE_CAM_SENSOR);
float sb = 5.0f;

View File

@ -14,7 +14,7 @@
#include "EfiWave.h"
#include "engine_configuration.h"
class trigger_shape_s;
class TriggerShape;
#define TRIGGER_CHANNEL_COUNT 3
@ -28,9 +28,9 @@ public:
class Engine;
class trigger_shape_s {
class TriggerShape {
public:
trigger_shape_s();
TriggerShape();
bool_t isSynchronizationNeeded;
int totalToothCount;
@ -92,7 +92,7 @@ private:
trigger_shape_helper h;
/**
* index of synchronization event within trigger_shape_s
* index of synchronization event within TriggerShape
* See findTriggerZeroEventIndex()
*/
int triggerShapeSynchPointIndex;
@ -120,8 +120,8 @@ private:
int getCycleDuration() const;
};
void setTriggerSynchronizationGap(trigger_shape_s *s, float synchGap);
void setTriggerSynchronizationGap2(trigger_shape_s *s, float syncGapFrom, float syncRatioTo);
void setToothedWheelConfiguration(trigger_shape_s *s, int total, int skipped, engine_configuration_s const *engineConfiguration);
void setTriggerSynchronizationGap(TriggerShape *s, float synchGap);
void setTriggerSynchronizationGap2(TriggerShape *s, float syncGapFrom, float syncRatioTo);
void setToothedWheelConfiguration(TriggerShape *s, int total, int skipped, engine_configuration_s const *engineConfiguration);
#endif /* TRIGGER_STRUCTURE_H_ */

View File

@ -267,5 +267,5 @@ int getRusEfiVersion(void) {
return 1; // this is here to make the compiler happy about the unused array
if (UNUSED_CCM_SIZE == 0)
return 1; // this is here to make the compiler happy about the unused array
return 20150112;
return 20150113;
}

View File

@ -12,7 +12,6 @@
#include "main.h"
#include "error_handling.h"
#include "ec2.h"
#include "test_accel_enrichment.h"
#include "test_interpolation_3d.h"
#include "test_find_index.h"

View File

@ -9,7 +9,6 @@
#include "main.h"
#include "engine_math.h"
#include "engine_configuration.h"
#include "ec2.h"
#include "map.h"
#include "speed_density.h"

View File

@ -12,7 +12,6 @@
#include "trigger_structure.h"
#include "allsensors.h"
#include "engine_math.h"
#include "ec2.h"
#include "trigger_decoder.h"
#include "engine_test_helper.h"
#include "efiGpio.h"
@ -105,7 +104,7 @@ void testFuelMap(void) {
extern engine_configuration_s *engineConfiguration;
extern engine_configuration2_s *engineConfiguration2;
static void confgiureFordAspireTriggerShape(trigger_shape_s * s) {
static void confgiureFordAspireTriggerShape(TriggerShape * s) {
s->reset(FOUR_STROKE_CAM_SENSOR);
s->addEvent(53.747, T_SECONDARY, TV_HIGH);
@ -159,7 +158,7 @@ void testAngleResolver(void) {
engineConfiguration->globalTriggerAngleOffset = 175;
assertTrue(engine->engineConfiguration2!=NULL);
trigger_shape_s * ts = &engine->triggerShape;
TriggerShape * ts = &engine->triggerShape;
confgiureFordAspireTriggerShape(ts);

View File

@ -48,7 +48,7 @@ int getTheAngle(engine_type_e engineType) {
engine_configuration_s *engineConfiguration = eth.ec;
initDataStructures(PASS_ENGINE_PARAMETER_F);
trigger_shape_s * shape = &eth.engine.triggerShape;
TriggerShape * shape = &eth.engine.triggerShape;
return findTriggerZeroEventIndex(shape, &engineConfiguration->triggerConfig PASS_ENGINE_PARAMETER);
}
@ -61,7 +61,7 @@ static void testDodgeNeonDecoder(void) {
EngineTestHelper eth(DODGE_NEON_1995);
engine_configuration_s *ec = eth.ec;
trigger_shape_s * shape = &eth.engine.triggerShape;
TriggerShape * shape = &eth.engine.triggerShape;
assertEquals(8, shape->getTriggerShapeSynchPointIndex());
TriggerState state;
@ -120,7 +120,7 @@ static void test1995FordInline6TriggerDecoder(void) {
engine_configuration_s *engineConfiguration = eth.engine.engineConfiguration;
Engine *engine = &eth.engine;
trigger_shape_s * shape = &eth.engine.triggerShape;
TriggerShape * shape = &eth.engine.triggerShape;
assertEqualsM("triggerShapeSynchPointIndex", 0, shape->getTriggerShapeSynchPointIndex());
@ -212,7 +212,7 @@ void testMazdaMianaNbDecoder(void) {
engine_configuration_s *ec = eth.ec;
Engine *engine = &eth.engine;
engine_configuration_s *engineConfiguration = ec;
trigger_shape_s * shape = &eth.engine.triggerShape;
TriggerShape * shape = &eth.engine.triggerShape;
assertEquals(11, shape->getTriggerShapeSynchPointIndex());
TriggerState state;
@ -298,7 +298,7 @@ static void testTriggerDecoder2(const char *msg, engine_type_e type, int synchPo
initSpeedDensity(ec);
trigger_shape_s *t = &eth.engine.triggerShape;
TriggerShape *t = &eth.engine.triggerShape;
assertEqualsM("synchPointIndex", synchPointIndex, t->getTriggerShapeSynchPointIndex());
@ -324,7 +324,7 @@ void testGY6_139QMB(void) {
TriggerState state;
assertFalseM("shaft_is_synchronized", state.shaft_is_synchronized);
trigger_shape_s * shape = &eth.engine.triggerShape;
TriggerShape * shape = &eth.engine.triggerShape;
assertFalseM("shaft_is_synchronized", state.shaft_is_synchronized);
assertEquals(0, state.getCurrentIndex());
@ -500,7 +500,7 @@ void testTriggerDecoder(void) {
printf("*************************************************** testTriggerDecoder\r\n");
Engine engine;
trigger_shape_s * s = &engine.triggerShape;
TriggerShape * s = &engine.triggerShape;
initializeSkippedToothTriggerShapeExt(s, 2, 0, FOUR_STROKE_CAM_SENSOR);

View File

@ -11,7 +11,6 @@
#include "console_io.h"
#include "eficonsole.h"
#include "engine_configuration.h"
#include "ec2.h"
#include "rusefi_enums.h"
#include "pwm_generator_logic.h"
#include "trigger_central.h"