Vcc - U) * R1) / U Where: RFSR - FSR Resistance Vcc – supply voltage. Usually 5 V U – The measured voltage. The ADC reading must be converted to 0 V - Vcc R1 – resistor. 10 k Then you can calculate the conductivity CFSR in S/m [Siemens per meter]. The conductance is plotted vs. force (the inverse of resistance: 1/r). This format allows interpretation on a linear scale. CFSR = 1 / RFSR Use the FSR guide graphs on the datasheet to approximate the force. It depends on the measurable range. For example (0-1 Kg) low force range can be use formula: FFSR = CFSR / 80 The example program of the force sensor shows the measured force (Newtons) and weight (kg) on the LCD.
 

//
// The demonstration program of the force sensor.
// The LCD display shows the measured force (Newtons) and weight (kg).
//
#include <stdio.h>
#include <homelab/adc.h>
#include <homelab/delay.h>
#include <homelab/pin.h>
#include <homelab/module/lcd_gfx.h>
 
//
// Map a value from one range to another.
//
long map(long x, long in_min, long in_max, long out_min, long out_max)
{
  return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
 
//
// The main program.
//
int main(void)
{
	signed short value;// The analog reading.
	char text[16];
	int voltage;      // The analog reading converted to voltage.
	unsigned long resistance;// The voltage converted to resistance.
	unsigned long conductance; 
	long force; // The resistance converted to force. 
	long weight; // The force converted to weight. 
 
 
	// Set the external sensors pins.
	pin ex_sensors = PIN(G, 0);
	pin_setup_output(ex_sensors);
	pin_set(ex_sensors);
 
	// LCD initialization.
	lcd_gfx_init();
 
	// Display clearing.
	lcd_gfx_clear();
 
	// Move the cursor to the right of the screen.
	lcd_gfx_goto_char_xy(1,1);
 
	// Print the name of the program.
	lcd_gfx_write_string("Force sensor");
 
	// Set the ADC.
	adc_init(ADC_REF_AVCC, ADC_PRESCALE_8);
 
	// An endless loop.
	while (true)
	{
		// Converting and averaging channel 0 value.
		value = adc_get_average_value(0, 4);
 
		// Analog voltage reading ranges from about 0 to 1023 
		// which maps to 0V to 5V   (= 5000mV)
	        voltage = map(value, 0, 1023, 0, 5000);
 
		// The voltage = Vcc * R / (R + FSR) where R = 10K and Vcc = 5V
    	        // so FSR = ((Vcc - V) * R) / V
		resistance = 5000 - voltage;     // fsrVoltage is in millivolts so 5V = 5000mV
	        resistance *= 10000;             // 10K resistor
	        resistance /= voltage;           // FSR resistance in ohms.
 
		conductance = 1000000;           //We measure in micromhos.
	        conductance /= resistance;	 //Conductance in microMhos.
 
 		// Move the cursor to the right of the screen.
		lcd_gfx_goto_char_xy(1,3);
 
		// Calculate the force.	    
                force = conductance / 80;
                sprintf(text, "%lu Newtons   ", force);
 
		// Printing of the force.
		lcd_gfx_goto_char_xy(1,3);
		lcd_gfx_write_string(text);
 
		// Printing and calculating of the weight.
		lcd_gfx_goto_char_xy(1,4);
		weight = force / 9,8;
		sprintf(text, "%lu kg   ", weight);
		lcd_gfx_write_string(text);
 
		// Delay.
		sw_delay_ms(500);
	}
}

===== Motors ===== Motors are actuator devices, actually some of them are and those can also be very different, beginning with operating principles and ending with power and size. In robotics mainly electric motors are used. Electrical motor is a device which converts electrical energy to mechanical energy (work). It works on principles of electromagnetism. There are several ways to classify electrical motors. Most important is to divide them as alternate current (AC) and direct current (DC) motors. In addition, there are electrical motors with brushes and brush-less motors, linear motors and rotary motors, nano-motors and large motors and so on. On the other hand, some of the segmentations are provisional. For example, linear motion is achieved usually using rotary electrical motor, which is integrated into unitary body with screw mechanism and treated so as linear actuator. In this chapter are covered three most common types of electrical motors in robotics: DC motor with permanent magnets, RC servos and stepper-motor. ===== DC motor ===== Necessary knowledge: [HW] Motor Module, [AVR] Digital Inputs/Outputs, [LIB] Motors, [LIB] Delay ==== Theory ====

DC motor

Permanent magnet DC motors are very common in different applications, where small dimensions, high power and low price are essential. Due to their fairly high speed, they are used together with transmission (to output lower speed and higher torque).

The perfect graph of relationship between speed (V), current (I), power (P), efficiency (η)and torque (T)of a DC motor.

Permanent magnet DC motors have quite simple construction and their controlling is quite elementary. Although controlling is easy, their speed is not precisely determined by the control signal because it depends on several factors, primarily of the torque applied on the shaft and feeding current. The relationship between torque and speed of a ideal DC motor is linear, which means: the higher is the load on the shaft the lower is the speed of the shaft and the higher is the current through the coil. Brushed DC motors are using DC voltage and basically do not need special control electronics because all necessary communication is done inside the motor. When the motor is operating, two static brushes are sliding on the revolving commutator and holding the voltage on the coils. The direction of revolving of the motor is determined by the polarity of the current. If the motor must revolve in only one direction, then the current may come through relay or some other simple connection. If the motor has to revolve in both directions, then an electronic circuit called H-bridge is used.

The working principle of H-bridge used on switches.

In the H-bridge are four transistors (or four groups) directing the current for driving the motor. The electrical scheme of the H-bridge is similar to the letter H and that is where it gets its name. The peculiarity of the H-bridge is the possibility to apply both directional polarities to the motor. Picture on the side shows the principal scheme of the H-bridge based on the example of the switches. If two diagonal switches are closed, the engine starts operating. The direction of the revolving of the motor depends on in which diagonal the switches are closed. In the real H-bridge the switches are replaced with transistors which are selected according to the current of the motor and voltage. There exist also integrated H-bridges, for conducting smaller currents. For higher currents special power MOSFET-s are used. The H-bridge with other electronics is called motor controller or driver. The driver of DC motor in the HomeLab L293D includes 2 integrated H-bridges and circuit breaking diodes. The motor is controlled with three digital signals,one of them is operation enabling signal enable and the other two are determining the state of the transistors in the H-bridge. Never can occur that two vertical transistors are opened, because this would short-circuit the power source. This means that the driver is designed as foolproof and only option that can be chosen is which transistor (upper or bottom) of one side of the H-bridge (of “semi-bridge”) is opened. In other words the polarity is selected using two driving signals which is applied to the two ends of the coil of the motor. ==== Practice ==== The board of the motors of the HomeLab allows connecting up to four DC motors. The schemes and instructions for connection are found in the chapter “Motors module”. Basically, for every motor there is a H-bridge which is controlled with two digital output pins of the microcontroller, because the enable pin is constantly high. If both controlling pins have same value, then the motor is stopped if different then it revolves in the corresponding direction. The state of the H-bridge is described in the following table: ^ Input A ^ Input B ^ Output A ^ Output B ^ Result ^ | 0 | 0 | - | - | The motor is stopped | | 1 | 1 | + | + | The motor is stopped | | 1 | 0 | + | - | The motor revolves in direction 1 | | 0 | 1 | - | + | The motor revolves in direction 2 | DC motors can be controlled by manipulating directly corresponding driver pins with microcontroller. Though, special functions for driving the motor are in the library of the HomeLab.

//
// The setup of the pins driving pins.
//
static pin dcmotor_pins[4][2] =
{
	{ PIN(B, 7), PIN(B, 4) },
	{ PIN(D, 1), PIN(D, 0) },
	{ PIN(D, 7), PIN(D, 6) },
	{ PIN(D, 5), PIN(D, 4) }
};
 
//
// Allowing the control of the chosen DC motor.
//
void dcmotor_init(unsigned char index)
{	
	pin_setup_output(dcmotor_pins[index][0]);
	pin_setup_output(dcmotor_pins[index][1]);
}
 
//
// Determining the operation and the direction of the chosen DC motor.
//
void dcmotor_drive(unsigned char index, signed char direction)
{	
	pin_set_to(dcmotor_pins[index][0], direction < 0);			
	pin_set_to(dcmotor_pins[index][1], direction > 0);
}

With the array dcmotor_pins in the library, the controlling pins of four motor-controllers are determined. Before controlling the motors, function dcmotor_init with the number of the motor-controller (0 – 3) must be called out. It sets the pins as output. For controlling is the function dcmotor_drive, with it the negative direction parameter is used to give to the motor one revolving direction and other direction with positive parameter, and 0 if the motor is stopped. The following is an example program which controls first and second DC motor so that they alter their revolving direction after every second. The speed could be controlled if one controlling pin were modulated with PWM signal

//
// Testing program of the DC motor of the motor's module of the home-lab.
//
 
#include <homelab/module/motors.h>
#include <homelab/delay.h>
 
//
// Main program
//
int main(void)
{
	// Variable of direction and speed.
	signed char direction = 1, speed = 1;
 
	// Setup of motors no 0.
	dcmotor_init(0);
 
        // Setup of motors no 1. pwm mode
	dcmotor_drive_pwm_init(1, TIMER2_NO_PRESCALE);
 
	// Endless loop
	while (true)
	{
		// One motor revolves in one direction and the other one to other direction.
		dcmotor_drive(0, direction);
		dcmotor_drive_pwm(1, direction, speed);
 
		// Break for 1 second.
		sw_delay_ms(1000);
 
		// Reversing the direction.
		direction = -direction;
 
		// The speed increase of +10.
		speed+=10;
 
	}
}

===== DC motor speed ===== Necessary knowledge: [HW] Motor Module, [AVR] Digital Inputs/Outputs, [LIB] Motors, [LIB] Delay ==== Theory ====

DC motor with wheel

Permanent magnet DC motors are very common in robotics and mechatronics. DC motors are relatively easy to control, both direction and speed. Motor rotation direction is determined by power supply polarity and H-bridge driver is often used when DC motor is controlled by microcontroller. Even DC motor speed is easy to control there is no guarantee that required speed is also actually obtained. The reason is that the actual speed depends on several factors, primarily of the torque applied on the shaft, feeding current and other motor characteristics. The relationship between torque and speed of a ideal DC motor is linear, which means: the higher is the load on the shaft the lower is the speed of the shaft and the higher is the current through the coil. In reality it is not linear and can vary depending on the motor quite a lot. Controlling the speed of DC motor can be realized either by analogous or digital signaling.

PWM signal examples for one period

In general, motor speed is dependent of the applied voltage. When powering motor with its nominal voltage, motor runs at its nominal speed at no load condition. When reducing the voltage motor speed and torque also decreases. This kind of speed control can be called as analogous motor speed control. This can be realized for example with one transistor. In robotics DC motors are in most cases controlled by microcontrollers and as microcontrollers are digital devices it is much easier to control motor speed also digitally. To do that, instead of keeping transistor open partly, transistors need to be closed and opened constantly using pulse width modulation (PWM), so the total energy supplied to the motor is somewhere between motor switched off and motor running on full power. Opened time in the whole PWM period is called duty cycle, which is marked as percents. 0% means the transistor is closed constantly – it is not conducting current. 100% means the transistor is constantly open and is conducting current all the time. The frequency of the PWM has to be high enough to avoid vibrations in the shaft of the motor. At low frequencies the motor produces noise and due to that, modulation frequencies over 20 kHz are used quite often. On the other hand the efficiency of the transistors might not be so good at higher frequencies. Vibrating of the shaft of the motor is reduced by inertia of the rotor and the inductivity of the coils. Instead of using single transistor, H-bridge can be feed with the same PWM signal by controlling so motor speed and direction. By using digital contorol, i.e. PWM signal to control the transistor and by this motor speed, there are several advantages over the analogous control. Most important ones for microcontroller driven systems are that speed can be controlled only by one single digital output (no need for complicated digital-analogous converter) and control is more effective (power dissipation are minimized).

Controlling motor speed with PWM

Simplified control schematics is shown on the figure. Control voltage Vc from microcontroller output pin turns on and off the transistor Q in approx. 20 kHz frequency. When Q is turned on (saturation), full current I flows freely through the motor M. In this state transistor acts as a closed switch and voltage on the transistor Vq is nearly 0 by leaving almost full Vdd across the motor. We can calculate the power dissipated by the transistor by using formula P = I × V. Applying this to Q: P = I × Vq, and if Vq = 0 also P = 0 W This means that almost no power is consumed by transistor when it is ON state. Similar situation is also when transistor is closed (OFF state). In this situation nearly no current flows through the motor and transistor. Calculating the power consumed by transistor once again: P = I × Vq, and if I = 0 also P = 0 W As a conclusion, when transistor operates only on and off states the efficiency can be very high as nearly no power is consumed by transistor itself. Compared with linear (analogous) control of the transistor when half of the power can be consumed by transistor in case motor is operated at half speed. However in practice, digital control (PWM) is also not totally lossless as transistors cannot be turned on and off instantaneously. Therefore little dissipation occurs in every transistor and every switching, by cousing bigger dissipation when frequency is higher. Note: do not mix up RC Servo PWM signal with ordinary PWM signals. ==== Practice ==== The Motor module of the HomeLab includes motor board and DC motor equipped with integrated gearbox and encoder. Motor board allows connecting up to four DC motors. The schemes and instructions for connection are found in the chapter “Motors module”. Every motor is connected to H-bridge which is controlled with two digital output pins of the microcontroller. Motor speed is controlled by timers which are generating software PWM signal for H-bridge. Motor speed can be controlled by relative value between 0 to 255, where 0 means that motor is stopped and 255 that motor runs at maximum speed.

//
// The setup of the pins driving pins.
//
static pin dcmotor_pins[4][2] =
{
	{ PIN(B, 7), PIN(B, 4) },
	{ PIN(D, 1), PIN(D, 0) },
	{ PIN(D, 7), PIN(D, 6) },
	{ PIN(D, 5), PIN(D, 4) }
};
 
static int motorindex[4][2] =
{
	{ 0, 1 },
	{ 2, 3 },
	{ 4, 5 },
	{ 6, 7 }
};
 
//
// Initialize PWM for specified DC motor. 
//
void dcmotor_drive_pwm_init(unsigned char index, timer2_prescale prescaler)
{
  	unsigned char i, pwm;
 
	pin_setup_output(dcmotor_pins[index][0]);
	pin_setup_output(dcmotor_pins[index][1]);
 
	motor[index] = 1;
 
  	pwm = PWMDEFAULT;
 
  	for(i=0 ; i<CHMAX ; i++)      // initialize all channels
  	{
    	  compare[i] = pwm;           // set default PWM values
    	  compbuff[i] = pwm;          // set default PWM values
  	}
 
	// Timer 2 normal regime, set prescaler
	timer2_init_normal(prescaler);
  	// Timer 2 interrupts set enabled
	timer2_overflow_interrupt_enable(true);
 
  	// Enable global interrupts
	sei();
}
 
void dcmotor_drive_pwm(unsigned char index, signed char direction, unsigned char speed) 
{
	if(direction = -1)
	{
		compbuff[motorindex[index][0]] = 0x00;
		compbuff[motorindex[index][1]] = speed;
	}
	if(direction = 1)
	{
		compbuff[motorindex[index][0]] = speed;
		compbuff[motorindex[index][1]] = 0x00;
	} 
}

With the array dcmotor_pins in the library, the controlling pins of four motor-controllers are determined. Before controlling the motors and their speed, function dcmotor_drive_pwm_init with the number of the motor-controller (0 – 3) must be called out. It sets the pins as output. In addition prescaler - timer2_prescale prescaler have to be set as a second parameter. Prescaler sets PWM frequency and is important when using other timer based functions on the same time. If only motors are used TIMER2_NO_PRESCALE value is most suitable. If other timer based functions are used on the same time e.g. ultrasonic sensor TIMER2_PRESCALE_8 is recommended value. Bigger prescaler values are not suitable for DC motor speed control as vibration will be too high. However the same function can be used for example flashing the LED and in this case bigger prescaler values are important to consider. For controlling motor speed the function dcmotor_drive_pwm is included into library. With this function three parameters are needed. First is motor index (0-3), second is direction -negative direction parameter is used to give to the motor one revolving direction and other direction with positive parameter, and 0 if the motor is stopped. Third parameter is speed where the value can be from 0 to 255. The speed value is not any specific rpm, but is relative value and the actual speed is depending on the motor and power supply. The precision of motor speed control is 8-bit, meaning that smallest controlling value is 1/255 of full speed. The following is an example program which controls first DC motor (DC motor connector 0) so that motor speed is half of the full speed. The speed is modulated with PWM signal of controlling pin.

//
// Desc.: DC motor speed control
// Hardware: ATMega2561 Controller board, Motor board with DC motor
// Author: Raivo Sell, 2012
//
#include <homelab/delay.h>
#include <homelab/module/motors.h>
 
int main(void)
{
 
	// DC motor 0 init with no prescaler
  	dcmotor_drive_pwm_init(0, TIMER2_NO_PRESCALE);
 
  	while(1)
  	{   	
 
		// DC motor drive with half of the nominal speed
		dcmotor_drive_pwm(0, 1, 128);			      
  	}
}

Another example program which controls first DC motor (DC motor connector 0) with potentiometer from Sensor module.

//
// Desc.: DC motor speed control with potentiometer
// Hardware: ATMega2561 Controller board, Motor board with DC motor, Sensor board
// Author: Raivo Sell, 2012
//
#include <homelab/delay.h>
 
#include <homelab/module/motors.h>
#include <homelab/adc.h>
 
int main(void)
{
	int speed;
 
	// Adjusting ADC
	adc_init(ADC_REF_AVCC, ADC_PRESCALE_8);
 
	// DC motor 0 init with no prescaler
  	dcmotor_drive_pwm_init(0, TIMER2_NO_PRESCALE);
 
  	while(1)
  	{
		// Potentiometer is connected to channel 3
		// Average of 4 samples are acquired
		speed = adc_get_average_value(3, 4);
 
		// DC motor drive with speed from potentiometer
		// As potentiometer has 10-bit output but DC motor drive function
		// 8-bit input the adc output have to be converted to 8-bit
		// e.g dividing the output with 4, or shifting bit 2 position >>2
		dcmotor_drive_pwm(0, 1, speed/4);
  	}
}

===== Servomotor ===== Necessary knowledge: [HW] Motor Module, [HW] Sensors Module, [AVR] Digital Inputs/Outputs, [LIB] Motors, [LIB] Analog to Digital Converter ==== Theory ====

RC servo motor
The relationship between width of the signal and position of Servo PWM.

Servo motors are often used in radio-controlled (RC) models, and are very useful in different kinds of small robotics applications because they are compact and inexpensive. An RC servo motor includes a built-in DC motor, gearbox, position feedback sensor (usually potentiometer), and drive electronics. RC servo motors can be controlled by an external pulse-width modulation (PWM) signal. If a signal meets RC servo timing requirements, it usually “describes” a (target) position input for the servo drive electronics. Servo motor electronics compare the shaft position with the inputted position, trying to find a shaft position where they match. The position control signal is a continuous square-wave signal, as depicted in figure. RC (radio-controlled) servo-motors are very common actuator devices in robotics and model building. RC servo motors are consisting of small DC motor, reduction gear and control logic device. Usually the rotor of the servo motor moves to a certain position and tries to maintain that position. The position of the rotor depends of the control signal received by the servo motor. Depending on the type of the motor, the maximum revolving angle of the motor may differ. Servo motors that revolve constantly are rare. In this case, the control signal determines not the revolving angle but the speed of revolving. Servo motor “hack” is also quite common. This makes the position determining servo motor to constantly revolving servo. In this case the feedback potentiometer is replaced by two fixed resistors and the mechanical resistor that prevents full rotations is removed from the gear. A very important characteristic of servo motors is its power-weight ratio. The controlling signal of servo motor is specific pulse with modulated signal (PWM), where width of the pulse determines the position of the rotor. The period of the signal is 20 ms (50 Hz) and the width of the high period is 1 ms – 2 ms. 1 ms marks one extreme position and 2 ms marks the second one. 1,5 ms marks the middle position of the servo motor’s rotor. Traditional RC servo motor is also known as analogue-servo motor. It is because in the last decade so called digital servo motors were becoming common. The difference between those two is that in analogue servo motor the motor is controlled by the same 50 Hz PWM input signal. In digital servo motor the motor is controlled by a microcontroller with much higher frequency signal. The input signal is the same in the digital servo motor but higher modulation frequency of the motor enables much more precise and faster position determining.

==== Practice ==== On the board of module of motors of the HomeLab are two plugs for connecting RC servo motors. The PWM ends of the plugs are connected to the PB5 and PB6 pins of the microcontroller, which alternative functions are outputs of comparing units A and B of the timer 1. Timer 1 is capable of producing PWM signal and due to that the control of motors is very simple in the program. Only difficulty is set-up of the timer. The timer 1 must be set up in PWM production mode, where the maximum value of the timer is determined with ICR register. With the maximum value changed in the program and in the pace divider of the timer, the precise PWM frequency for controlling the servo motor can be determined. With the comparison register of the timer, lengths of both high semi periods of PWM signal can be determined. The timers have special comparing units which are monitoring the value of the counter and in case it remains equal with the value of the comparison register they change the output value of comparing units. The following is the program code of the servo motor control library of the HomeLab. For the purpose of functionality, it uses parameters for timers which are determined with macro functions. For example, the period is found using F_CPU constant, which marks the clock rate of the microcontroller. When using macros, there is no need to calculate the parameters of timer for different clock rates and the compiler converts the operations with macros to constants anyway, so the program memory is not growing and does not demand more time.

//
// The value of the timer (20 ms)for achieving the full period of PWM.
// F_CPU is the clock rate of the microcontroller which is divided with 50 Hz and 8.
//
//
#define PWM_PERIOD      (F_CPU / 8 / 50)
 
//
// Middle position of PWM servo (5 ms / 20 ms)
// Middle position is 15/200 of full period.
//
#define PWM_MIDDLE_POS  (PWM_PERIOD * 15 / 200)
 
//
// Factor for converting the percents (-100% to 100%)to periods.
// +1 is added to ensure that semi periods would reach to the boundaries of 1 ms and 2 ms or // a little over.
//
#define PWM_RATIO       (PWM_PERIOD / 20 / 2 / 100 + 1)
 
//
// Set-up of the pins.
//
static pin servo_pins[2] =
{
	PIN(B, 5), PIN(B, 6)
};
 
//
// Preparing the servo motor for working.
//
void servomotor_init(unsigned char index)
{
	// The pin of PWM signal for output.
	pin_setup_output(servo_pins[index]); 
 
	// Setup of timer 1.
	// Prescaler = 8
	// Fast PWM mode, where TOP = ICR
	// OUTA and OUTB to low in comparisson.
	timer1_init_fast_pwm(
		TIMER1_PRESCALE_8,
		TIMER1_FAST_PWM_TOP_ICR,
		TIMER1_FAST_PWM_OUTPUT_CLEAR_ON_MATCH,
		TIMER1_FAST_PWM_OUTPUT_CLEAR_ON_MATCH,
		TIMER1_FAST_PWM_OUTPUT_DISABLE);
 
	// Determining the period by maximum value.
	timer1_set_input_capture_value(PWM_PERIOD);	
}
 
//
// Determining the position of the servo motor.
// The parameter of the position is from -100% to +100%.
//
void servomotor_position(unsigned char index, signed short position)
{	
	switch (index)
	{
		case 0:			
			timer1_set_compare_match_unitA_value(
				PWM_MIDDLE_POS + position * PWM_RATIO);
			break;
 
		case 1:
			timer1_set_compare_match_unitB_value(
				PWM_MIDDLE_POS + position * PWM_RATIO);
			break;
	}
}

The example program uses described functions of the library of the HomeLab. In the beginning of the program the first servo motor’s PWM signal generator is started with the servomotor_init function. The value of the position of the servo motor is obtained from the channel number 3 of the analogue-digital converter, where a potentiometer on the board of sensors is connected. To get the range -100 % - +100 % necessary for controlling the servo motor, half of the maximum (512) is subtracted of the ADC value and the result is divided with 5. The result is +/- 102, but small inaccuracy does not count because servo motors also differ by the relation of the PWM signal and revolving angle. Final PWM‘s semi period’s width in applications has to be determined using test-and-error method. Also the remote controls of RC models have corresponding opportunities for precise setup. When the program is started the rotors position of the servomotor is changed according to the position of the potentiometer.

//
// Testing program of the motors module of the HomeLab kit.
//
#include <homelab/adc.h>
#include <homelab/module/motors.h>
 
//
// Main program.
//
int main(void)
{
	short position;
 
	// Set-up of the ADC.
	adc_init(ADC_REF_AVCC, ADC_PRESCALE_8);
 
	// Set-up of the motor.
	servomotor_init(0);
 
	// Endless loop.
	while (true)
	{
		// Reading the position of the potentiometer and converting the range of
		// the servo motor.
		position = ((short)adc_get_value(3) - (short)512) / (short)5;
 
		// Determining the position of the servo motor.
		servomotor_position(0, position);
	}
}

===== Stepper motor ===== Necessary knowledge: [HW] Motor Module, [AVR] Digital Inputs/Outputs, [LIB] Motors ==== Theory ====

Stepper-motor

Stepper motors can generally be divided into unipolar and bipolar steppers. Unipolar stepper motors are characterized by their centre-tapped windings, which divide two coils into four. Stepper motors have neither built-in brushes nor internal electronics, meaning all commutation must be performed externally. The most common commutation type is the open-loop mode: the motor driver energizes the coils following a certain pattern, but uses no feedback. Steps can be missed in case of motor shaft torque overload. Missed steps cause inaccurate positioning. Bipolar stepper motors usually have four wires and two separate coils inside; they have many features similar to those of unipolar steppers. Unipolar stepper motors can be run as bipolar stepper motors, but not vice versa. Stepper-motors are widely used in applications which demand accuracy. Unlike DC motors, stepper motors do not have brushes nor commutator – they have several independent coils, which are commutated with exterior electronics (drivers). Rotating the rotor is done by commutating coils step by step, without feedback. This is one of the faults in stepper motors – in case of mechanical overloading, when the rotor is not rotating, the steps will be mixed up and movement becomes inaccurate. Two types of stepper motors are distinguished by coils: unipolar and bipolar stepper motors. By construction three additional segments are considered: * Variable Reluctance Stepper (high accuracy, low torque, low price) * Permanent Magnet Stepper (low accuracy, high torque, low price) * Hybrid Synchronous Stepper (high accuracy, high torque, high price) Variable reluctance stepper motors have toothed windings and toothed iron rotor. The largest pulling force is when the teeth of both sides are covering each other. In Permanent magnet stepper motor,just like the name hints, are permanent magnets which orientate according to the polarity of the windings. In hybrid synchronous steppers both technologies are used. Depending on the model of stepper motor, performing one full rotation (360 degrees) of the rotor, demands hundredths of steps of commutations. For stable and smooth movement, appropriate control electronics are used which control the motor according to its parameters (inertia of the rotor, torque, resonance etc.). In addition to control electronics different commutating methods may be applied. Commutating one winding in a row is called Full Step Drive and if the drive is alternated between one and two windings it is called Half Stepping. Cosine micro stepping is also used, allowing specially accurate and smooth controlling.

 
Unipolar stepper-motor

The windings of an unipolar-stepper motor

Unipolar-stepper motor has 5 or 6 leads. According to the scheme of the motor only ¼ of the windings is activated. Vcc lines are usually connected to the positive power supply. During commutation the ends of windings 1a, 1b, 2a and 2b are connected through transistors (transistor array of the motor board ULN2803) only to the ground and that makes their control electronics fairly simple. Bipolar stepper-motor

The windings of a bipolar stepper-motor.

Bipolar stepper motor differs from unipolar stepper motor by having the polarity of the windings altered during the commutation. Half of the windings are activated together, this allows to gain higher efficiency than unipolar stepper motors. Bipolar stepper motors have four leads, each connected to a different half-bridge (driver L293 on the board of motors). During commutation half-bridges are applying either positive or negative voltage to the ends of the windings. Unipolar motors can be started using bipolar driver: just connect lines 1a, 1b, 2a and 2b of the windings (Vcc will be not connected). The commutation necessary for controlling stepper-motors with windings at full step mode and half step mode is displayed in the table below. Since in drivers for uni-polar stepper motors only opening of the transistors takes place, the steps are marked by 0 and 1. Controlling of bipolar stepper motors may need more signals and therefore the steps are marked using the polarity of the driver outputs: ^ ^ Unipolar ^^^^ Bipolar ^^^^ ^ Step ^ 1A ^ 2A ^ 1B ^ 2B ^ 1A ^ 2A ^ 1B ^ 2B ^ ^ Full step ^^^^^^^^^ | 1 ^ 1 | 0 | 0 | 0 ^ + | - | - | - | | 2 | 0 ^ 1 | 0 | 0 | - ^ + | - | - | | 3 | 0 | 0 ^ 1 | 0 | - | - ^ + | - | | 4 | 0 | 0 | 0 ^ 1 | - | - | - ^ + | ^ Half step ^^^^^^^^^ | 1 ^ 1 | 0 | 0 | 0 ^ + | - | - | - | | 2 ^ 1 ^ 1 | 0 | 0 ^ + ^ + | - | - | | 3 | 0 ^ 1 | 0 | 0 | - ^ + | - | - | | 4 | 0 ^ 1 ^ 1 | 0 | - ^ + ^ + | - | | 5 | 0 | 0 ^ 1 | 0 | - | - ^ + | - | | 6 | 0 | 0 ^ 1 ^ 1 | - | - ^ + ^ + | | 7 | 0 | 0 | 0 ^ 1 | - | - | - ^ + | | 8 ^ 1 | 0 | 0 ^ 1 ^ + | - | - ^ + | ==== Practice ==== The goal of this exercise is to start a bipolar stepper motor, which can be replaced by unipolar stepper motor using the above described method. There are drivers, on the board of motors, which must be controlled via four input pins by the microcontroller. Each pin represents the polarity of one end of a winding. The voltage of the end of the winding is positive if the pin is high and negative if the pin is low. To the ends 1A, 1B, 2A and 2B correspond the pins of the microcontroller PB0, PB1, PB2 and PB3. There is function bipolar_init in the library of the HomeLab for controlling the bipolar stepper motors setting the pins as output and function bipolar_halfstep executes revolving by determined half steps. The commutation is done by the table of half steps, but more complex bit operations are used.

//
// Preparing for controlling the bipolar stepper motor.
//
void bipolar_init(void)
{
	DDRB |= 0x0F;
	PORTB &= 0xF0;
}
 
//
// Moving the bipolar stepper motor by half steps.
//
void bipolar_halfstep(signed char dir,
	unsigned short num_steps, unsigned char speed)
{
	unsigned short i;
	unsigned char pattern, state1 = 0, state2 = 1;
 
	// Insuring the direction +- 1
	dir = ((dir < 0) ? -1 : +1);
 
	// Execution of half-steps.
	for (i = 0; i < num_steps; i++)
	{		
		state1 += dir;
		state2 += dir;
 
		// Creating the pattern.
		pattern = (1 << ((state1 % 8) >> 1)) |
		          (1 << ((state2 % 8) >> 1));
 
		// Setting the output.
		PORTB = (PORTB & 0xF0) | (pattern & 0x0F);
 
		// Taking a break to wait for executing the step.
		sw_delay_ms(speed);
	}
 
	// Stopping the motor.
	PORTB &= 0xF0;
}

Usage of the functions is demonstrated by the example program which rotates the motor alternately to one direction and then to the other direction 200 half steps. The speed of rotating the motor is determined by the length of the brakes made between the steps. If the break is set to be too short, the motor can not accomplish the turn due to the inertia of the rotor and the shaft does not move.

//
// The test program for the bipolar stepper motor of the motor's
//module of the HomeLab.
//
#include <homelab/module/motors.h>
 
//
// Main program.
//
int main(void)
{
	// Set up of the motor.
	bipolar_init();
 
	// Endless loop.
	while (true)
	{
		// Turning the rotor 200 half steps to one direction at speed of 30 ms/step.
		bipolar_halfstep(+1, 200, 30);
 
		// Turning 200 half steps to the other direction at speed 30 ms/step.
		bipolar_halfstep(-1, 200, 30);
	}
}
en/book1.txt · Last modified: 2020/07/20 09:00 by 127.0.0.1
CC Attribution-Share Alike 4.0 International
www.chimeric.de Valid CSS Driven by DokuWiki do yourself a favour and use a real browser - get firefox!! Recent changes RSS feed Valid XHTML 1.0