Skip to content

Commit 1a71bc2

Browse files
author
jenkie
committed
Bugfix SUPPORT_TORQUE_THROTTLE
1 parent 527cf53 commit 1a71bc2

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

Arduino_Pedelec_Controller/Arduino_Pedelec_Controller.ino

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -810,7 +810,7 @@ if (loadcell.is_ready()) //new conversion result from load cell available
810810

811811
if (power_set>curr_power_max*factor_speed)
812812
{power_set=curr_power_max*factor_speed;} //Maximum allowed power including Speed-Cutoff
813-
if ((((poti_stat<=throttle_stat)||(pedaling==false))&&(throttle_stat==0))||(brake_stat==0)) //integral part of PID regulator is slowly shrinked to 0 when you stop pedaling or brake
813+
if ((((poti_stat<=throttle_stat)||(pedaling==false))&&(power_throttle<10))||(brake_stat==0)) //integral part of PID regulator is slowly shrinked to 0 when you stop pedaling or brake
814814
{
815815
#ifdef RESET_PID_ON_BRAKE
816816
myPID.ResetIntegral();
@@ -839,9 +839,9 @@ if (loadcell.is_ready()) //new conversion result from load cell available
839839
throttle_write=map(pid_out*brake_stat*factor_volt,0,1023,motor_offset,motor_max);
840840
#endif
841841
#ifdef SUPPORT_PAS
842-
if ((pedaling==false)&&(throttle_stat<5)||power_set<=0||spd>curr_spd_max2)
842+
if ((pedaling==false)&&(power_throttle<10)||power_set<=0||spd>curr_spd_max2)
843843
#else
844-
if (throttle_stat<5||spd>curr_spd_max2)
844+
if (power_throttle<10||spd>curr_spd_max2)
845845
#endif
846846
{throttle_write=motor_offset;}
847847
//Broken speed sensor detection START

0 commit comments

Comments
 (0)