thanks all for the comments and ideas , now for improving on the theme
/*****************************************************************************************
Title: MOSFET Radio Control DC motor controller
Author: D Armstrong dud.one@ntlworld.com
File: $Id: motor.c, v 2.1 22/4/2006 $
Software: AVR-GCC 3.4.5 ( Winavr 20060125 )
Hardware: AT90S2313 at 10.0MHz or atmega128
Copyright (c) use for whatever purpose you wish , change modify as you want, but dont blame me if it all goes pearshaped
all i ask is , if you modify or can improve please email a copy back and i will incorporate changes
for future users . it would be nice to remove the scale factor and have calibration in code saved in eeprom etc
DESCRIPTION:
The board is designed to control a DC motor for a remote control application, notably RC Model Aircraft. It takes input
from a standard RC receiver and produces a PWM output to drive a motor via a MOSFET circuit. It also monitors
battery voltage and disables to motor when it becomes too low.
The main task is to poll the incoming signal on PB4 to see when it changes. The period is about 22ms. For the
JR Propo R700 the pulse width is between 1.08ms and 2.04ms. The trim can vary this from 1.02ms to 2.15ms.
Set up timer 0 to clk/256 = 25.6 microseconds, and look for a pulse width count more than 43 (1.08ms) and less
than 78 (2.04ms). This leaves a band at the lower and upper ends for safety. We do this by polling the signal
until it turns on high, then start timer 0. Continue polling until it is low, then read the timer.
Once we have the pulse width count, we will generate a PWM signal using the timer 1 interrupt. Clock timer 1
at ck/8 giving a 0.8 microsecond resolution. If the incoming pulse width is between 43 and 78, scale up by 8.
An empirical maximum count of 230 gives a PWM period of about 210us (about 5kHz). Start the timer for
the first part of the PWM cycle, check for comparator match, and toggle the PWM output. Set the timer to count
for the remainder of the cycle, then toggle the PWM output, and so on.
A section of code is activated once every "timer_count" cycles to provide a place for execution of infrequent
events. This includes battery checks and lost signal checks. The motor speed changes occur here also, even though
the computation of speed change is done every cycle and smoothed.
A valid signal is one that falls within a range of pulse widths from just below the lowest to just above the
highest (using about 130us safety margin). On initialisation this valid range is much reduced to just above the
minimum pulse width.
When a sequence of valid signals exceeds a count of 16 in a row, then the signal is considered good and a change
of motor speed is permitted. The absence of this good signal indication is also used to determine if a signal
has been lost. As a lost signal can result in a failure of pulses to arrive, a variable is used to track this
condition. Make sure that at least five pulse periods are present within the "infrequent event" period,
otherwise a false "lost signal" can occur, disabling the motor prematurely. A timer_count of 10000 seems to be
adequate for a 10MHz clock. The R700 produces random pulses out (response to noise) while the JETI Rex 5 simply
stops in a high or low state when signal disappears.
The motor is not enabled until a valid signal that gives a motor off condition is first detected. That is, once
the motor has been disabled by an event (usually battery low but also on startup), the operator must reduce the
control to zero in order to enable it. The motor is turned off if the signal disappears for a given period of
time (nominally 1 second).
A battery low signal, detected by the analogue comparator, will turn off and disable the motor. If the
battery recovers, the motor can be re-enabled automatically or by the normal manual process.
*/
/* code is compiled for AT90S2313 and will compile for Atmega128
by adding the following defines it should work on others
without too many changes */
#define OCR1L _SFR_IO8(0x2A)
#define OCR1H _SFR_IO8(0x2B)
#include <avr/io.h>
#include <avr/wdt.h>
/***************************************************************************************/
const unsigned short in_pw_min=43; /* Minimum input pulse width */
const unsigned short in_pw_max=78; /* Maximum input pulse width */
const unsigned short PWM_period=232; /* Count for PWM period timer (multiple of 8 best) */
const unsigned short scale=9; /* Scale factor to convert input to PWM */
const unsigned short signal_lost_count=8; /* Countdown to determine if a signal is lost */
const unsigned short pulse_threshold = 4; /* Count to determine if a valid pulse occurred */
const unsigned short battery_threshold = 4; /* Count to determine if a battery low has occurred */
const unsigned short timer_count = 10000; /* Count for infrequent event timer loop */
const unsigned short PWM_step = 10; /* Step for motor speed on ramp up/down */
/* GLOBAL STATE VARIABLES */
unsigned short pulse_present; /* A valid pulse is in progress */
unsigned short pulse_started; /* A pulse start has been detected */
unsigned short pulse_ended; /* A pulse end has been detected */
unsigned short motor_enable; /* Use to keep motor off until conditions right */
unsigned short battery_down; /* A low battery voltage has been detected */
unsigned short battery_low; /* A low battery voltage has been determined */
unsigned short pulse_width; /* A measure of the input pulse width */
unsigned short PWM_width; /* PWM width setting for intermediate speed */
unsigned short PWM_final_width; /* PWM width setting for final speed goal */
unsigned short PWM_on; /* The PWM cycle is in the "on" period */
unsigned short PWM_limit; /* Speed limit on motor */
unsigned short PWM_count; /* Value read from PWM timer */
unsigned short PWM_active; /* Allow PWM processing to occur when needed */
unsigned short signal_check; /* Timer to check if a signal is present */
unsigned short valid_signal; /* Indicates the input is in a valid range */
unsigned short good_signal; /* Indicates a strong signal is present */
unsigned short timer; /* Used to create a time delay loop for infrequent events */
unsigned short pulse_detected; /* We need this to find out if pulses are actually occurring */
int main(void)
{
/*******************************************************************************************************/
/* Initialise hardware timers and ports */
#define INIT_HARDWARE ({ \
TCCR0 = 0; /* Stop timer 0 */ \
TCCR1B = 0; /* Stop timer 1 */ \
TCCR1A = 0; /* Disable hardware actions on timer 1 */\
OCR1H = 0; /* Clear the Output Compare Register */ \
OCR1L = 0; \
DDRB = 0xEC; /* Set unused B ports and B3 to output */\
ACSR = 0; /* Enable comparator */ \
(PORTB) |= (1 << (PB3)); /* Turn off motor */ \
})
/*******************************************************************************************************/
/* Initialise the global variables used in tracking states */
#define INIT_GLOBALS ({ \
motor_enable = 0; /* Keep it disabled for now */ \
signal_check = 0; /* Use to check if a signal is present */\
pulse_started = 0; /* Use to test if a pulse starting */ \
pulse_ended = 0; /* Use to test if a pulse ending */ \
pulse_detected = 0; /* No pulses detected */ \
battery_down = 0; /* Used to test if a battery low condition occurred */\
PWM_width = 0; /* Intermediate fraction of PWM cycle to activate */\
PWM_final_width = 0; \
PWM_on = 0; /* Start PWM in the "off" cycle */ \
PWM_limit = PWM_period; \
valid_signal = 0; /* Use to filter out bad signals */ \
good_signal = 0; \
timer = 0; /* Start the infrequent event timer*/ \
})
/********************************************************************************************************/
/* Configure and reset timer 0 */
#define INIT_TIMER_0 ({ \
TCCR0 = 0x04; /* Start timer 0 clk/256 (up to 8ms count) */\
TCNT0 = 0; /* Clear timer 0 to start counting */\
})
/********************************************************************************************************/
/* Reset timer 1 (16 bit timer) */
#define RESET_TIMER_1 ({ \
TCNT1H = 0; \
TCNT1L = 0; \
})
/**********************************************************************************************************/
/* This processes several state variables to determine if a pulse is starting, by waiting for pulse_threshold
cycles. It then determines if the pulse is finishing by waiting a similar amount of time. This type of
filtering may be overkill, hardware filtering in the receiver could make it redundant. */
#define TEST_PULSE ({ \
if (bit_is_set(PINB,PB4)) /* Check to see if a pulse is starting */\
{ if (pulse_present && pulse_ended) pulse_ended = 0; /* Abortive pulse end detected, so clear count */\
if (! pulse_present) /* Looks like the start of a new pulse */\
pulse_present = (pulse_started++ > pulse_threshold);/* Bump start verification count and test */\
} \
else \
{ if (! pulse_present && pulse_started) pulse_started = 0;/* Abortive pulse detected, so clear count */\
if (pulse_present) \
pulse_present = (pulse_ended++ <= pulse_threshold); /* Bump end verification count and test */\
} \
})
/*********************************************************************************************************/
/* If the motor is enabled, Find the input pulse width count and calculate the scaled PWM output pulse width.
Motor is enabled here also if the PWM setting is zero.
Filtering over 8 samples is applied to smooth out noise in the pulse width */
#define COMPUTE_PWM_SETTING ({ \
if (pulse_width > in_pw_min) /* If greater than minimum allowed pulse */\
{ if (motor_enable) /* Only allow changes if motor enabled */\
{ PWM_final_width = (7*PWM_final_width+scale*(pulse_width-in_pw_min))/8; /* Scale and smooth */\
if (PWM_final_width > PWM_limit) \
PWM_final_width = PWM_limit; \
} \
} \
else \
{ PWM_final_width = 0; \
motor_enable = 1; /* Can safely enable motor having detected motor off*/\
} \
})
/**********************************************************************************************************/
/* Just turn off the motor */
#define MOTOR_OFF ({ \
PWM_final_width = 0; /* Turn motor off */ \
})
/********************************************************************************************************/
/* Setup PWM counters and set motor control for cases of motor full on, full off or in PWM mode.
The actual PWM setting is changed gradually until it reaches the computed final speed setting. */
#define INIT_PWM ({ \
TCCR1B = 0; /* Turn off Timer 1 */ \
PWM_active = 0; /* Don't allow PWM processing yet */ \
if (PWM_final_width > PWM_width) /* Move PWM setting up towards goal */ \
{ PWM_width += PWM_step; \
if (PWM_final_width < PWM_width) /* Check if we have jumped past it */ \
PWM_width = PWM_final_width; \
} \
else if (PWM_final_width < PWM_width) /* Move PWM setting down towards goal */\
{ if (PWM_width < PWM_step) /* check we don't go below zero*/ \
PWM_width = 0; \
else \
PWM_width -= PWM_step; \
if (PWM_final_width > PWM_width) /* Check if we have jumped past it */ \
PWM_width = PWM_final_width; \
} \
if (PWM_width == 0) /* if shorter than minimum width */ \
(PORTB) |= (1 << (PB3)); /* Turn motor fully off */ \
else if (PWM_width == PWM_limit) /* else if at upper limit */ \
(PORTB) &= ~(1 << (PB3)); /* Turn motor fully on */ \
else /* Setup timer for timed PWM cycle */ \
{ (PORTB) |= (1 << (PB3)); /* Pulse motor off to start */ \
PWM_active = 1; /* If inbetween, allow PWM processing */\
TCCR1B = 0x02; /* Configure timer 1 at ck/8 */ \
RESET_TIMER_1; /* Start timer at 0 */ \
} \
})
/**********************************************************************************************************/
/* Detailed PWM processing: Check for position in the PWM cycle and execute cycle changes */
#define PWM_ACTIVATE ({ \
if (PWM_active) /* Only do this if PWM mode is appropriate */\
{ PWM_count = TCNT1; /* Read timer to get input pulse width */\
if (PWM_on) /* "On" part of cycle */ \
{ if (PWM_count > PWM_width) /* Check if timer has reached end of "on" cycle */\
{ (PORTB) |= (1 << (PB3)); /* Turn off motor */ \
PWM_on = 0; /* Advance to "off" part of cycle */ \
RESET_TIMER_1; \
} \
} \
else \
{ if (PWM_count > PWM_period-PWM_width) /* Check if timer has reached end of "off" cycle */\
{ (PORTB) &= ~(1 << (PB3)); /* Turn on motor */ \
PWM_on = 1; /* Advance to "on" part of cycle */ \
RESET_TIMER_1; \
} \
} \
} \
})
/**********************************************************************************************************/
/* Test over a few cycles to see if the battery has dropped below threshold defined in circuit */
#define CHECK_BATTERY ({ \
if (bit_is_clear(ACSR,ACO)) /* Battery low detected */ \
{ if (battery_down++ > battery_threshold) /* If a number of detections occur */ \
battery_low = 1; /* Set battery low variable */ \
motor_enable = 0; /* disable motor to lett bettery recover*/\
MOTOR_OFF; \
} \
else \
{ battery_down = 0; /* reset battery low signal if battery recovers */\
/* Use this code for an automatic soft motor control on battery low. When the battery recovers (after \
the motor has been turned off), it will clear the condition, re-enable the motor, but only allow a \
slightly lower maximum speed that cannot be increased. */ \
if (battery_low && (PWM_limit > 0)) /* If battery has recovered */ \
{ battery_low = 0; /* Clear battery low condition */ \
motor_enable = 1; /* Re-enable motor */ \
PWM_limit -= PWM_period/8; /* Drop maximum speed */ \
if (PWM_limit <= 0) /* If down to zero, stop everything */ \
{ PWM_limit = 0; \
motor_enable = 0; /* disable motor */ \
MOTOR_OFF; \
} \
} \
/* Use this code for a hard disable motor control on battery low. It will clear the condition but keep the
motor disabled. The operator can then try to restart it (by setting the control to zero then up again)\
if absolutely necessary */ \
/* battery_low = 0; */ \
} \
})
/*********************************************************************************************************/
/* MAIN PROGRAM */
unsigned short finished;
/* Watchdog timer - no need to reset as the macros do this */
/* Setup the watchdog timer for 30ms timeout */
wdt_enable(0x9);
INIT_HARDWARE;
INIT_GLOBALS;
/* First we will wait until the input signal is low (inactive) to get to a useful state */
finished = 0;
while (! finished)
finished = bit_is_clear(PINB,PB4);
pulse_present = 0; /* At this stage we now have no pulse present */
/* This is the big loop, testing for input pulse present and also activating PWM cycle and testing flat battery */
while (1)
{ wdt_reset(); /* Reset the watchdog timer */
/* Check the input pulse condition and activate motor changes */
TEST_PULSE; /* Test condition of input signal */
if (pulse_present && pulse_started) /* We have detected a pulse start */
{ pulse_started = 0;
INIT_TIMER_0; /* Start timer 0 counting to get pulse width */
}
if ((! pulse_present) && pulse_ended) /* We have detected a pulse end */
{ pulse_ended = 0;
pulse_detected = 1; /* Indicate a pulse (on-off) has been found */
(PORTB) |= (1 << (PB2)); /* Turn off PB2 */
pulse_width = TCNT0; /* Get pulse width from timer 0 value */
if (motor_enable) /* If enabled, accept any signal over whole range */
valid_signal = ((pulse_width > in_pw_min-5) && (pulse_width < in_pw_max+5));
else /* Wait for minimum control before accepting signal */
valid_signal = ((pulse_width > in_pw_min-5) && (pulse_width < in_pw_min+5));
if (valid_signal)
good_signal++; /* Count sequence of valid signals */
else
good_signal = 0; /* If a bad one, kill the sequence */
if (good_signal > 15) /* We have a continuously valid signal set */
{ COMPUTE_PWM_SETTING; /* Determine the PWM parameters for selected speed*/
good_signal = 16; /* Don't allow unlimited increase of this variable */
}
}
/* Activate the PWM pulse width control if needed. */
PWM_ACTIVATE; /* This actually times the PWM cycle in detail */
/* Infrequent Event Section: Perform some actions infrequently */
if (timer++ > timer_count)
{ timer = 0;
INIT_PWM; /* Setup PWM to run at selected speed */
/* Check the lost-signal counters. This triggers if no signal occurs for a while */
if (pulse_detected == 0) /* A proper pulse not detected in the last round */
MOTOR_OFF;
pulse_detected = 0; /* Reset this to ensure that a lost signal is caught */
(PORTB) &= ~(1 << (PB2)); /* Turn on PB2 */
if (good_signal > 15) signal_check = 0; /* If a good signal, reset lost-signal counter */
else if (signal_check++ > signal_lost_count) /* If we think we have lost the signal -- */
MOTOR_OFF;
/* Test for battery low. If so, turn off motor and disable. Two options to re-enable - either automatically when
battery voltage recovers, but to a lower maximum speed, or re-enabled if battery recovers but stays off, requiring
operator to follow manual process (note when the motor is turned off the battery voltage will increase, so you
probably can restart the motor, but do it gradually as too much juice will cause the battery voltage to fall
again and it will cut off the motor). */
CHECK_BATTERY;
}
} /* End of while loop */
/********************************************************************************/
}