diff --git a/ESP32/include/ABSOscillation.h b/ESP32/include/ABSOscillation.h index 44a07424..96cb5551 100644 --- a/ESP32/include/ABSOscillation.h +++ b/ESP32/include/ABSOscillation.h @@ -31,7 +31,7 @@ class ABSOscillation { long timeNowMillis = millis(); float timeSinceTrigger = (timeNowMillis - _timeLastTriggerMillis); - float absForceOffset_local = 0; + float absForceOffset_local = 0.00f; if (timeSinceTrigger > ABS_ACTIVE_TIME_PER_TRIGGER_MILLIS) { @@ -50,7 +50,7 @@ class ABSOscillation { absAmp_fl32 = calcVars_st->absAmplitude; break; case 1: - absAmp_fl32 = calcVars_st->stepperPosRange * calcVars_st->absAmplitude / 100.; + absAmp_fl32 = calcVars_st->stepperPosRange * calcVars_st->absAmplitude / 100.0f; break; default: break; @@ -61,13 +61,13 @@ class ABSOscillation { switch (absPattern) { case 0: // sine wave pattern - absForceOffset_local = absAmp_fl32 * sin(2 * PI * calcVars_st->absFrequency * absTimeSeconds); + absForceOffset_local = absAmp_fl32 * sin(2.0f * PI * calcVars_st->absFrequency * absTimeSeconds); break; case 1: // sawtooth pattern - if (calcVars_st->absFrequency > 0) + if (calcVars_st->absFrequency > 0.0f) { - absForceOffset_local = absAmp_fl32 * fmod(absTimeSeconds, 1.0 / (float)calcVars_st->absFrequency) * (float)calcVars_st->absFrequency; + absForceOffset_local = absAmp_fl32 * fmod(absTimeSeconds, 1.0f / (float)calcVars_st->absFrequency) * (float)calcVars_st->absFrequency; absForceOffset_local -= absAmp_fl32 * 0.5f; // make it symmetrical around 0 } break; @@ -78,10 +78,10 @@ class ABSOscillation { switch (absForceOrTarvelBit) { case 0: *absForceOffset = absForceOffset_local; - *absPosOffset = 0; + *absPosOffset = 0.0f; break; case 1: - *absForceOffset = 0; + *absForceOffset = 0.0f; *absPosOffset = absForceOffset_local; break; default: @@ -108,7 +108,7 @@ class RPMOscillation { RPMOscillation() : _timeLastTriggerMillis(0) {} - float RPM_value =0; + float RPM_value =0.0f; int32_t RPM_position_offset = 0; public: void trigger() { @@ -120,13 +120,13 @@ class RPMOscillation { long timeNowMillis = millis(); float timeSinceTrigger = (timeNowMillis - _timeLastTriggerMillis); - float RPMForceOffset = 0; + float RPMForceOffset = 0.0f; float RPM_max_freq = calcVars_st->RPM_max_freq; float RPM_min_freq = calcVars_st->RPM_min_freq; //float RPM_max =10; float RPM_amp_base = calcVars_st->RPM_AMP; float RPM_amp=0; - RPM_amp=RPM_amp_base*(1.0f+0.3*RPM_value/100.0f); + RPM_amp=RPM_amp_base*(1.0f+0.3f*RPM_value/100.0f); if(RPM_value==0) { RPM_min_freq=0; @@ -188,7 +188,7 @@ class BitePointOscillation { long timeNowMillis = millis(); float timeSinceTrigger = (timeNowMillis - _timeLastTriggerMillis); - float BitePointForceOffset = 0; + float BitePointForceOffset = 0.0f; float BP_freq = calcVars_st->BP_freq; //float BP_freq = 15; float BP_amp = calcVars_st->BP_amp; @@ -205,7 +205,7 @@ class BitePointOscillation { float BPTimeSeconds = _BiteTimeMillis / 1000.0f; //RPMForceOffset = calcVars_st->absAmplitude * sin(calcVars_st->absFrequency * RPMTimeSeconds); - BitePointForceOffset = BP_amp * sin( 2*PI* BP_freq* BPTimeSeconds); + BitePointForceOffset = BP_amp * sin( 2.0f*PI* BP_freq* BPTimeSeconds); } BitePoint_Force_offset=BitePointForceOffset; _lastCallTimeMillis = timeNowMillis; @@ -247,13 +247,13 @@ MovingAverageFilter::MovingAverageFilter(unsigned int newDataPointsCount) for (i = 0; i < dataPointsCount; i++) { - values[i] = 0; // fill the array with 0's + values[i] = 0.0f; // fill the array with 0's } } float MovingAverageFilter::process(float in) { - out = 0; + out = 0.0f; values[k] = in; k = (k + 1) % dataPointsCount; @@ -263,7 +263,7 @@ float MovingAverageFilter::process(float in) out += values[i]; } - float retValue= 0; + float retValue= 0.0f; if (dataPointsCount> 0) { retValue= out / dataPointsCount; @@ -294,7 +294,7 @@ class G_force_effect } else { - G_force_raw=10*(G_value)*G_multiplier/9.8; + G_force_raw=10.0f*(G_value)*G_multiplier/9.8f; //G_force_raw=constrain(G_force_raw,-1*Force_Range*0.25,Force_Range*0.25); } @@ -317,7 +317,7 @@ class WSOscillation { : _timeLastTriggerMillis(0) {} //float RPM_value =0; - float WS_Force_offset = 0; + float WS_Force_offset = 0.0f; public: void trigger() { _timeLastTriggerMillis = millis(); @@ -328,7 +328,7 @@ class WSOscillation { long timeNowMillis = millis(); float timeSinceTrigger = (timeNowMillis - _timeLastTriggerMillis); - float WSForceOffset = 0; + float WSForceOffset = 0.0f; float WS_freq = calcVars_st->WS_freq; //float BP_freq = 15; float WS_amp = calcVars_st->WS_amp; @@ -337,7 +337,7 @@ class WSOscillation { if (timeSinceTrigger > WS_ACTIVE_TIME_PER_TRIGGER_MILLIS) { _WSTimeMillis = 0; - WSForceOffset = 0; + WSForceOffset = 0.0f; } else { @@ -345,7 +345,7 @@ class WSOscillation { float WSTimeSeconds = _WSTimeMillis / 1000.0f; //RPMForceOffset = calcVars_st->absAmplitude * sin(calcVars_st->absFrequency * RPMTimeSeconds); - WSForceOffset = WS_amp * sin( 2*PI* WS_freq* WSTimeSeconds); + WSForceOffset = WS_amp * sin( 2.0f*PI* WS_freq* WSTimeSeconds); /*if (WS_freq > 0) { //WSForceOffset = WS_amp * fmod(WSTimeSeconds, 1.0 / (float)WS_freq) * WS_freq; @@ -376,10 +376,10 @@ class Road_impact_effect void forceOffset(DAP_calculationVariables_st* calcVars_st, uint8_t Road_impact_multi) { uint32_t Force_Range; - float Road_multiplier=((float)Road_impact_multi)/100; + float Road_multiplier=((float)Road_impact_multi)/100.0f; Force_Range=calcVars_st->Force_Range; //Road_multiplier=0.1; - Road_Impact_force_raw=0.3*Road_multiplier*((float)Force_Range)*((float)Road_Impact_value)/100; + Road_Impact_force_raw=0.3f*Road_multiplier*((float)Force_Range)*((float)Road_Impact_value)/100; //apply filter Road_Impact_force=movingAverageFilter_roadimpact.process(Road_Impact_force_raw); @@ -400,7 +400,7 @@ class Custom_vibration { : _timeLastTriggerMillis(0) {} //float RPM_value =0; - float CV_Force_offset = 0; + float CV_Force_offset = 0.0f; public: void trigger() { _timeLastTriggerMillis = millis(); @@ -411,20 +411,20 @@ class Custom_vibration { long timeNowMillis = millis(); float timeSinceTrigger = (timeNowMillis - _timeLastTriggerMillis); - float CVForceOffset = 0; + float CVForceOffset = 0.0f; if (timeSinceTrigger > CV_ACTIVE_TIME_PER_TRIGGER_MILLIS) { _CVTimeMillis = 0; - CVForceOffset = 0; + CVForceOffset = 0.0f; } else { _CVTimeMillis += timeNowMillis - _lastCallTimeMillis; float CVTimeSeconds = _CVTimeMillis / 1000.0f; - CVForceOffset = CV_amp/20.0f * sin( 2*PI* CV_freq* CVTimeSeconds); + CVForceOffset = CV_amp/20.0f * sin( 2.0f*PI* CV_freq* CVTimeSeconds); @@ -464,13 +464,13 @@ class Rudder{ endpos_travel=(float)calcVars_st->stepperPosRange; position_ratio_current=((float)(current_pedal_position-calcVars_st->stepperPosMin))/endpos_travel; dead_zone=20; - Center_offset=calcVars_st->stepperPosMin+ calcVars_st->stepperPosRange/2; - float center_deadzone = 0.51; + Center_offset=calcVars_st->stepperPosMin+ calcVars_st->stepperPosRange/2.0f; + float center_deadzone = 0.51f; if(calcVars_st->Rudder_status) { if(position_ratio_sync>center_deadzone) { - offset_raw=(int32_t)(-1*(position_ratio_sync-0.50)*endpos_travel); + offset_raw=(int32_t)(-1*(position_ratio_sync-0.50f)*endpos_travel); } else @@ -492,9 +492,9 @@ class Rudder{ void force_offset_calculate(DAP_calculationVariables_st* calcVars_st) { dead_zone=20; - Center_offset=calcVars_st->stepperPosRange/2; - dead_zone_upper=Center_offset+dead_zone/2; - dead_zone_lower=Center_offset-dead_zone/2; + Center_offset=calcVars_st->stepperPosRange/2.0f; + dead_zone_upper=Center_offset+dead_zone/2.0f; + dead_zone_lower=Center_offset-dead_zone/2.0f; sync_pedal_position=calcVars_st->sync_pedal_position; current_pedal_position=calcVars_st->current_pedal_position; stepper_range=calcVars_st->stepperPosRange; @@ -506,23 +506,23 @@ class Rudder{ position_ratio_current=((float)(current_pedal_position-calcVars_st->stepperPosMin))/endpos_travel; - float center_deadzone = 0.51; + float center_deadzone = 0.51f; if(calcVars_st->Rudder_status) { if(position_ratio_sync>center_deadzone) { - force_offset_raw=(float)(-1*(position_ratio_sync-0.50)*force_range); + force_offset_raw=(float)(-1.0f*(position_ratio_sync-0.50f)*force_range); } else { - force_offset_raw=0; + force_offset_raw=0.0f; } if(calcVars_st->rudder_brake_status) { - force_offset_raw=0; + force_offset_raw=0.0f; } force_offset_filter=averagefilter_rudder_force.process(force_offset_raw+force_center_offset); diff --git a/ESP32/include/Main.h b/ESP32/include/Main.h index 1cbfff7b..7b459176 100644 --- a/ESP32/include/Main.h +++ b/ESP32/include/Main.h @@ -50,9 +50,9 @@ /********************************************************************/ /* Loadcell defines */ /********************************************************************/ -#define LOADCELL_WEIGHT_RATING_KG 300.0 -#define LOADCELL_EXCITATION_V 5.0 -#define LOADCELL_SENSITIVITY_MV_V 2.0 +#define LOADCELL_WEIGHT_RATING_KG 300.0f +#define LOADCELL_EXCITATION_V 5.0f +#define LOADCELL_SENSITIVITY_MV_V 2.0f /********************************************************************/ diff --git a/ESP32/include/StepperMovementStrategy.h b/ESP32/include/StepperMovementStrategy.h index 16448acb..b7459381 100644 --- a/ESP32/include/StepperMovementStrategy.h +++ b/ESP32/include/StepperMovementStrategy.h @@ -11,7 +11,7 @@ float Setpoint, Input, Output; //Specify the links and initial tuning parameters -double Kp=0.3, Ki=50.0, Kd=0.000; +float Kp=0.3f, Ki=50.0f, Kd=0.000f; uint8_t control_strategy_u8 = 0; QuickPID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, /* OPTIONS */ myPID.pMode::pOnError, /* pOnError, pOnMeas, pOnErrorMeas */ @@ -86,10 +86,10 @@ int32_t MoveByPidStrategy(float loadCellReadingKg, float stepperPosFraction, Ste // clamp the stepper position to prevent problems with the spline - float stepperPosFraction_constrained = constrain(stepperPosFraction, 0, 1); + float stepperPosFraction_constrained = constrain(stepperPosFraction, 0.0f, 1.0f); // constrain the output to the correct positioning interval to prevent PID windup - float neg_output_limit_fl32 = 1.0 - stepperPosFraction_constrained; + float neg_output_limit_fl32 = 1.0f - stepperPosFraction_constrained; float pos_output_limit_fl32 = stepperPosFraction_constrained; if (pos_output_limit_fl32 < PID_OUTPUT_LIMIT_FL32) { @@ -126,12 +126,12 @@ int32_t MoveByPidStrategy(float loadCellReadingKg, float stepperPosFraction, Ste float gradient_fl32 = gradient_orig_fl32; float gradient_abs_fl32 = fabs(gradient_fl32); - float gain_modifier_fl32 = 10.0; - if (gradient_abs_fl32 > 1e-5) + float gain_modifier_fl32 = 10.0f; + if (gradient_abs_fl32 > 1e-5f) { - gain_modifier_fl32 = 1.0 / pow( gradient_abs_fl32 , 1); + gain_modifier_fl32 = 1.0f / pow( gradient_abs_fl32 , 1.0f); } - gain_modifier_fl32 = constrain( gain_modifier_fl32, 0.1, 10); + gain_modifier_fl32 = constrain( gain_modifier_fl32, 0.1f, 10.0f); myPID.SetTunings(gain_modifier_fl32 * Kp, gain_modifier_fl32 * Ki, gain_modifier_fl32 * Kd); } @@ -154,13 +154,14 @@ int32_t MoveByPidStrategy(float loadCellReadingKg, float stepperPosFraction, Ste // https://www.youtube.com/watch?v=XaD8Lngfkzk // https://github.com/pronenewbits/Arduino_Constrained_MPC_Library - if (calc_st->Force_Range > 0.001) + if (calc_st->Force_Range > 0.001f) { Input = ( loadCellReadingKg_clip - calc_st->Force_Min) / calc_st->Force_Range; Setpoint = ( loadCellTargetKg_clip - calc_st->Force_Min) / calc_st->Force_Range; } else { + Input = 0.0f; Input = 0; Setpoint= 0; } @@ -194,9 +195,17 @@ int32_t MoveByPidStrategy(float loadCellReadingKg, float stepperPosFraction, Ste return posStepperNew; } - +unsigned long lastTime = 0; +float output = 0.0f; // PID-Ausgang +float filteredOutput = 0.0f; +bool expFilterHasBeenInitialized = false; +// Filter-Variablen +float RC = 1.0f / (2.0f * 3.14159f * 100.0f); // RC für 20 Hz Eckfrequenz int printStep = 0; + +float posArray[10] = {0.0f}; +uint8_t arrayIndex = 0; int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* stepper, ForceCurve_Interpolated* forceCurve, const DAP_calculationVariables_st* calc_st, DAP_config_st* config_st, float absForceOffset_fl32, float changeVelocity, float d_phi_d_x, float d_x_hor_d_phi) { // see https://github.com/ChrGri/DIY-Sim-Racing-FFB-Pedal/wiki/Movement-control-strategies#mpc @@ -215,15 +224,52 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* f(x_n) = -k1 * x + b - forceCurve(x) f'(x_n) = -k1 - d(forceCurve(x)) / dx */ + + // get current stepper position float stepperPos = stepper->getCurrentPositionFromMin(); + // float lagedPos; + + // posArray[arrayIndex] = stepperPos; + // arrayIndex++; + // arrayIndex %= 10; + + // lagedPos = + + + + // for (uint8_t aryIdx = 1; aryIdx <= 9; aryIdx++) + // { + // posArray[aryIdx-1] = posArray[aryIdx]; + // } + // posArray[9] = stepperPos; + + // uint8_t lag = 9-2; + // stepperPos = posArray[lag]; + + + // stepperPos = posArray[lag]; + + + // // get iSVs position + // float stepperPos2 = stepper->getServosInternalPositionCorrected() - stepper->getMinPosition(); + // stepperPos = stepperPos2; + + // Serial.printf("ESP pos: %f, iSV pos: %f\n", stepperPos, stepperPos2); + // delay(20); + + if (false == expFilterHasBeenInitialized) + { + filteredOutput = stepperPos; + expFilterHasBeenInitialized = true; + } // get current stepper velocity int32_t currentSpeedInMilliHz = stepper->getCurrentSpeedInMilliHz(); uint32_t maxSpeedInMilliHz = stepper->getMaxSpeedInMilliHz(); float speedNormalized_fl32 = ( (float)currentSpeedInMilliHz ) / ((float)maxSpeedInMilliHz) ; // 250000000 --> 250 - float speedAbsNormalized_fl32 = constrain( fabsf(speedNormalized_fl32), 0.0f, 1.0f); + float speedAbsNormalized_fl32 = constrain( fabsf(speedNormalized_fl32), 0.1f, 1.0f); float oneMinusSpeedNormalized_fl32 = 1.0f - speedAbsNormalized_fl32; // motion corrected loadcell reading @@ -252,8 +298,8 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* float mm_per_motor_rev = config_st->payLoadPedalConfig_.spindlePitch_mmPerRev_u8;//TRAVEL_PER_ROTATION_IN_MM; float steps_per_motor_rev = (float)calc_st->stepsPerMotorRevolution; //(float)STEPS_PER_MOTOR_REVOLUTION; - float mmPerStep = 0; - if (steps_per_motor_rev > 0) + float mmPerStep = 0.0f; + if (steps_per_motor_rev > 0.0f) { mmPerStep = mm_per_motor_rev / steps_per_motor_rev ; } @@ -305,7 +351,7 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* float stepperPosFraction = stepper->getCurrentPositionFractionFromExternalPos( stepperPos ); // clamp the stepper position to prevent problems with the spline - float x_0 = constrain(stepperPosFraction, 0, 1); + float x_0 = constrain(stepperPosFraction, 0.0f, 1.0f); // get force and force gradient of force vs travel curve float loadCellTargetKg = forceCurve->EvalForceCubicSpline(config_st, calc_st, x_0); @@ -340,6 +386,8 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* // Translational foot model // given in kg/step float m1 = d_f_d_x_hor * d_x_hor_d_step; + + // m1 *= oneMinusSpeedNormalized_fl32; // gradient of the force curve // given in kg/step @@ -353,7 +401,7 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* // float denom = (m1 - m2) * (1.0f - config_st->payLoadPedalConfig_.MPC_1st_order_gain * fabsf(m1) / speedAbsNormalized_fl32 ); float denom = m1 - m2;// - velocityDependingForceInKg_fl32;//config_st->payLoadPedalConfig_.MPC_1st_order_gain * oneMinusSpeedNormalized_fl32; - if ( fabs(denom) > 0 ) + if ( fabsf(denom) > 0.0f ) { // https://en.wikipedia.org/wiki/Newton%27s_method // Newton algorithm @@ -374,7 +422,7 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* stepperPos += stepUpdate; // stop iteration - if (abs(stepUpdate) < 2) + if (fabsf(stepUpdate) < 2.0f) { break; } @@ -382,6 +430,21 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* } } + // unsigned long now = micros(); + // float deltaTime = ( (float)(now - lastTime) ) / 1000000.0f; // in Sekunden + // lastTime = now; + + + + // // Filter-Koeffizient berechnen + // float alpha = deltaTime / (deltaTime + RC); + + // output = stepperPos;// - stepperPos_initial; + + // // Tiefpassfilter anwenden + // filteredOutput = alpha * output + (1.0 - alpha) * filteredOutput; + + // stepperPos = filteredOutput; // Serial.printf("0:%i, 1:%i, 2:%i, 3:%i, 4:%i\n", stepUpdates[0], stepUpdates[1], stepUpdates[2], stepUpdates[3], stepUpdates[4]); // delay(20); @@ -399,136 +462,6 @@ int32_t MoveByForceTargetingStrategy(float loadCellReadingKg, StepperWithLimits* -int32_t MoveByForceTargetingStrategy_old(float loadCellReadingKg, StepperWithLimits* stepper, ForceCurve_Interpolated* forceCurve, const DAP_calculationVariables_st* calc_st, DAP_config_st* config_st, float absForceOffset_fl32, float changeVelocity, float d_phi_d_x, float d_x_hor_d_phi) { - // see https://github.com/ChrGri/DIY-Sim-Racing-FFB-Pedal/wiki/Movement-control-strategies#mpc - - - /* - This closed-loop control strategy models the foot as a spring with a certain stiffness k1. - The force resulting from that model is F1 = k1 * x. - To find the servo target position: - 1) A line with the slope -k1 at the point of the loadcell reading & current position is drawn. - 2) The intersection with the force-travel curve gives the target position - - Since the force-travel curve might be non-linear, Newtons method is used to numerically find the intersection point. - f(x_n) = -k1 * x + b - forceCurve(x) = 0 - x_n+1 = x_n - f(x_n) / f'(x_n) - whereas x_n is the servo position at iteration n - f(x_n) = -k1 * x + b - forceCurve(x) - f'(x_n) = -k1 - d(forceCurve(x)) / dx - */ - - // get current stepper position - // float stepperPos = stepper->getCurrentPosition(); - float stepperPos = stepper->getCurrentPositionFromMin(); - - // add velocity feedforward - //stepperPos += changeVelocity * config_st->payLoadPedalConfig_.PID_velocity_feedforward_gain; - - // motion corrected loadcell reading - float loadCellReadingKg_corrected = loadCellReadingKg; - //loadCellReadingKg_corrected += config_st->payLoadPedalConfig_.MPC_1st_order_gain * stepper_vel_filtered_fl32 / STEPS_PER_MOTOR_REVOLUTION / 10;// + stepper_accel_filtered_fl32; - //loadCellReadingKg_corrected += config_st->payLoadPedalConfig_.MPC_1st_order_gain * stepper_accel_filtered_fl32 / STEPS_PER_MOTOR_REVOLUTION / 10;// + stepper_accel_filtered_fl32; - - - // set initial guess - float stepperPos_initial = stepperPos; - - // Find the intersections of the force curve and the foot model via Newtons-method - #define MAX_NUMBER_OF_NEWTON_STEPS 5 - for (uint8_t iterationIdx = 0; iterationIdx < MAX_NUMBER_OF_NEWTON_STEPS; iterationIdx++) - { - //float stepperPosFraction = stepper->getCurrentPositionFraction(); - float stepperPosFraction = stepper->getCurrentPositionFractionFromExternalPos( stepperPos ); - - // clamp the stepper position to prevent problems with the spline - float x_0 = constrain(stepperPosFraction, 0, 1); - - // get force and force gradient of force vs travel curve - float loadCellTargetKg = forceCurve->EvalForceCubicSpline(config_st, calc_st, x_0); - float gradient_force_curve_fl32 = forceCurve->EvalForceGradientCubicSpline(config_st, calc_st, x_0, false); - - // apply effect force offset - loadCellTargetKg -= absForceOffset_fl32; - - // how many mm movement to order if 1kg of error force is detected - // this can be tuned for responsiveness vs oscillation - float mm_per_motor_rev = config_st->payLoadPedalConfig_.spindlePitch_mmPerRev_u8;//TRAVEL_PER_ROTATION_IN_MM; - float steps_per_motor_rev = (float)calc_st->stepsPerMotorRevolution;; - - // foot spring stiffness - float d_f_d_phi = -config_st->payLoadPedalConfig_.MPC_0th_order_gain; - - float move_mm_per_kg = config_st->payLoadPedalConfig_.MPC_0th_order_gain; - float MOVE_STEPS_FOR_1KG = (move_mm_per_kg / mm_per_motor_rev) * steps_per_motor_rev; - - - - // make stiffness dependent on force curve gradient - // less steps per kg --> steeper line - float gradient_normalized_force_curve_fl32 = forceCurve->EvalForceGradientCubicSpline(config_st, calc_st, x_0, true); - gradient_normalized_force_curve_fl32 = constrain(gradient_normalized_force_curve_fl32, 0.05, 1); - - float mmPerStep = 0; - if (steps_per_motor_rev > 0) - { - mmPerStep = mm_per_motor_rev / steps_per_motor_rev ; - } - - - - // The foot is modeled to be of proportional resistance with respect to deflection. Since the deflection depends on the pedal kinematics, the kinematic must be respected here - // This is accomplished with the forceGain variable - /*float forceGain_abs = fabs( d_phi_d_x ); - if (forceGain_abs > 0) - { - MOVE_STEPS_FOR_1KG *= fabs( forceGain ); - }*/ - - - - // angular foot model - // m1 = d_f_d_x dForce / dx - //float m1 = d_f_d_phi * (-d_phi_d_x); - - - // Translational foot model - // given in kg/step - float m1 = d_f_d_phi * (-d_x_hor_d_phi) * (-d_phi_d_x) * mmPerStep; - - // smoothen gradient with force curve gradient since it had better results w/ clutch pedal characteristic - //m1 /= gradient_normalized_force_curve_fl32; - - // gradient of the force curve - // given in kg/step - float m2 = gradient_force_curve_fl32; - - // Newton update - float denom = m1 - m2; - if ( fabs(denom) > 0 ) - { - float stepUpdate = ( loadCellReadingKg_corrected - loadCellTargetKg) / ( denom ); - - // smoothen update with force curve gradient since it had better results w/ clutch pedal characteristic - stepUpdate *= gradient_normalized_force_curve_fl32; - - stepperPos -= stepUpdate; - } - } - - // read the min position - stepperPos += stepper->getMinPosition(); - - // limit the position update - float deltaMax = 0.5 * (float)(calc_st->stepperPosMax - calc_st->stepperPosMin); - int32_t posStepperNew = constrain(stepperPos, stepperPos_initial-deltaMax, stepperPos_initial+deltaMax ); - - // clamp target position to range - posStepperNew = constrain(posStepperNew,calc_st->stepperPosMin,calc_st->stepperPosMax ); - - return posStepperNew; -} - // int32_t mpcBasedMove(float loadCellReadingKg, float stepperPosFraction, StepperWithLimits* stepper, ForceCurve_Interpolated* forceCurve, const DAP_calculationVariables_st* calc_st, DAP_config_st* config_st, float absForceOffset_fl32) // { @@ -631,8 +564,8 @@ void measureStepResponse(StepperWithLimits* stepper, const DAP_calculationVariab { int32_t currentPos = stepper->getCurrentPositionFromMin(); - int32_t minPos = currentPos - dap_calculationVariables_st.stepperPosRange * 0.05; - int32_t maxPos = currentPos + dap_calculationVariables_st.stepperPosRange * 0.05; + int32_t minPos = currentPos - dap_calculationVariables_st.stepperPosRange * 0.05f; + int32_t maxPos = currentPos + dap_calculationVariables_st.stepperPosRange * 0.05f; stepper->moveTo(minPos, true); diff --git a/ESP32/src/ForceCurve.cpp b/ESP32/src/ForceCurve.cpp index 602343fe..5a93d79c 100644 --- a/ESP32/src/ForceCurve.cpp +++ b/ESP32/src/ForceCurve.cpp @@ -16,7 +16,7 @@ float ForceCurve_Interpolated::EvalForceCubicSpline(const DAP_config_st* config_ float fractionalPos_lcl = constrain(fractionalPos, 0, 1); - float splineSegment_fl32 = fractionalPos_lcl * 5; + float splineSegment_fl32 = fractionalPos_lcl * 5.0f; uint8_t splineSegment_u8 = (uint8_t)floor(splineSegment_fl32); if (splineSegment_u8 < 0){splineSegment_u8 = 0;} @@ -34,7 +34,7 @@ float ForceCurve_Interpolated::EvalForceCubicSpline(const DAP_config_st* config_ //double dx = 1.0f; float t = (splineSegment_fl32 - (float)splineSegment_u8);// / dx; - float y = (1 - t) * yOrig[splineSegment_u8] + t * yOrig[splineSegment_u8 + 1] + t * (1 - t) * (a * (1 - t) + b * t); + float y = (1.0f - t) * yOrig[splineSegment_u8] + t * yOrig[splineSegment_u8 + 1] + t * (1.0f - t) * (a * (1.0f - t) + b * t); if (calc_st->Force_Range> 0) { @@ -61,7 +61,7 @@ float ForceCurve_Interpolated::EvalForceGradientCubicSpline(const DAP_config_st* float fractionalPos_lcl = constrain(fractionalPos, 0, 1); - float splineSegment_fl32 = fractionalPos_lcl * 5; + float splineSegment_fl32 = fractionalPos_lcl * 5.0f; uint8_t splineSegment_u8 = (uint8_t)floor(splineSegment_fl32); if (splineSegment_u8 < 0){splineSegment_u8 = 0;} @@ -79,24 +79,24 @@ float ForceCurve_Interpolated::EvalForceGradientCubicSpline(const DAP_config_st* - float Delta_x_orig = 100; // total horizontal range [0,100] + float Delta_x_orig = 100.0f; // total horizontal range [0,100] float dx = Delta_x_orig / NUMBER_OF_SPLINE_SEGMENTS; // spline segment horizontal range float t = (splineSegment_fl32 - (float)splineSegment_u8); // relative position in spline segment [0, 1] float dy = yOrig[splineSegment_u8 + 1] - yOrig[splineSegment_u8]; // spline segment vertical range - float y_prime = 0; - if (fabs(dx) > 0) + float y_prime = 0.0f; + if (fabsf(dx) > 0) { - y_prime = dy / dx + (1 - 2 * t) * (a * (1 - t) + b * t) / dx + t * (1 - t) * (b - a) / dx; + y_prime = dy / dx + (1.0f - 2.0f * t) * (a * (1.0f - t) + b * t) / dx + t * (1.0f - t) * (b - a) / dx; } // when the spline was identified, x and y were givin in the unit of percent --> 0-100 // --> conversion of the gradient to the proper axis scaling is performed if (normalized_b == false) { - float d_y_scale = calc_st->Force_Range / 100.0; - float d_x_scale=0; - if (fabs(calc_st->stepperPosRange) > 0.01) + float d_y_scale = calc_st->Force_Range / 100.0f; + float d_x_scale=0.0f; + if (fabs(calc_st->stepperPosRange) > 0.01f) { - d_x_scale = 100.0 / calc_st->stepperPosRange; + d_x_scale = 100.0f / calc_st->stepperPosRange; } y_prime *= d_x_scale * d_y_scale; diff --git a/ESP32/src/LoadCell.cpp b/ESP32/src/LoadCell.cpp index 39ffed5c..6fa44a53 100644 --- a/ESP32/src/LoadCell.cpp +++ b/ESP32/src/LoadCell.cpp @@ -4,15 +4,16 @@ #include #include "Main.h" -static const float ADC_CLOCK_MHZ = 7.68; // crystal frequency used on ADS1256 -static const float ADC_VREF = 2.5; // voltage reference +static const float ADC_CLOCK_MHZ = 7.68f; // crystal frequency used on ADS1256 +static const float ADC_VREF = 2.5f; // voltage reference static const int NUMBER_OF_SAMPLES_FOR_LOADCELL_OFFFSET_ESTIMATION = 1000; static const float DEFAULT_VARIANCE_ESTIMATE = 0.2f * 0.2f; static const float LOADCELL_VARIANCE_MIN = 0.001f; //static const float CONVERSION_FACTOR = LOADCELL_WEIGHT_RATING_KG / (LOADCELL_EXCITATION_V * (LOADCELL_SENSITIVITY_MV_V/1000)); -#define CONVERSION_FACTOR LOADCELL_WEIGHT_RATING_KG / (LOADCELL_EXCITATION_V * (LOADCELL_SENSITIVITY_MV_V/1000)) +float updatedConversionFactor_f64 = 1.0f; +#define CONVERSION_FACTOR LOADCELL_WEIGHT_RATING_KG / (LOADCELL_EXCITATION_V * (LOADCELL_SENSITIVITY_MV_V/1000.0f)) ADS1256& ADC() { @@ -36,7 +37,7 @@ ADS1256& ADC() { Serial.println("ADC Started"); adc.waitDRDY(); // wait for DRDY to go low before changing multiplexer register - if ( fabs(CONVERSION_FACTOR) > 0.01) + if ( fabs(CONVERSION_FACTOR) > 0.01f) { adc.setConversionFactor(CONVERSION_FACTOR); } @@ -55,10 +56,10 @@ void LoadCell_ADS1256::setLoadcellRating(uint8_t loadcellRating_u8) const { ADS1256& adc = ADC(); float originalConversionFactor_f64 = CONVERSION_FACTOR; - float updatedConversionFactor_f64 = 1; + float updatedConversionFactor_f64 = 1.0f; if (LOADCELL_WEIGHT_RATING_KG>0) { - updatedConversionFactor_f64 = 2 * ((float)loadcellRating_u8) * (CONVERSION_FACTOR/LOADCELL_WEIGHT_RATING_KG); + updatedConversionFactor_f64 = 2.0f * ((float)loadcellRating_u8) * (CONVERSION_FACTOR/LOADCELL_WEIGHT_RATING_KG); } Serial.print("OrigConversionFactor: "); Serial.print(originalConversionFactor_f64); @@ -73,7 +74,7 @@ void LoadCell_ADS1256::setLoadcellRating(uint8_t loadcellRating_u8) const { LoadCell_ADS1256::LoadCell_ADS1256(uint8_t channel0, uint8_t channel1) - : _zeroPoint(0.0), _varianceEstimate(DEFAULT_VARIANCE_ESTIMATE) + : _zeroPoint(0.0f), _varianceEstimate(DEFAULT_VARIANCE_ESTIMATE) { ADC().setChannel(channel0,channel1); // Set the MUX for differential between ch0 and ch1 //ADC().setChannel(channel1, channel0); // Set the MUX for differential between ch0 and ch1 @@ -84,7 +85,7 @@ float LoadCell_ADS1256::getReadingKg() const { adc.waitDRDY(); // wait for DRDY to go low before next register read // correct bias, assume AWGN --> 3 * sigma is 99.9 % - return adc.readCurrentChannel() - ( _zeroPoint + 3.0 * _standardDeviationEstimate ); + return adc.readCurrentChannel() - ( _zeroPoint + 3.0f * _standardDeviationEstimate ); } void LoadCell_ADS1256::setZeroPoint() { @@ -129,7 +130,7 @@ void LoadCell_ADS1256::estimateVariance() { if (varEstimate < LOADCELL_VARIANCE_MIN) { varEstimate = LOADCELL_VARIANCE_MIN; } - varEstimate *= 9; // The variance is 1*sigma --> to make it 3*sigma, we have to multiply by 3*3 + varEstimate *= 9.0f; // The variance is 1*sigma --> to make it 3*sigma, we have to multiply by 3*3 _varianceEstimate = varEstimate; diff --git a/ESP32/src/PedalGeometry.cpp b/ESP32/src/PedalGeometry.cpp index 6ad1be0a..e496a27a 100644 --- a/ESP32/src/PedalGeometry.cpp +++ b/ESP32/src/PedalGeometry.cpp @@ -46,10 +46,10 @@ float pedalInclineAngleDeg(float sledPositionMM, DAP_config_st * config_st) { #endif float nom = b*b + c*c - a*a; - float den = 2 * b * c; + float den = 2.0f * b * c; - float alpha = 0; - if (abs(den) > 0.01) { + float alpha = 0.0f; + if (abs(den) > 0.01f) { alpha = acos( nom / den ); } @@ -58,7 +58,7 @@ float pedalInclineAngleDeg(float sledPositionMM, DAP_config_st * config_st) { #endif // add incline due to AB incline --> result is incline realtive to horizontal - if (abs(c_hor)>0.01) { + if (abs(c_hor)>0.01f) { alpha += atan2f(c_ver, c_hor); // y, x //alpha += atan2Fast(c_ver, c_hor); // y, x } @@ -90,12 +90,12 @@ float convertToPedalForce(float F_l, float sledPositionMM, DAP_config_st * confi // c: is sled line (connection AC) // d: is upper pedal plate (connection AC) - float a = config_st->payLoadPedalConfig_.lengthPedal_a; - float b = config_st->payLoadPedalConfig_.lengthPedal_b; - float d = config_st->payLoadPedalConfig_.lengthPedal_d; + float a = (float)config_st->payLoadPedalConfig_.lengthPedal_a; + float b = (float)config_st->payLoadPedalConfig_.lengthPedal_b; + float d = (float)config_st->payLoadPedalConfig_.lengthPedal_d; - float c_ver = config_st->payLoadPedalConfig_.lengthPedal_c_vertical; - float c_hor = config_st->payLoadPedalConfig_.lengthPedal_c_horizontal + sledPositionMM; + float c_ver = (float)config_st->payLoadPedalConfig_.lengthPedal_c_vertical; + float c_hor = (float)config_st->payLoadPedalConfig_.lengthPedal_c_horizontal + sledPositionMM; float c = sqrtf(c_ver * c_ver + c_hor * c_hor); @@ -109,22 +109,22 @@ float convertToPedalForce(float F_l, float sledPositionMM, DAP_config_st * confi // lower plus upper pedal plate length - float b_plus_d = fabs(b + d); + float b_plus_d = fabsf(b + d); // compute gamma angle, see https://de.wikipedia.org/wiki/Kosinussatz float nom = a*a + b*b - c*c; float den = 2 * a * b; - float arg = 0; - if (abs(den) > 0.01) { + float arg = 0.0f; + if (abs(den) > 0.01f) { arg = nom / den; arg *= arg; } // apply conversion factor to loadcell reading - float one_minus_arg = 1 - arg; + float one_minus_arg = 1.0f - arg; float F_b = F_l; - if ( (b_plus_d > 0) && (one_minus_arg > 0) ) + if ( (b_plus_d > 0.0f) && (one_minus_arg > 0.0f) ) { F_b *= b / (b_plus_d) * sqrt( one_minus_arg ); } @@ -160,7 +160,7 @@ float convertToPedalForceGain(float sledPositionMM, DAP_config_st * config_st) { float c = sqrtf(c_ver * c_ver + c_hor * c_hor); - float alpha = acos( (b*b + c*c - a*a) / (2*b*c) ); + float alpha = acos( (b*b + c*c - a*a) / (2.0f*b*c) ); float alphaPlus = atan2f(c_ver, c_hor); // y, x //float alphaPlus = atan2Fast(c_ver, c_hor); // y, x @@ -201,12 +201,12 @@ float pedalInclineAngleAccel(float pedalInclineAngleDeg_global) { float delta_t_pow3 = delta_t_pow2 * delta_t; float delta_t_pow4 = delta_t_pow2 * delta_t_pow2; - K_pedal_geometry.F = {1.0, delta_t, 0.5 * delta_t * delta_t, - 0.0, 1.0, delta_t, - 0.0, 0.0, 1.0}; + K_pedal_geometry.F = {1.0f, delta_t, 0.5f * delta_t * delta_t, + 0.0, 1.0f, delta_t, + 0.0, 0.0, 1.0f}; // measurement matrix. Size is - K_pedal_geometry.H = {1.0, 0.0, 0.0}; + K_pedal_geometry.H = {1.0f, 0.0f, 0.0f}; // model covariance matrix. Size is /*K_pedal_geometry.Q = {1000, 0.0, 0.0, @@ -214,7 +214,7 @@ float pedalInclineAngleAccel(float pedalInclineAngleDeg_global) { 0.0, 0.0, 1000};*/ // measurement covariance matrix. Size is - K_pedal_geometry.R = { 0.0001 }; + K_pedal_geometry.R = { 0.0001f }; /* float K_Q_11 = KF_MODEL_NOISE_FORCE_ACCELERATION * 0.5f * delta_t_pow3; @@ -230,13 +230,13 @@ float pedalInclineAngleAccel(float pedalInclineAngleDeg_global) { // 1 / 2 * delta_t * delta_t // delta_t - float Q11 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1. / 6. * delta_t * delta_t * delta_t) * (1. / 6. * delta_t * delta_t * delta_t); - float Q12 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1. / 6. * delta_t * delta_t * delta_t) * (1. / 2. * delta_t * delta_t); - float Q13 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1. / 6. * delta_t * delta_t * delta_t) * (delta_t); + float Q11 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1.0f / 6.0f * delta_t * delta_t * delta_t) * (1.0f / 6.0f * delta_t * delta_t * delta_t); + float Q12 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1.0f / 6.0f * delta_t * delta_t * delta_t) * (1.0f / 2.0f * delta_t * delta_t); + float Q13 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1.0f / 6.0f * delta_t * delta_t * delta_t) * (delta_t); float Q21 = Q12; - float Q22 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1. / 2. * delta_t * delta_t) * (1. / 2. * delta_t * delta_t); - float Q23 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1. / 2. * delta_t * delta_t) * (delta_t); + float Q22 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1.0f / 2.0f * delta_t * delta_t) * (1.0f / 2.0f * delta_t * delta_t); + float Q23 = KF_MODEL_NOISE_FORCE_ACCELERATION * (1.0f / 2.0f * delta_t * delta_t) * (delta_t); float Q31 = Q13; float Q32 = Q23; diff --git a/ESP32/src/SignalFilter.cpp b/ESP32/src/SignalFilter.cpp index fdd6e010..2dba6abf 100644 --- a/ESP32/src/SignalFilter.cpp +++ b/ESP32/src/SignalFilter.cpp @@ -15,11 +15,11 @@ static const double KF_MODEL_NOISE_FORCE_ACCELERATION = ( 8.0f * 4.0f / 0.1f/ 0. float position = 0; // Estimated position float velocity = 0; // Estimated velocity -float dt = 0.1; // Time step (seconds) +float dt = 0.1f; // Time step (seconds) float P[2][2] = { // Initial error covariance - {1, 0}, - {0, 1} + {0, 0}, + {0, 0} }; float F[2][2] = { // State transition matrix {1, dt}, @@ -77,15 +77,11 @@ float KalmanFilter::filteredValue(float observation, float command, uint8_t mode modelNoiseScaling_fl32 /= 1000.0f; - - if (modelNoiseScaling_fl32 < 0.000001) - { - modelNoiseScaling_fl32 = 0.000001; - } + float modelNoiseLowerThreshold = 1e-9f; // 1/255 / 1000 / 1000 ca. 4*1e-9 + if (modelNoiseScaling_fl32 < modelNoiseLowerThreshold){ modelNoiseScaling_fl32 = modelNoiseLowerThreshold; } if (elapsedTime < 1) { elapsedTime=1; } - _timeLastObservation = currentTime; - if (elapsedTime > 5000) { elapsedTime=5000; } + _timeLastObservation = currentTime; @@ -148,26 +144,38 @@ float KalmanFilter::filteredValue(float observation, float command, uint8_t mode // S = P + R, since H = [1, 0] S = P_pred[0][0] + R; // Residual covariance - // K = P_pred * H' * inv(S) - // since S is 1x1 --> inv(S) = 1 / S - // P_pred * H' = [P_pred[0][0]; P_pred[1][0] ], since H' = [1;0] - K[0] = P_pred[0][0] / S; // Kalman Gain - K[1] = P_pred[1][0] / S; - - // Update state estimate - position = x_pred[0] + K[0] * y; - velocity = x_pred[1] + K[1] * y; - - // Update error covariance - // P = (I - K*H)*P_pred - // K*H = [K[0], 0; K[1], 0] - // p_arg = (I - K*H) - float p_arg[2][2] = { - { (1 - K[0]), 0.0f}, - {-K[1], 1.0f} - }; - - multiplyMatrices(p_arg, P_pred, P); + if (fabsf(S) > 0.000001f) + { + // K = P_pred * H' * inv(S) + // since S is 1x1 --> inv(S) = 1 / S + // P_pred * H' = [P_pred[0][0]; P_pred[1][0] ], since H' = [1;0] + K[0] = P_pred[0][0] / S; // Kalman Gain + K[1] = P_pred[1][0] / S; + + // Update state estimate + position = x_pred[0] + K[0] * y; + velocity = x_pred[1] + K[1] * y; + + // Update error covariance + // P = (I - K*H)*P_pred + // K*H = [K[0], 0; K[1], 0] + // p_arg = (I - K*H) + float p_arg[2][2] = { + { (1.0f - K[0]), 0.0f}, + {-K[1], 1.0f} + }; + + multiplyMatrices(p_arg, P_pred, P); + } + else + { + P[0][0] = 0.0f; + P[0][1] = 0.0f; + P[1][0] = 0.0f; + P[1][1] = 0.0f; + } + + return position; diff --git a/ESP32/src/StepperWithLimits.cpp b/ESP32/src/StepperWithLimits.cpp index 357838e5..81835ab8 100644 --- a/ESP32/src/StepperWithLimits.cpp +++ b/ESP32/src/StepperWithLimits.cpp @@ -182,7 +182,7 @@ void StepperWithLimits::findMinMaxSensorless(DAP_config_st dap_config_st) // voltage return is given in 0.1V units --> 10V range --> threshold 100 // at beginning the values typically are initialized with -1 float servosBusVoltageInVolt_fl32 = ( (float)getServosVoltage() ) / 10.0f; - servoRadingsTrustworthy_b = ( servosBusVoltageInVolt_fl32 >= 16) && ( servosBusVoltageInVolt_fl32 < 39); + servoRadingsTrustworthy_b = ( servosBusVoltageInVolt_fl32 >= 16.0f) && ( servosBusVoltageInVolt_fl32 < 39.0f); if (true == servoRadingsTrustworthy_b) { diff --git a/ESP32/src/isv57communication.cpp b/ESP32/src/isv57communication.cpp index 0ee61a67..aa86176c 100644 --- a/ESP32/src/isv57communication.cpp +++ b/ESP32/src/isv57communication.cpp @@ -151,7 +151,8 @@ void isv57communication::sendTunedServoParameters(bool commandRotationDirection, retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_1_00+33, 0); // speed given filter retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_1_00+35, 0); // position command filter retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_1_00+36, 0); // encoder feedback - retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_1_00+37, 1052); // special function register + //retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_1_00+37, 1052); // special function register + retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_1_00+37, 4); // special function register // see https://www.oyostepper.com/images/upload/File/ISV57T-180.pdf // 0x01 = 1: velocity feedforward disabled // 0x02 = 2: torque feedforward disabled @@ -169,7 +170,7 @@ void isv57communication::sendTunedServoParameters(bool commandRotationDirection, retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_2_00+5, 20); retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_2_00+6, 99); retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_2_00+22, 0); - retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_2_00+23, 80);// FIR based command smoothing time. Since the stpper task runs every 4ms, this time is selected to be larger than that. Unit is 0.1ms + retValue_b |= modbus.checkAndReplaceParameter(slaveId, pr_2_00+23, 0);// FIR based command smoothing time. Since the stpper task runs every 4ms, this time is selected to be larger than that. Unit is 0.1ms // Pr3 register diff --git a/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/1a2a3474-fe57-41b1-b49c-1746897f070b.vsidx b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/1a2a3474-fe57-41b1-b49c-1746897f070b.vsidx new file mode 100644 index 00000000..c2c8f476 Binary files /dev/null and b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/1a2a3474-fe57-41b1-b49c-1746897f070b.vsidx differ diff --git a/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/5f9bae3c-e851-4a74-9951-4018ad9144c7.vsidx b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/5f9bae3c-e851-4a74-9951-4018ad9144c7.vsidx new file mode 100644 index 00000000..819c833a Binary files /dev/null and b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/5f9bae3c-e851-4a74-9951-4018ad9144c7.vsidx differ diff --git a/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/96d4220d-700a-4c38-bd7b-9088cceddf94.vsidx b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/96d4220d-700a-4c38-bd7b-9088cceddf94.vsidx new file mode 100644 index 00000000..c2c8f476 Binary files /dev/null and b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/96d4220d-700a-4c38-bd7b-9088cceddf94.vsidx differ diff --git a/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/a24b04e5-a0e9-44b0-9492-a495b0bc840c.vsidx b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/a24b04e5-a0e9-44b0-9492-a495b0bc840c.vsidx new file mode 100644 index 00000000..c2c8f476 Binary files /dev/null and b/SimHubPlugin/.vs/User.PluginSdkDemo/FileContentIndex/a24b04e5-a0e9-44b0-9492-a495b0bc840c.vsidx differ diff --git a/SimHubPlugin/SettingsControlDemo.xaml b/SimHubPlugin/SettingsControlDemo.xaml index 993f28c4..8ef44ea5 100644 --- a/SimHubPlugin/SettingsControlDemo.xaml +++ b/SimHubPlugin/SettingsControlDemo.xaml @@ -1113,19 +1113,19 @@ - + - + - +