Self Bal Scooter

41
Self Balancing Scooter

Transcript of Self Bal Scooter

Page 1: Self Bal Scooter

Self Balancing Scooter

Page 2: Self Bal Scooter

Overview

The BTWS is an electric driven scooter with an electronic for controlling and driving the system. The signal processing is done by an Atmel Atmega32 microcontroller. It shows how powerful, flexible and secure a so fast signal processing can be done with an AVR device.

1. Operating

2. Mechanics

3. System Control

4. Electronic

5. Schematics

6. Software

7. Part list

8. Flowcharts

9. Listing

10.Sources / References

1. Operating

After switching on the unit, the electronics is in stand by mode. Through shift the handle into the verticality position, driving mode will be activated. The engines are powered and the equipment is balanced. Now you can ascend and drive off.

Pavner 2

Page 3: Self Bal Scooter

2. Mechanics

The basic construction exists of wood. You stand on the base plate firmly with a straight stick is connected. At the upper end of the stick a potentiometer - rocker is appropriate for the left / right steering. In the middle between the feet the lead acid batteries are stowed. Under the base plate a stiff axis is fastened on that the ball bearing wheels are fastened. The engines are fastened from below to the base plate and transferred her strength about a chain drive on the wheels. Sprockets with 72 teeth are screwed at the side onto the wheels.In midst the base plate the electronics is fastened.

Figure 1: mechanical construction

Photo 1: Motor Chain Photo 2: Motor , Wheel

Pavner 3

Page 4: Self Bal Scooter

Photo 3: Wheel

Photo 4: Bottom View Photo 5: Complete

Pavner 4

Page 5: Self Bal Scooter

3. System Control

Control of the BTWS functions after the principle of the " dynamic stabilization ". This means that itself the vehicle balances independently. The functional way is as the human balance sense. Instead of inner ear, eyes, muscles and brain works a Gyro (Sensor for the angle rate) and an acceleration Sensor, a microprocessor ATMEGA32 and high power electric motors together to stabilize the balance. Forward and regression is reached by leaning forward and leaning back. A rocker that is placed at the upper end of the stick generates the Signal for the left right control.

Figure 2: BTWS System Block Diagram

Pavner 5

Page 6: Self Bal Scooter

4. Electronic

The electronics is placed on approx. 100 cm ² single layer printed circuit board. All signal processing and control is done by an ATMEGA32. The ATMEGA use his internal oscillator and his Brown-Out-Detection for the sure operation. For the power supply are two voltage regulators on the PCB. A voltage of 12 V is generated to supply the half bridges drivers. The second voltage regulator generates a voltage of 5 V with which the MCU and the sensors are supplied. The Gyro is placed in a rubber case and it is mounted on the PCB. The Gyro axis of rotation is parallel with the axis of the BTWS. The analog output of the Gyro has a normal voltage of approx. 2.5 V. With rotation the voltage changes according to the angle rate (25mV / deg / sec). The Signal is measured from an analog input of the MCU.

Photo 6: PCBPhoto 7: PCB top side

Photo 8: PCB bottom side

Pavner 6

Page 7: Self Bal Scooter

The acceleration Sensor ADXL311 is an SMD-component witch is soldered at the underside of the PCB. His normal voltage is likewise approx. 2.5 V. Only one axes of the two axis of the Sensor is used for the balance stabilization (acceleration in direction of the traffic). The source signal according to the acceleration matters not really.

For the stabilization, the changing source signal is necessarily which is proportionally to the tilt angle change to the earth (approx. 5mV / degree). The signal is led on an analog input of the MCU and is measured. The benefit signal is won there by digital filtering.

Analog Devices ADXL311 Acceleration Sensor

The ADXL311 is a low cost, low power, complete dual-axis accelerometer with signal conditioned voltage outputs, all on a single monolithic IC.

