The photo depicts a completed (bread-barded) locked anti-phase motor controller
using general purpose transistors, which allows you to
control small DC motors for robotics applications. The big picture problem is
that a normal DC motor controller does not have the "braking" function, which
allows for precise control. Solving this partially or completely is important
because precise motor control is needed in robotics applications, and where cost
is a factor. A DC motor is fairly cheap, dependent on size, compared to
other types of motors. This tutorial shows you how to
bread-board the motor controller hardware, and program the Netburner to
output the lcked anti-phase PWM. It takes approximately 3
hours to complete.
The rest of the tutorial is presented as follows:
To complete this tutorial, you'll need the following items:
| PART DESCRIPTION | VENDOR | PART | PRICE (1999) | QTY | |
| Netburner Development Kit | Netburner Inc. | MOD5213 | $99.00 | 1 | |
| USB to Serial Adapter* | ---- | ---- | $10 and up | 1 |
*If your computer does not have a 9 pin RS-232 Serial port, you will need to purchase a USB Adapter. They can be found almost anywhere on the internet, or in a computer store near you.

The next question deals with the concept of controlling the motor using the inverter technique on the h-bridge. With having the inverter on the signal, only one diagonal set of transistors can conduct at any given time, thus all 4 transistors will usually never be on. The motor is driven by a difference in the time high vs. time low pulse in the duty cycle, rather than the duty cycle all together. When the input signal is low, the motor spins full throttle in one direction, and when the signal is high, spins full throttle the opposite direction. When a 50% duty cycle is given as a signal, the difference of the time high vs. time low is zero, so there is no motor rotation (assuming the PWM is a fairly high frequency >20kHz). There are some downsides to using this circuit type for robotics. The main drawback is that even when the motor is not rotating, current is still being drawn through the motor, which may pose a problem when working with efficiency and battery life.
This section gives step-by-step instructions along with photos to build the PWM motor driver. A schematic to construct the locked anti-phase motor controller is shown below. This transistor motor driver will drive motors up to around 500mA current draw. Using these transistors is not recommended, but is used to show the concept by using LED's wired up in reverse polarity (a bi-color LED). for more information on the specific motor controller theory, refer to this web page: http://library.solarbotics.net/circuits/driver_4varHbridge.html. I enhanced the motor controller circuit a little to make it more robust to the PWM output from the Netburner.
NOTE!!! On the development board, I took and soldered in some female pin headers on each side of the MOD5213 chip. This allows me to easily hook up breadboarding wires to external circuitry for use on breadboards, etc. I will recommend this, either male (for wire wrapping) or female headers (for solid hookup wire), depending on your personal preference.
Once the breadboard is hooked up to the development board, check to make sure that the ADC works at reading the value from the potentiometer (you may have to look back to my tutorial on the ADC demo, on how to read from the ADC). Once this is good, and the breadboard circuit is double checked, the code can then be compiled to run on the MOD5213.
click here to see a short video of the working transistor motor controller driver. Note how the duty cycle changes when the potentiometer is moved in position.
#include "predef.h"
#include <stdio.h>
#include <ctype.h>
#include <basictypes.h>
#include <serialirq.h>
#include <system.h>
#include <constants.h>
#include <ucos.h>
#include <SerialUpdate.h>
#include <pins.h>
#include <..\MOD5213\system\sim5213.h>
#include <a2d.h>
#include <bsp.h>
#include <utils.h>
// Instruct the C/C++ Compiler not to mangle the function name
extern "C" {
void UserMain(void * pd);
}
// Name for the Development IDE to identify this application
const char * AppName="PWM_DevBoard";
// User Main - Main task
void UserMain(void * pd) {
SimpleUart(0,SystemBaud); // Start UART 0 at 115200 baud for chip communication
assign_stdio(0);
OSChangePrio(MAIN_PRIO); // Set te Priority of the UserMain loop to 50 (in the RTOS)
EnableSerialUpdate();
Pins[24].function( PIN24_PWM0 ); // Configure Pin 24 for PWM Channel 0 functionallity
iprintf("Pin Function Set.\n"); // Debug register set to Mttty Terminal
sim.pwm.pwme = 0; // Disable all PWM channels before making any settings
iprintf("PWM Channels Disabled.\n"); // Debug register set to Mttty Terminal
sim.pwm.pwmpol &= ~0x00; // Set to have an initial high signal, then set low on Duty cycle output compare
sim.pwm.pwmclk |= 0x01; // Set to use clock SA (Scale A)
sim.pwm.pwmprclk |= 0x07; // Set to use clock A prescale value of 2 (Internal Bus Clock/ 2^1)
iprintf("Pin Prescaler Set.\n"); // Debug register set to Mttty Terminal
sim.pwm.pwmcae &= ~0x01; // Set to operate channel 0 in left-aligned output mode
sim.pwm.pwmctl = 0; // All channels are 8-bit channels, doze and debug mode disabled
sim.pwm.pwmscla = 0x1A; // Use scale divisor value of 2 to generate clock SA from clock A
iprintf("PWM Scale Divisor Set.\n"); // Debug register set to Mttty Terminal
sim.pwm.pwmcnt[0] = 1; // Write any value to this register to reset the counter and start off clean
iprintf("Counter is reset.\n"); // Debug register set to Mttty Terminal
sim.pwm.pwmper[0] = 100; // Set PWM Chnnel Period register to a value
iprintf("PWM Period Set.\n"); // Debug register set to Mttty Terminal
sim.pwm.pwmdty[0] = 50; // Set PWM Channel Duty register to a value of 50
iprintf("PWM Duty Cycle Set.\n"); // Debug register set to Mttty Terminal
sim.pwm.pwme |= 0x01; // Enable PWM Output for PWM Channel 0
iprintf("PWM's are enabled.\n"); // Debug register set to Mttty Terminal
Pins[18].function( PIN18_AN4 );
iprintf("ADC Pins configured.\n");
EnableAD();
iprintf("ADC Enabled.\n");
iprintf("Application started\n"); // Debug register set to Mttty Terminal
while (1) {
int counts = ReadA2DResult( 4 ) >> 3;
float scale = (int)counts / (40.95);
printf( "AD= %d counts, AD Scale= %f\r\n", counts, scale);
sim.pwm.pwmdty[0] = scale; // Set PWM Channel Duty register to a value of 50
OSTimeDly( TICKS_PER_SECOND / 20 ); // The while loop keeps the processor running, since the PWM module
// is external to the processor.
}
}
The code for the motor controller operates as follows:
-The DSP first sets up all the parameters and registers for the ADC and PWM. After this, the DSP enables the A/D converter and reads the voltage at the ADC pin. The ADC counts are then mathematically scaled, and output to the duty cycle register of the PWM Module. The PWM Module then outputs the new calculated duty cycle on the preset pin.
Speculating future work, derived from this tutorial, includes an even more simple motor controller using the L298 chip. This includes two full H-Bridges on one chip, along with handling 4 amps per h-bridge, which is ideal for motor control applications. In the big picture, the problem of motor control through a DSP can be solved with this tutorial.
Click here to email me