Skip to content

Commit 52619d5

Browse files
author
jenkie
committed
New config option SUPPORT_MOTOR_SERVO
Uncomment SUPPORT_MOTOR_SERVO if you have an RC motor controller connected to the motor output. Do not forget to remove capacitor from the low pass filter of the motor output.
1 parent 2f18bbf commit 52619d5

File tree

2 files changed

+17
-8
lines changed

2 files changed

+17
-8
lines changed

Arduino_Pedelec_Controller/Arduino_Pedelec_Controller.ino

Lines changed: 14 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,11 @@ Features:
3838
#include "menu.h" //on the go menu
3939
#include "serial_command.h" //serial (bluetooth) communication stuff
4040

41+
#ifdef SUPPORT_MOTOR_SERVO //RC motor controller connected to motor output
42+
#include <Servo.h>
43+
Servo motorservo;
44+
#endif
45+
4146
#ifdef SUPPORT_BMP085
4247
#include <Wire.h>
4348
#include "BMP085.h" //library for altitude and temperature measurement using http://www.watterott.com/de/Breakout-Board-mit-dem-BMP085-absoluten-Drucksensor
@@ -452,6 +457,10 @@ void setup()
452457
torque_zero=analogRead_noISR(option_pin);
453458
#endif
454459

460+
#ifdef SUPPORT_MOTOR_SERVO
461+
motorservo.attach(throttle_out);
462+
#endif
463+
455464
#ifdef DEBUG_MEMORY_USAGE
456465
Serial.print(MY_F("memFree after setup:"));
457466
Serial.print(memFree());
@@ -590,12 +599,6 @@ void loop()
590599
}
591600
firstrun=false; //first loop run done (ok, up to this line :))
592601

593-
//Check power-off condition ---------------------------------------------------------------------------------------------
594-
if ((voltage<20.0)&&(voltage_2s>6.0)) //save to EEPROM when battery disconnect detected. Do this only if not running on usb power
595-
{
596-
save_shutdown();
597-
}
598-
599602
//Are we pedaling?---------------------------------------------------------------------------------------------------------
600603
#ifdef SUPPORT_PAS
601604
if (((millis()-last_pas_event)>500)||(pas_failtime>pas_tolerance))
@@ -699,7 +702,11 @@ void loop()
699702
if (throttle_stat<5||spd>curr_spd_max2)
700703
#endif
701704
{throttle_write=motor_offset;}
705+
#ifdef SUPPORT_MOTOR_SERVO
706+
motorservo.writeMicroseconds(throttle_write);
707+
#else
702708
analogWrite(throttle_out,throttle_write);
709+
#endif
703710

704711
#ifdef SUPPORT_DISPLAY_BACKLIGHT
705712
handle_backlight();
@@ -1241,6 +1248,7 @@ void read_eeprom()
12411248

12421249
void save_shutdown()
12431250
{
1251+
Serial.println("stop");
12441252
digitalWrite(throttle_out,0); //turn motor off
12451253
//power saving stuff. This is critical if battery is disconnected.
12461254
EIMSK=0; //disable interrupts

Arduino_Pedelec_Controller/config.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,7 @@ const int fixed_throttle_in_watts = 250; //number of watts to set as thr
133133
#define CONTROL_MODE_TORQUE 2 //power = x*power of the biker, see also description of power_poti_max!
134134
#define CONTROL_MODE CONTROL_MODE_NORMAL //Set your control mode here
135135

136+
//#define SUPPORT_MOTOR_SERVO //RC Motor controller with PWM input is used. Do not forget to remove capacitor from the low pass filter of the output to the motor controller.
136137
//#define SUPPORT_MOTOR_GUESS //enable guess of motor drive depending on current speed. Usefull for motor controllers with speed-throttle to optimize response behaviour
137138
#define SUPPORT_BATTERY_CHARGE_DETECTION //support detection if the battery was charged -> reset wh / trip km / mah counters if detected.
138139
const byte battery_charged_min_voltage = 20; //minimum battery voltage to consider it charged. Useful to prevent "false positives".
@@ -148,8 +149,8 @@ const int throttle_offset=196; //Offset voltage of throttle control wh
148149
const int throttle_max=832; //Offset voltage of throttle control when in "MAX" position (0..1023 = 0..5V)
149150
const int poti_offset=0; //Offset voltage of poti when in "0" position (0..1023 = 0..5V)
150151
const int poti_max=1023; //Offset voltage of poti when in "MAX" position (0..1023 = 0..5V)
151-
const int motor_offset=50; //Offset for throttle output where Motor starts to spin (0..255 = 0..5V)
152-
const int motor_max=200; //Maximum input value for motor driver (0..255 = 0..5V)
152+
const int motor_offset=50; //Offset for throttle output where Motor starts to spin (0..255 = 0..5V). Default: 50. In Servo mode this value is about 1000
153+
const int motor_max=200; //Maximum input value for motor driver (0..255 = 0..5V). Default: 200. In Servo mode this value is about 2000
153154
const int spd_idle=55; //idle speed of motor in km/h - may be much higher than real idle speed (depending on controller)
154155
const boolean startingaidenable = true; //enable starting aid?
155156
const int startingaid_speed = 6; //starting aid up to this speed. 6km/h is the limit for legal operation of a Pedelec by EU-wide laws

0 commit comments

Comments
 (0)