The ADXL311 will measure acceleration with a full-scale range of ±2 g. The ADXL311 can measure both dynamic acceleration (e.g., vibration) and static acceleration (e.g., gravity). The outputs are analog voltages proportional to acceleration.The typical noise floor is 300 μg/√Hz allowing signals below 2 mg (0.1° of inclination) to be resolved in tilt sensing applications using narrow bandwidths (10 Hz).The user selects the bandwidth of the accelerometer using capacitors CX and CY at the XFILT and YFILT pins. Bandwidths of 1 Hz to 2 kHz may be selected to suit the application.

Product Information 2 Axis of Acceleration Sensing on a Single IC Chip 5 milli-g Resolution Low power > 0.5mA (ADXL311) BW Adjustment with a Single Capacitor +2.7V to +5.25V Single Supply Operation

Pavner 7

Page 8: Self Bal Scooter

Panasonic EWTS4 Compact Angular Rate Sensor

This angular rate sensor utilizes Coriolis force generated by a vibrating tuning fork. This Sensor consists of sensing and driving elements, tuning fork driving circuit and the signal processing circuit. The tuning fork is composed of two metal pieces, a connecting block and four piezo-electric elements. A compact and reliable angular rate sensor has been realized.

Operating Temperature Range -30 to 80

Supply Voltage Range 5±0.25 V

Zero Point Voltage 2.5±0.4 V

Sensitivity 25 mV/deg/s

Output Voltage Range 0.3 to 4.7 V

Output Noise < 10 m Vp-p

Figure 3: Gyro EWTS4

For steering the system, the potentiometer rocker is measured by an analog input. In normal position a voltage of 2.5 V will be here. With activity on the left, a voltage of approx. 0.5 V, and with activity on the right a voltage of approx. 4.5 V will be generated.

Photo 9: Rocker Photo 10: Gyro EWTS4

The MCU generates two PWM, and two rotation direction signals for both electric motors. To reduce the peak current there is a phase shift from 180° between the PWM signals. The basic frequency of the PWM Signal was chosen with 15.5 kHz to have a low noise level for the environment. These signals are tied together by logic circuit and are given to the half bridge MOSFET driver. Two of these build a full bridge for any motor. The MOSFETS of the type IRF3205 (110 A / 8 mOhm) are strange enough to power the drive motors.A piezo sound generator is on the PCB to give warnings and weak batteries can be signaled.

Pavner 8

Page 9: Self Bal Scooter

5. Schematics

Pavner 9

Page 10: Self Bal Scooter

Pavner 10

Page 11: Self Bal Scooter

6. Software

Project is developed with the CodeVision AVR C-Compiler. The hole regulation is done in a interrupt routine. This function is called every10 m Sec. The program works only with char, int and long integer variables and no floats to have best cycle time. The cycle time is approx. 1,3 mSec.

The signal capture is very critical. To reach a good stabilization it is inevitably any time the correct tilt angle to earth is available. The signal of the acceleration Sensor must be integrated in addition for a long period to smooth the signal variations by accelerations. To this signal, the signal of the Gyro is added up. A quick and exact tilt angle measurement could be realized thus by adaptation of the factors by attempts.

Figure 4: Filter

Pavner 11

Page 12: Self Bal Scooter

Balancement:The balancement is relatively easy, the hold stick bends after In front, the engines both are powered in the direction of forward. The feet are pushed by the feed again under the main focus of the body and a balance is reached. Moreover the necessary strength and speed can be determined only in the attempt and strongly hang together with the mechanically quality of the vehicle. If the teamwork of the forces is not properly it is able to oscillating and instabilities.

Speed control:With every inclination of the hold stick the balance is produced and at the same time the basic speed a small part is changed in the direction of the inclination.

Speed limit:If the basic speed had reached too high, it would not be sometime any more possibly to balancement, because the voltage of electric motors already reached the highest value. To counteract against that, the basic speed is limited to 2/3 of the source voltage. With reach to the speed 2/3 a stronger feed impulse is generated in direction of the traffic, which generates then a light inclination to the back and reduces thus the driving speed. A good balancement is always given.

Steering:To steering the system the engines are driven with different voltages.The size of the differences is determined by the rocker signal and is depending on the driving speed. With high speeds only a small different steering control is allowed, because the curve radius then can be only very big.

Pavner 12

Page 13: Self Bal Scooter

7. Part list

