Skip to content

Commit ce63ff1

Browse files
jenkiethomasjfox
authored andcommitted
Added SUPPORT_TORQUE_THROTTLE config option
Enable SUPPORT_TORQUE_THROTTLE to use pedal force as starting aid (similar to thumb throttle). The motor will be powered if the torque is more than torque_throttle_min and will be at full power at torque_throttle_full.
1 parent e610ca2 commit ce63ff1

File tree

2 files changed

+15
-3
lines changed

2 files changed

+15
-3
lines changed

Arduino_Pedelec_Controller/Arduino_Pedelec_Controller.ino

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -260,7 +260,8 @@ PID myPID(&power, &pid_out,&pid_set,pid_p,pid_i,0, DIRECT);
260260
unsigned int idle_shutdown_count = 0;
261261
unsigned long idle_shutdown_last_wheel_time = millis();
262262
byte pulse_human=0; //cyclist's heart rate
263-
double torque=0.0; //cyclist's torque
263+
double torque=0.0; //cyclist's torque in Nm (averaged over one pedal revolution)
264+
double torque_instant=0.0; //cyclist's torque in Nm (live)
264265
double power_human=0.0; //cyclist's power
265266
double wh_human=0;
266267
#ifdef SUPPORT_XCELL_RT
@@ -643,6 +644,7 @@ if (loadcell.is_ready()) //new conversion result from load cell available
643644
power=current*voltage;
644645

645646
#ifdef SUPPORT_XCELL_RT
647+
torque_instant=(analogRead(option_pin)-torque_zero); //multiplication constant for THUN X-CELL RT is approx. 1Nm/count
646648
if (readtorque==true)
647649
{
648650
torque=0.0;
@@ -756,6 +758,14 @@ if (loadcell.is_ready()) //new conversion result from load cell available
756758
#if CONTROL_MODE == CONTROL_MODE_TORQUE //human power control mode
757759
#ifdef SUPPORT_XCELL_RT
758760
power_poti = poti_stat/102300.0* curr_power_poti_max*power_human*(1+spd/20.0); //power_poti_max is in this control mode interpreted as percentage. Example: power_poti_max=200 means; motor power = 200% of human power
761+
#ifdef SUPPORT_TORQUE_THROTTLE //we want to trigger throttle just by pedal torque
762+
if (abs(torque_instant)>torque_throttle_min) //we are above the threshold to trigger throttle
763+
{
764+
double power_torque_throttle = abs(torque_instant/torque_throttle_full*poti_stat/1023*curr_power_max); //translate torque_throttle_full to maximum power
765+
power_throttle = max(power_throttle,power_torque_throttle); //decide if thumb throttle or torque throttle are higher
766+
power_throttle = constrain(power_throttle,0,curr_power_max); //constrain throttle value to maximum power
767+
}
768+
#endif
759769
#endif
760770
#endif
761771

@@ -1220,7 +1230,7 @@ void serial_debug(HardwareSerial* localSerial)
12201230
localSerial->print(MY_F(" Pedaling"));
12211231
localSerial->print(pedaling);
12221232
localSerial->print(MY_F(" Torque"));
1223-
localSerial->print(torque,1);
1233+
localSerial->print(torque_instant,1); //print current torque value in Nm
12241234
#else
12251235
localSerial->print(MY_F(" PAS_On"));
12261236
localSerial->print(pas_on_time);

Arduino_Pedelec_Controller/config.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -141,6 +141,7 @@ const int fixed_throttle_in_watts = 250; //number of watts to set as thr
141141
// #define SUPPORT_BBS //uncomment if BBS02 PAS sensor is connected (2 wires analog to Thun)
142142
#define BBS_GEARCHANGEPAUSE 2000 //powerless time in milliseconds to allow gear change
143143
// #define SUPPORT_XCELL_RT //uncomment if X-CELL RT connected. FC1.4: pas_factor_min=0.2, pas_factor_max=0.5. FC1.5: pas_factor_min=0.5, pas_factor_max=1.5. pas_magnets=8
144+
// #define SUPPORT_TORQUE_THROTTLE
144145
// #define SUPPORT_HRMI //uncomment if polar heart-rate monitor interface connected to i2c port
145146
#define SUPPORT_BRAKE //uncomment if brake switch connected
146147
// #define INVERT_BRAKE //uncomment if brake signal is low when not braking
@@ -215,7 +216,8 @@ const double cfg_pid_i_throttle=2.5; //pid i-value for throttle mode
215216
const byte pulse_min=150; //lowest value of desired pulse range in bpm
216217
const byte pulse_range=20; //width of desired pulse range in bpm
217218
const int pas_timeout=500; //time in ms after which pedaling is set to false
218-
219+
const int torque_throttle_min=5; //minimum torque in Nm to trigger starting aid
220+
const int torque_throttle_full=20; //torque to give full throttle
219221
//Config Options for profile 2-----------------------------------------------------------------------------------------------------
220222
const int startingaid_speed_2 = 6;
221223
const int spd_max1_2=22; //speed cutoff start in Km/h

0 commit comments

Comments
 (0)