Quantity Value Price Price / EUR3 Pol. cap 470uF / 35V 0,20 0,607 Pol. cap 4,7u / 35V 0,05 0,3521 Ceramic C 100n 0,01 0,214 Ceramic C 470n 0,03 0,124 Diode SA158 0,03 0,121 Gyro Panasonic EWTS4 25,00 25,004 IC IR2184 1,50 6,001 IC MC7812 0,30 0,301 IC MC7805 0,30 0,301 MCU MEGA32-A 2,00 2,002 IC CD4001 0,20 0,402 LED LED3MM 0,03 0,0610 Resistor 4,7K 0,01 0,101 Resistor 200k 0,01 0,011 Resistor 10k 0,01 0,011 Resistor 68K 0,01 0,012 Resistor 330R 0,01 0,021 Resistor 15R 0,01 0,018 Resistor 4,7R 0,01 0,081 Sensor ADXL311 4,20 4,201 BUZZER F/TMB05 1,20 1,208 MOSFET IRF3205 0,90 7,201 Connector X-LPHS-10 0,15 0,151 Connector AK500/2 0,20 0,201 Connector AK500/3 0,30 0,301 PCB 1,80 1,80

0,002 Motors MY-1016 250W / 14A /24V Unite

Motors Taiwan15,50 31,00

1 Rocker JC030 Peny & Giles 16,50 16,504 Battery 12V / 7,2Ah Panasonic Lead Acid 11,50 46,001 Fuse 40 Amps 1,00 1,00

0,001 Switch 1,50 1,502 Wheel 8,50 17,001 Axle 2,50 2,502 Sprockets 6,20 12,402 Chain 3,80 7,601 Wood 8,00 8,001 Small Parts 5,00 5,00

Total: 199,25

Pavner 13

Page 14: Self Bal Scooter

8. Flowcharts

Pavner 14

Page 15: Self Bal Scooter

Pavner 15

Page 16: Self Bal Scooter

Pavner 16

Page 17: Self Bal Scooter

Pavner 17

Page 18: Self Bal Scooter

Pavner 18

Page 19: Self Bal Scooter

Pavner 19

Page 20: Self Bal Scooter

Pavner 20

Page 21: Self Bal Scooter

Pavner 21

Page 22: Self Bal Scooter

9. Listing

/*****************************************************CodeVision AVR V1.24.1e Standard© Copyright 1998-2004 Pavel Haiduc, HP InfoTech s.r.l.http://www.hpinfotech.roe-mail:[email protected]

Project : BTWSVersion : 1.00Date : 01.08.2006Author : xxxxxxComments:

Chip type : ATmega32Program type : ApplicationClock frequency : 8,000000 MHzMemory model : SmallExternal SRAM size : 0Data Stack size : 256

*****************************************************/

// includes

#include <mega32.h>#include <delay.h>#include <math.h>#include <stdio.h>

// definitions

#define FIRST_ADC_INPUT 0#define LAST_ADC_INPUT 6#define ADC_VREF_TYPE 0x40 #define Drivesumlimit 65000#define Overspeedlimit 40000 // 2/3 of max drive speed

#define total_looptime 2000 // Looptime for filters#define ADXL_offset -5; // Stick Angle offset#define ADXL_ZERO 521#define GYRO_ZERO 510#define ROCKER_ZERO 512#define ROCKER_DEADBAND 30#define ON 1#define OFF 0#define Run 1#define Standby 0

#define Batt25 664 // AD Value at 25 Volts#define Batt_low 235 // 23,5 Volt

#define max_PWM 250 // The MOSFET Driver must have a little pulse for Operation

#define PWM_A OCR1AL#define PWM_B OCR1BL

#define AD_GYRO adc_data[2]#define AD_ADXL adc_data[0]#define AD_ROCKER adc_data[5]#define AD_Batt adc_data[6]

#define CW_CCW_A PORTD.6

Pavner 22

Page 23: Self Bal Scooter

#define CW_CCW_B PORTD.7#define LED1 PORTC.2#define LED2 PORTC.3#define BUZZER PORTC.1

// global variables

unsigned int Voltage=0;unsigned char MODE=0; signed long total_ADXL_GYRO=0; signed long Average_Gyro=0; signed int DriveA=0; signed int DriveB=0; signed long buf1=0; signed int buf=0; signed int buf2=0; signed long Average_Batt=total_looptime*Batt25; signed int Tilt_ANGLE=0; signed int Drive_A=0; signed int Drive_B=0; signed int Drivespeed=0; signed int Steeringsignal=0; signed long Anglecorrection=0; signed int Angle_Rate=0; signed long Balance_moment=0; signed long Drive_sum=0; signed long Overspeed=0; signed long Overspeed_integral=0; bit Overspeed_flag=0; bit Batt_low_flag=0;

unsigned char intervalz=0;unsigned char interval=0;

unsigned int adc_data[LAST_ADC_INPUT-FIRST_ADC_INPUT+1];

interrupt [ADC_INT]/*-----------------------------------------------------------------------------Function : adc_isr()ADC interrupt service routine with auto input scanningDate : 01.08.2006

-----------------------------------------------------------------------------*/void adc_isr(void){ static unsigned char input_index=0; // Read the AD conversion result adc_data[input_index] = ADCW;

// Select next ADC input if (++input_index > (LAST_ADC_INPUT - FIRST_ADC_INPUT))input_index = 0; ADMUX=(FIRST_ADC_INPUT | ADC_VREF_TYPE) + input_index; // Start the AD conversion ADCSRA |= 0x40;}

Pavner 23

Page 24: Self Bal Scooter

/*-----------------------------------------------------------------------------Function : Get_Batt_Volt()calculate the Battery VoltageDate : 01.08.2006

-----------------------------------------------------------------------------*/void Get_Batt_Volt(){ buf = Average_Batt / total_looptime; Average_Batt -= buf; Average_Batt+=AD_Batt; Voltage=(Average_Batt*10)/80/Batt25;}

/*-----------------------------------------------------------------------------Function : Get_Tiltangle()calculate the Tilt Angle with a hand made Filter loop,calculate the Angle Rate

Date : 01.08.2006

-----------------------------------------------------------------------------*/void Get_Tiltangle(){ buf = total_ADXL_GYRO / total_looptime; total_ADXL_GYRO -= buf;

// ADXL part buf = AD_ADXL-ADXL_ZERO + ADXL_offset; total_ADXL_GYRO += buf;

// Gyro part buf1 = Average_Gyro / total_looptime; Average_Gyro -= buf1;

Average_Gyro += AD_GYRO; buf1 = Average_Gyro / (total_looptime / 10);

// calculate the Angle Rate buf1 = buf1 - AD_GYRO * 10; buf1 *= 35; buf1 /= 100; Angle_Rate = buf1;

// calculate the Tilt Angle total_ADXL_GYRO += Angle_Rate; Tilt_ANGLE = total_ADXL_GYRO / (total_looptime / 10);}

Pavner 24

Page 25: Self Bal Scooter

/*-----------------------------------------------------------------------------Function : Set_PWM()limiting and Setting the PWM Signals, and Set the Direction PinsDate : 01.08.2006

-----------------------------------------------------------------------------*/void Set_PWM(){ if(Drive_A > max_PWM)Drive_A = max_PWM; // limiting PWM Signal A if(Drive_A < -max_PWM)Drive_A = -max_PWM; // limiting PWM Signal A

if(Drive_A < 0) // Check direction { DriveA = Drive_A * -1; // only positive CW_CCW_A = 1; // CW } else { DriveA = Drive_A; CW_CCW_A = 0; // CCW } PWM_A = 255 - DriveA; // inverse Signal to have a Phase shift from 180° to Signal PWM B

if(Drive_B > max_PWM)Drive_B = max_PWM; // limiting PWM Signal B if(Drive_B < -max_PWM)Drive_B = -max_PWM; // limiting PWM Signal B if(Drive_B < 0) // Check direction { DriveB = Drive_B * -1; // only positive CW_CCW_B = 1; // CW } else { DriveB = Drive_B; CW_CCW_B = 0; // CCW } PWM_B = DriveB; // Set PWM}

Pavner 25

Page 26: Self Bal Scooter

/*-----------------------------------------------------------------------------Function : Algorythmus()Limit top speed by tilting back, Calculate the Driving speedDate : 01.08.2006

-----------------------------------------------------------------------------*/void Algorythmus()

{ Balance_moment = Angle_Rate*4 + 5 * (Tilt_ANGLE + Anglecorrection); // calculate balance moment

Overspeed = lmax(0, Drive_sum - Overspeedlimit); // get over speed

if (Overspeed > 0) { if(MODE == Run)Overspeed_flag = 1;

Overspeed_integral = lmin(1000, Overspeed_integral + min(500, Overspeed + 125)); // calculate over speed integral } else { Overspeed_flag = 0; Overspeed_integral = lmax(0, Overspeed_integral - 100); // calculate over speed integral }

Anglecorrection = Overspeed / 200 + Overspeed_integral / 125; // calculate Angle correction

Drive_sum += Balance_moment; // calculate Drive_sum

// limitting if(Drive_sum > Drivesumlimit)Drive_sum = Drivesumlimit; if(Drive_sum <- Drivesumlimit)Drive_sum =-Drivesumlimit;

Drivespeed = Drive_sum / 250 + Balance_moment / 40; // calculate Drive speed

}

Pavner 26

Page 27: Self Bal Scooter

/*-----------------------------------------------------------------------------Function : Signal_Processing()Generate Start condition, calculate the left / right steering signalDate : 01.08.2006

-----------------------------------------------------------------------------*/void Signal_Processing(){ if(MODE == Standby) // Standby Mode { Drive_A = 0; Drive_B = 0; Drivespeed=0; Anglecorrection=0; Overspeed=0; Overspeed_integral = 0; Drive_sum = 0; total_ADXL_GYRO = 0; Tilt_ANGLE = 0; Average_Gyro = total_looptime * GYRO_ZERO; buf2 = AD_ADXL - ADXL_ZERO + ADXL_offset; if(buf2 == 0) // The Stick is in Start position initial the System to run { MODE = Run; }

} else // Run operation { Steeringsignal = ROCKER_ZERO - AD_ROCKER; // get the Steering Signal

// check Dead band if(Steeringsignal <- ROCKER_DEADBAND) { Steeringsignal += ROCKER_DEADBAND; } else { if(Steeringsignal > ROCKER_DEADBAND) { Steeringsignal -= ROCKER_DEADBAND; } else { Steeringsignal = 0; } }

// calculate the signal to reduce the differential steering at higher Drive speed Steeringsignal *= 7; buf2 = Drivespeed; if(buf2 < 0)buf2 *= -1; buf2 /= 2; Steeringsignal /= (buf2 + 30);

Drive_A = Drivespeed + Steeringsignal; // differential Steering Drive_B = Drivespeed - Steeringsignal; // differential Steering }}

Pavner 27

Page 28: Self Bal Scooter

interrupt [TIM0_OVF]/*-----------------------------------------------------------------------------Function : timer0_ovf_isr()Timer loop every 10mSecDate : 01.08.2006

-----------------------------------------------------------------------------*/void timer0_ovf_isr(void){ // RONitialize Timer 0 value TCNT0 = 0xB2; // 10mS Get_Batt_Volt(); Get_Tiltangle(); Algorythmus(); Signal_Processing(); Set_PWM(); intervalz++; if(intervalz>=20) // generate 200mSec. interval { intervalz=0; interval=~interval; }}

/*-----------------------------------------------------------------------------Function : init()Initial the MCU HardwareDate : 01.08.2006

-----------------------------------------------------------------------------*/void init(){ // Input/Output Ports initialization // Port A initialization // Func7=In Func6=In Func5=In Func4=In Func3=In Func2=In Func1=In Func0=In // State7=T State6=T State5=T State4=T State3=T State2=T State1=T State0=T PORTA=0x00; DDRA=0x00;

// Port B initialization // Func7=Out Func6=Out Func5=Out Func4=In Func3=In Func2=In Func1=Out Func0=Out // State7=1 State6=1 State5=1 State4=T State3=T State2=T State1=1 State0=0 PORTB=0xE2; DDRB=0xE3;

// Port C initialization // Func7=Out Func6=Out Func5=Out Func4=Out Func3=Out Func2=Out Func1=Out Func0=Out // State7=0 State6=0 State5=0 State4=0 State3=0 State2=0 State1=0 State0=0 PORTC=0x00; DDRC=0xFF;

// Port D initialization // Func7=Out Func6=Out Func5=Out Func4=Out Func3=Out Func2=Out Func1=Out Func0=Out // State7=0 State6=0 State5=0 State4=0 State3=0 State2=0 State1=0 State0=0 PORTD=0x30; DDRD=0xFF;

// Timer/Counter 0 initialization // Clock source: System Clock // Clock value: 7,813 kHz // Mode: Normal top=FFh // OC0 output: Disconnected

Pavner 28

Page 29: Self Bal Scooter

TCCR0=0x05; TCNT0=0xB2; OCR0=0x00;

// Timer/Counter 1 initialization // Clock source: System Clock // Clock value: 8000,000 kHz // Mode: Ph. correct PWM top=00FFh // OC1A output: Non-Inv. // OC1B output: Inverted // Noise Canceler: Off // Input Capture on Falling Edge // Timer 1 Overflow Interrupt: Off // Input Capture Interrupt: Off // Compare A Match Interrupt: Off // Compare B Match Interrupt: Off

TCCR1A=0xB1; TCCR1B=0x01; TCNT1H=0x00; TCNT1L=0x00; ICR1H=0x00; ICR1L=0x00; OCR1AH=0x00; OCR1AL=0xff; OCR1BH=0x00; OCR1BL=0x00;

// Timer/Counter 2 initialization // Clock source: System Clock // Clock value: Timer 2 Stopped // Mode: Normal top=FFh // OC2 output: Disconnected ASSR=0x00; TCCR2=0x00; TCNT2=0x00; OCR2=0x00;

// External Interrupt(s) initialization // INT0: Off // INT1: Off // INT2: Off MCUCR=0x00; MCUCSR=0x00;

// Timer(s)/Counter(s) Interrupt(s) initialization TIMSK=0x01;

// Analog Comparator initialization // Analog Comparator: Off // Analog Comparator Input Capture by Timer/Counter 1: Off // Analog Comparator Output: Off ACSR=0x80; SFIOR=0x00;

// ADC initialization // ADC Clock frequency: 62,500 kHz // ADC Voltage Reference: AVCC pin // ADC High Speed Mode: Off // ADC Auto Trigger Source: None ADMUX=FIRST_ADC_INPUT|ADC_VREF_TYPE; ADCSRA=0xCF; SFIOR&=0xEF;}

Pavner 29

Page 30: Self Bal Scooter

/*-----------------------------------------------------------------------------Function : main()Date : 01.08.2006

-----------------------------------------------------------------------------*/void main(void){init();

#asm("sei") // Global enable interrupts

delay_ms(500);

while (1){ // Set debug LED's if(Drivespeed>240 || Drivespeed<-240) { LED1 = ON; } else { LED1 = OFF; } if(Drivespeed>180 || Drivespeed<-180) { LED2 = ON; } else { LED2 = OFF; }

if(Voltage < Batt_low) { Batt_low_flag = interval; } else { Batt_low_flag = 0; }

BUZZER = Overspeed_flag || Batt_low_flag;};}

Pavner 30

Page 31: Self Bal Scooter

10. Sources / References

The MCUhttp://www.atmel.com

Thanks to Trevor Blackwell for good ideashttp://www.tlb.org/scooter.html

Acceleration Sensors and Gyro Sensorshttp://www.analog.com/

The perfect systemhttp://www.segway.com/

Balancing basicshttp://www.tedlarson.com/robots/balancingbot.htm

Balancing one Wheelhttp://fhznet.fh-bielefeld.de/fb2/labor-le/le3einrad.html

C-Compilerhttp://www.hpinfotech.ro

Eagle Layout CADhttp://www.cadsoft.de/

Pavner 31