Blog Entry




Building the I2C Smart DC Motor Controller with Atmel AVR Microcontroller – Part 1

June 12, 2013 by , under Microcontroller.




The idea of building my own I2C (read as I square C) smart DC motor controller is came to me when I was learning and playing together with my son on his LEGO® MINDSTORM® NXT 2.0 about a year ago. The NXT sophisticated controller also called NXT Intelligent Brick is powered by Atmel 32-bit ARM7 AT91SAM7S256 microcontroller and communicating with Atmel 8-bit AVR ATmega48 acting as a co-microcontroller using I2C protocol. This NXT co-microcontroller main function is to help handle some of the NXT I/O special task i.e. power management, reading buttons, analog’s input sensors and control to the motors. The following picture shows my version of the I2C smart DC motor controller which is power by Atmel 8-bit AVR ATmega168 microcontroller:

motor_cnt00

The advantage of separating this special I/O task to the co-microcontroller is to release the main microcontroller from the hungry resources task such as generating the required Pulse Width Modulation (PWM) to the motor and reading the analog input, therefore the main microcontroller could be used to do other important task. This I2C smart motor controller which has these following features:

  • Communicate with a standard I2C protocol to the any smart controller (e.g. microcontroller based board or microprocessor based board) that supports I2C protocol.
  • Driving two DC geared Motors simultaneously which maximum current up to 1 A, maximum voltage of 20 volts
  • Separate PWM for each motor for precision motor steering
  • Build in steering routine such e.g. forward/backward, turn left/right, rotate left/right, and arc left/right
  • Support unlimited, timed (in second), rotation (with wheel encoder), and degree (with wheel encoder) wheel movement
  • One channel precision 5 volt Servo Motor Driver
  • Two Interrupt input channel for wheel encoder
  • One 10-bit analog input channel
  • TTL UART communication, implemented for debugging purpose

I will split this project into 3 articles (part 1 to 3) and as we move to implement more complex features, the firmware will be slightly modified to support the additional features, and finally we will use a different type of master controller board to experiment with this I2C smart DC motor controller as shown in this following picture:

motor_cnt04

This I2C smart DC motor controller project also serve as a basic knowledge required to any microcontroller enthusiast or hobbyists to start their own embedded system application design. Ok let’s take a look at all the electronic components and software required to develop this project:

  1. Resistors: 10K Ohm (6), 330 Ohm (1), 1K Ohm (4)
  2. Capacitors: 0.1uF (7), 0.01uF (1), 22pF (2), 100uF/25v (1), 10uF/25v (1)
  3. Inductor: 100uH (1)
  4. Crystal: 16 MHz (1) used for external clock
  5. Diode: 1N5817 (1)
  6. LED: 3mm blue (4), 3 mm red (1)
  7. One 5 Volt Regulator IC LM7805
  8. One Atmel AVR ATmega168 Microcontroller
  9. One L293D Push Pull Four Channel Motor Driver
  10. One Tactical Switch
  11. One standard size Breadboard
  12. Adequate jumper cables for bread boarding
  13. One USB to UART converter for debugging
  14. Atmel AVR Studio 6.0 for coding and debugging environment
  15. Atmel AVR Programmer such as Atmel mkII programmer
  16. 5 Alkaline AA battery (7.5 volt) or two 18650 3.7volt Rechargeable Lithium battery (7.4 volt), or any adequate 7.5 volt regulated DC power source.
  17. Atmel AVR ATmega168 and L293D Datasheet
  18. The complete electronic schematic file (PDF) for this project

The following is a simplified version of the I2C smart DC motor controller electronic schematic used in this project:

motor_cnt02

The AVR ATmega168 as the I2C Slave

The I2C bus use only 2 bidirectional data lines called SDA (serial data) and SCL (serial clock) for communicating between the main microcontroller called “Master” and co-microcontroller called “Slave”. The I2C protocol specification can support up to 128 slave devices attached to the same bus which is one of its the main advantages.

motor_cnt01

The master I2C controller is responsible to initiate any communication between the I2C master device and the I2C slave device. Each of these I2C slave devices has their own 7-bit individual address which consists of fixed 4-bit device identification and configurable 3-bit physical address. These individual slave addresses allow the master controller to communicate to each of the slave devices attached to the I2C bus. You could read more about the I2C in these articles “How to use I2C-bus on the Atmel AVR Microcontroller” and “Transforming your AVR Microcontroller to the I2C (TWI) Slave I/O Expander Devices Project”.

In the first part, I will implement the AVR ATmega168 microcontroller as the I2C slave with a simple speed and steering motor controller. Therefore on top of I2C protocol I’ve used a simple data write and read rules (protocol), so the master controller could easily communicate with the I2C smart DC Motor controlling using this following I2C data communication format:

motor_cnt03

The I2C master controller first will send the “start” condition to the I2C bus; this will trigger the attention to the entire I2C slave devices attached to the same bus. Next the I2C master controller will send the particular I2C slave address with write instruction, in our case the I2C smart DC motor controller has the 4-bit fixed address of “1000” and configurable 3-bit address of “111”, therefore the I2C slave device will send the “acknowledge” to the I2C master controlled. Next the I2C master will send the first 8-bit data (i.e. register address) and the second 8-bit data (i.e. register data) before sending the “stop” condition.

By interpreting the appropriate register address and register data send by the I2C master controller, the I2C slave device could be programmed to response to any specific request needed as shown in this following picture:

motor_cnt05

The following is the first version of our firmware which implements these features written in AVR GCC language.

//***************************************************************************
//  File Name    : i2cmcont.c
//  Version      : 0.8
//  Description  : I2C Smart Motor Controller Firmware version 0.8
//  Author       : RWB
//  Target       : Atmel AVR ATmega168 Microcontroller
//  Compiler     : AVR_8_bit_GNU_Toolchain_3.4.0_663
//  IDE          : Atmel AVR Studio 6.0
//  Programmer   : Atmel AVRISP mkII 
//               : Atmel AVR Studio 6.0
//  Last Updated : 12 February 2013
//***************************************************************************
#define F_CPU 16000000UL   // Used 16MHz 

// I2C Motor Control Debugging Mode, 0-Debug Off, 1-Debug On
#define I2C_MCTL_DEBUG 0

#include <avr/io.h>
#include <util/delay.h>
#include <compat/twi.h>
#include <avr/interrupt.h>

#if I2C_MCTL_DEBUG 
#include <stdio.h>

#define BAUD_RATE 19200
#endif

// I2C Motor Address and Register Address
#define I2C_MCTL_ADDR 0x4E
#define I2C_MCTL_ID 0x40

// MCONTL - Motor Control Register Address
// BIT 2,1,0 - Steering: 000-Stop, 001-Forward, 010-Backward, 011-Break
//                       100-Turn Left, 101-Turn Right, 110-Rotate Left,
//                    111-Rotate Right
// BIT 4,3 - Duration: 00-Unlimited, 01-Reserve, 10-Reserve, 11-Reserve
// BIT 5-7 - Reverse
// 
#define MCONTL 0x00
volatile uint8_t motor_contl = 0x00; // Motor Control Data Register 

// MECONT - Extended Motor Control Register Address
// BIT 0-7 - Reserve
#define MECONT 0x01
volatile uint8_t motor_econt = 0x00; // Extended Motor Control Data Register 

#define MDURA 0x02
// BIT 0-7 - Reserve
volatile uint8_t motor_dur = 0x00;   // Motor Duration 8-Bit Data Register

#define MSTEER 0x03
// BIT 0-7 - Reserve
volatile uint8_t motor_steer = 0x00; // Motor Steer Data Register 

// MPOWER - Motor Power Register Address
// Value: 0 to 100
// This Register will automatically write to MPWMA and MPWMB registers
#define MPOWER 0x04
volatile uint8_t motor_pwr = 100;   // Motor A/B Power Data Register 

// MPWMA - Motor A PWM Register Address
// Value: 0 to 100
#define MPWMA 0x05
volatile uint8_t pwm_a = 100;       // Motor A PWM Data Register 

// MPWMB - Motor B PWM Register Address
// Value: 0 to 100
#define MPWMB 0x06
volatile uint8_t pwm_b = 100;       // Motor B PWM Data Register 

// Define The I2C Motor Differential Steering
#define FULL_STOP     0
#define MOVE_FORWARD  1
#define MOVE_BACKWARD 2
#define FULL_BREAK    3
#define TURN_LEFT     4
#define TURN_RIGHT    5
#define ROTATE_LEFT   6
#define ROTATE_RIGHT  7

// I2C Motor Controller Register variables
volatile uint8_t regaddr,regdata;  

// Motor PWM variables
volatile uint16_t pwm_top=4000;
volatile uint16_t pwm_duty=40;

#if I2C_MCTL_DEBUG 
// UART Functions
void uart_init(void)
{
  UBRR0H = (((F_CPU/BAUD_RATE)/16)-1)>>8;    // set baud rate
  UBRR0L = (((F_CPU/BAUD_RATE)/16)-1);
  UCSR0B = (1<<RXEN0)|(1<<TXEN0);         // enable Rx & Tx
  UCSR0C=  (1<<UCSZ01)|(1<<UCSZ00);              // config USART; 8N1
}

void uart_flush(void)
{
  unsigned char dummy;

  while (UCSR0A & (1<<RXC0)) dummy = UDR0;
}

int uart_putch(char ch,FILE *stream)
{    
   if (ch == '\n')
    uart_putch('\r', stream);

   while (!(UCSR0A & (1<<UDRE0)));
   UDR0=ch;

   return 0;
}

int uart_getch(FILE *stream)
{
   unsigned char ch;

   while (!(UCSR0A & (1<<RXC0)));
   ch=UDR0;  

   // Echo the Output Back to terminal 
   uart_putch(ch,stream);       

   return ch;
}
#endif

void MotorPWM(uint8_t msel)
{   
  if (msel == 0x00) {    
    OCR1A=pwm_top - (pwm_duty * pwm_a); // Set the Motor A Duty Cycle               
  } else {
    OCR1B=pwm_top - (pwm_duty * pwm_b); // Set the Motor B Duty Cycle                
  }
}

void MotorPower(void)
{  
  pwm_a=motor_pwr;
  MotorPWM(0);        // Set Motor A PWM
  pwm_b=motor_pwr;
  MotorPWM(1);        // Set Motor B PWM  
}

void MotorDirection(uint8_t msteer)
{  
#if I2C_MCTL_DEBUG  
  printf("Motor Direction: %d\n",msteer);  
#endif  
  switch(msteer) {
    case FULL_STOP:      
      PORTD &= ~(1 << PD4); PORTD &= ~(1 << PD5); // Motor A Stop 
      PORTD &= ~(1 << PD6); PORTD &= ~(1 << PD7); // Motor B Stop
      break;
    case MOVE_FORWARD:
      PORTD &= ~(1 << PD4); PORTD |= (1 << PD5);  // Motor A On Forward
      PORTD &= ~(1 << PD6); PORTD |= (1 << PD7);  // Motor B On Forward            
      break;
    case MOVE_BACKWARD:
      PORTD |= (1 << PD4); PORTD &= ~(1 << PD5);  // Motor A On Reverse
      PORTD |= (1 << PD6); PORTD &= ~(1 << PD7);  // Motor A On Reverse      
      break;
    case FULL_BREAK:      
      PORTD |= (1 << PD4); PORTD |= (1 << PD5);   // Motor A Break 
      PORTD |= (1 << PD6); PORTD |= (1 << PD7);   // Motor B Break
      break;    
    case TURN_LEFT:
      MotorPower();
      PORTD &= ~(1 << PD4); PORTD |= (1 << PD5);  // Motor A On Forward
      PORTD &= ~(1 << PD6); PORTD &= ~(1 << PD7); // Motor B Off      
      break;
    case TURN_RIGHT:
      MotorPower();
      PORTD &= ~(1 << PD4); PORTD &= ~(1 << PD5); // Motor A Off
      PORTD &= ~(1 << PD6); PORTD |= (1 << PD7);  // Motor B On Forward            
      break;    
    case ROTATE_LEFT:
      MotorPower();
      PORTD &= ~(1 << PD4); PORTD |= (1 << PD5);  // Motor A On Forward
      PORTD |= (1 << PD6); PORTD &= ~(1 << PD7);  // Motor B On Reverse      
      break;
    case ROTATE_RIGHT:
      MotorPower();
      PORTD |= (1 << PD4); PORTD &= ~(1 << PD5);  // Motor A On Reverse
      PORTD &= ~(1 << PD6); PORTD |= (1 << PD7);  // Motor B On Forward      
      break;   
  }  
}

void ControlAction(uint8_t rw_status)
{    
#if I2C_MCTL_DEBUG  
  printf("Register Address: %x\n",regaddr);
  printf("Register Data: %x\n",regdata);
#endif     
  // rw_status: 0-Read, 1-Write
  switch(regaddr) {      
    case MCONTL:                         
      if (rw_status) {
        motor_contl=regdata;  // Write to Motor Control Register                            

        // Set Motor Direction
        MotorDirection((motor_contl & 0x07));    
      } else {
        regdata=motor_contl;  // Read from Motor Control Register                 
      }                                 
      break;
    case MECONT:
      if (rw_status) {
        motor_econt=regdata;  // Write to Extended Motor Control Register 
      } else {
        regdata=motor_econt;  // Read from Extended Motor Control Register 
      }
      break;       
    case MDURA:
      if (rw_status) {
        motor_dur=regdata;    // Write to Motor Duration Register          
      } else {
        regdata=motor_dur;    // Read from Motor Duration Register  
      }
      break;    
    case MSTEER:                    
      if (rw_status) {
        motor_steer=regdata;  // Write to Motor Steering register        
      } else {
        regdata=motor_steer;  // Read from Motor Steering register
      }
      break;
    case MPOWER:                    
      if (rw_status) {
        motor_pwr=regdata;    // Write to Motor Power register
        if (motor_pwr > 100) motor_pwr = 100;
        MotorPower();         // Set Motor Power to Motor A and Motor B
      } else {
        regdata=motor_pwr;    // Read from Motor Power register
      }
      break;     
    case MPWMA:                         
      if (rw_status) {
        pwm_a=regdata;       // Write to PWMA register     
        if (pwm_a > 100) pwm_a = 100;
        MotorPWM(0);         // Set PWM On Motor A         
      } else {
        regdata=pwm_a;       // Read from PWMA register    
      }             
      break;
    case MPWMB:                         
      if (rw_status) {
        pwm_b=regdata;       // Write to PWMB register
        if (pwm_b > 100) pwm_b = 100;
        MotorPWM(1);         // Set PWM On Motor B
      } else {
        regdata=pwm_b;       // Read from PWMB register   
      }                          
      break;       
  } 
}

ISR(TWI_vect)
{     
   static uint8_t i2c_state;    
   // Disable Global Interrupt
   cli(); 

   // Get TWI Status Register, mask the prescaler bits (TWPS1,TWPS0)    
   switch(TWSR & 0xF8) {    
     case TW_SR_SLA_ACK:      // 0x60: SLA+W received, ACK returned                 
       i2c_state=0;           // Start I2C State for Register Address required     

       TWCR |= (1<<TWINT);    // Clear TWINT Flag      
       break;

     case TW_SR_DATA_ACK:     // 0x80: data received, ACK returned       
    if (i2c_state == 0) {                 
         regaddr = TWDR;      // Save data to the register address         
     i2c_state = 1;             
       } else {                          
     regdata = TWDR;      // Save to the register data             
     i2c_state = 2;            
       }

       TWCR |= (1<<TWINT);    // Clear TWINT Flag          
       break;

     case TW_SR_STOP:   // 0xA0: stop or repeated start condition received while selected            
       if (i2c_state == 2) {            
      ControlAction(1);    // Call Write I2C Action (rw_status = 1)          
      i2c_state = 0;    // Reset I2C State           
    }       

    TWCR |= (1<<TWINT);    // Clear TWINT Flag         
    break;

     case TW_ST_SLA_ACK:      // 0xA8: SLA+R received, ACK returned            
     case TW_ST_DATA_ACK:     // 0xB8: data transmitted, ACK received      
    if (i2c_state == 1) {          
      ControlAction(0);    // Call Read I2C Action (rw_status = 0)

     TWDR = regdata;      // Store data in TWDR register
     i2c_state = 0;    // Reset I2C State                     
       }             

       TWCR |= (1<<TWINT);     // Clear TWINT Flag
       break;       

     case TW_ST_DATA_NACK:    // 0xC0: data transmitted, NACK received       
     case TW_ST_LAST_DATA:      // 0xC8: last data byte transmitted, ACK received 
     case TW_BUS_ERROR:       // 0x00: illegal start or stop condition
     default:                           
    TWCR |= (1<<TWINT);    // Clear TWINT Flag       
    i2c_state = 0;         // Back to the Begining State       
   }   

   // Enable Global Interrupt
   sei();  
}

#if I2C_MCTL_DEBUG 
// Assign I/O stream to UART 
FILE uart_str = FDEV_SETUP_STREAM(uart_putch, uart_getch, _FDEV_SETUP_RW);
#endif

int main(void)
{        
  uint8_t i2c_address;   

  DDRB = 0xFF;      // Set PORTB as Output
  PORTB = 0x00;     // Reset PORTB Output
  DDRC = 0x00;      // Set PORTC as Input
  PORTC = 0x07;     // Activate Pul-up on PORTC: 0,1,3
  DDRD = 0xF0;      // Set PORTD: 0,1,2,3 as input and PORTD 4,5,6,7 as Output  
  PORTD = 0x0F;     // Set All PORTD 0,1,2,3 High and PORTD 4,5,6,7 to Low      

#if I2C_MCTL_DEBUG 
  // Define Output/Input Stream  
  stdout = stdin = &uart_str;      

  // Initial UART Peripheral 
  uart_init();           
#endif 

  // Motor PWM using TIMER1
  // Initial the 16-bit TIMER1 PWM, Phase and Frequency Correct
  // Set OC1A and OC1B when up counting, Clear OC1A and OC1B when down counting
  TCCR1A = (1<<COM1A1)|(1<<COM1A0)|(1<<COM1B1)|(1<<COM1B0);   

  // TCNT1 Counter Increment Freq: 1 / (Fclk/ (2 x 1 x pwm_top) 
  //                         Freq = 1 / (16000000/8000) = 2000 Hertz
  // PWM, Phase and Frequency Correct, pwm_top = ICR1 = 4000, Prescaler: 1
  TCCR1B = (1<<WGM13)|(1<<CS10);      

  // Set the TIMER1 PWM Top Value ICR1 and OCR1A/OCR1B  
  ICR1=pwm_top;  // Used default 2000 Hz  
  OCR1A=pwm_top - (pwm_duty * pwm_a); // Set the Motor A Duty Cycle                 
  OCR1B=pwm_top - (pwm_duty * pwm_b); // Set the Motor B Duty Cycle          

  // Now read the I2C Address from PC0, PC1, and PC2  
  i2c_address=I2C_MCTL_ID | ((PINC & 0x07) << 1);

  // Initial I2C Slave
  TWAR = i2c_address & 0xFE;   // Set I2C Address, Ignore I2C General Address 0x00   
  TWDR = 0x00;                 // Default Initial Value

  // Start Slave Listening: Clear TWINT Flag, Enable ACK, Enable TWI, TWI Interrupt Enable
  TWCR = (1<<TWINT) | (1<<TWEA) | (1<<TWEN) | (1<<TWIE);    

  // Enable Global Interrupt
  sei();    

  // Assigned Default I2C Motor Control Register Value  
  MotorPower();          // Set Motor Power to Motor A and Motor B     

  for(;;) {            
    _delay_us(50);      // Put 50 us delay here        
  }         
  return 0;
}              

// EOF: i2cmcont.c, version 0.8

The I2C configurable address is determined by the logical input status of PC0, PC1, and PC2 on PORTC witch if configured as input port, next these 3 bits value is combined with the device 4-bits fix ID value of “1000” (I2C_MCTL_ID) and be assigned to the Two Wire Interface Address Register (TWAR, Two Wire Interface is the name given by Atmel for the Philips I2C interface) as shown on this following C code:

// Now read the I2C Address from PC0, PC1, and PC2
i2c_address=I2C_MCTL_ID | ((PINC & 0x07) << 1);
// Initial I2C Slave
TWAR = i2c_address & 0xFE; // Set I2C Address, Ignore I2C General Address 0x00
TWDR = 0x00; // Default Initial Value

Next we enable the I2C acknowledgement of the device’s own slave address by setting the TWEA bit and TWSTA bit and TWSTO bit must be written to zero on TWCR (Two Wire Interface Control Register) and activate the interrupt as shown in this following C Code:

// Start Slave Listening: Clear TWINT Flag, Enable ACK, Enable TWI, TWI Interrupt Enable
TWCR = (1<<TWINT) | (1<<TWEA) | (1<<TWEN) | (1<<TWIE);
// Enable Global Interrupt
sei();

Now all the I2C master request to the I2C slave will be handled by interrupt in the ISR(TWI_vect) function where the request to the I2C slave and response from the I2C slave will be read or assigned to the TWDR (Two Wire Interface Data Register). Therefore by interpreting the “predetermined” data (protocols) send from the I2C master, the I2C slave device could easily be programmed to behave as instructed e.g. turn on the DC motor, steering the wheel, controlling the motor speed, etc as implemented in the ControlAction() function.

The Motor Steering and Power

The motor steering is controlled by the SGS L293D four channel motor drivers which capable of driving 600mA continue current on each channel. The L293D chip has equipped with a flying diode on each channel which simplified the overall electronic schematic design. By configuring two of the L293D channels as the H-Bridge circuit driver to each of the DC Motor, we could easily control the two DC motor rotation direction and speed as shown in this following picture.

motor_cnt06

The L293D chip IN1 to IN4 input terminal is connected to the AVR ATmega168P microcontroller PD4 to PD7 output port, while the L293D four channel ENABLE1 and ENABLE2 input are connected to the AVR ATmega168P microcontroller 16-bit TIMER2 PWM output channel OC1A and OC1B.

motor_cnt07

The DC motor differential steering is controlled by applying the correct output logic (see the L293D truth table above) to the PD4 to PD7 output on PORTD which is implemented in the MotorDirection() function.

By supplying the PWM (Pulse Width Modulation) signal on each of the L293D chip ENABLE input we could control the power on each DC Motor. The AVR ATmega168 microcontroller 16-bit TIMER1 is choosed as the DC motor PWM source and is configured as the Phase and Frequency Correct PWM mode, we choose this mode as later on we will implement a flexible configurable PWM frequency in the I2C smart DC motor Controller firmware. You could read more about AVR PWM in these articles “Introduction to AVR Microcontroller Pulse Width Modulation (PWM)”, “AVR Twinkle Twinkle Using PWM Project” and “Working with Atmel AVR Microcontroller Basic Pulse Width Modulation (PWM) Peripheral”.

The TIMER1 Phase and Frequency Correct PWM mode used a dual slope counter operation in order to generate the PWM signal. First the 16-bit TIMER1 counter TCNT1 will count up, when the TCNT1 reach the OCR1A or OCR1B (Output Compare Register) value then the TIMER1 pheripheral will set the OC1A or OC1B output to a logical one. When the TCNT1 reach its maximum value (TOP) set in ICR1 (Input Capture Register) value, then the TCNT1 will start to count down, when it reach the OCR1A or OCR1B value the TIMER1 pheripheral will reset the OC1A or OC1B output to a logical zero as shown in this following picture.

motor_cnt08

The TIMER1 Phase and Frequency Correct PWM mode is initialized in this following C code:

// Motor PWM using TIMER1
// Initial the 16-bit TIMER1 PWM, Phase and Frequency Correct
// Set OC1A and OC1B when up counting, Clear OC1A and OC1B when down counting
TCCR1A = (1<<COM1A1)|(1<<COM1A0)|(1<<COM1B1)|(1<<COM1B0);   

// TCNT1 Counter Increment Freq: 1 / (Fclk/ (2 x 1 x pwm_top) 
//                         Freq = 1 / (16000000/8000) = 2000 Hertz
// PWM, Phase and Frequency Correct, pwm_top = ICR1 = 4000, Prescaler: 1
TCCR1B = (1<<WGM13)|(1<<CS10);      

// Set the TIMER1 PWM Top Value ICR1 and OCR1A/OCR1B  
ICR1=pwm_top;  // Used default 2000 Hz  
OCR1A=pwm_top - (pwm_duty * pwm_a); // Set the Motor A Duty Cycle                 
OCR1B=pwm_top - (pwm_duty * pwm_b); // Set the Motor B Duty Cycle

The PWM frequency is controled by the TCNT1 maximum counter value or ICR1 register value and could be calculated using this following formula:

PWM Frequency = Freq Clock / (2 x n x TOP)

With the frequency clock of 16.000.000 Hz, prescaler (n) of 1 and TOP value of 4000 (pwm_top variable), the PWM frequency is 2000 Hz.

The PWM duty cycle is controlled by the OCR1A and OCR1B register value. Therefore by changing the OCR1A and OCR1B value we could easily change each of the DC motor speed connected to AVR ATmega168 microcontroller OC1A (PB1) and OC1B (PB2) output port. The duty cycle could be calculated using this following formula:

OCR1A = pwm_top – (pwm_duty x pwm_a)
OCR1B = pwm_top – (pwm_duty x pwm_b)

Where pwm_top and pwm_duty variables are fixed value of 4000 and 40, while the pwm_a or pwm_b variable value represent the PWM output duty cycle from 0 to 100, therefore by setting the pwm_a or pwm_b to 100 the OCR1A or OCR1B value is 0 (100% PWM duty cycle) or when pwm_a or pwm_b is set to 0 the OCR1A or OCR1B value is 4000 (0% PWM duty cycle). The DC Motor speed control is implemented in MotorPower() and MotorPWM() functions.

motor_cnt09

One of the important feature implemented in this project is the runtime debugging which is implemented using the Atmel AVR ATmega168 microcontroller UART peripheral. This runtime debugging will help us to capture and examine program variables value on the terminal such as window Hyperterminal or PuTTY program (i.e. baud rate: 19200, data bit: 8, and stop bit: 1) while we run the code. In order to enable this debugging feature you could simply change the I2C_MCTL_DEBUG definition from 0 to 1 and connect the AVR UART port RXD (PD0) and TXD (PD1) to the UART to USB or UART to RS232 adapter to your personal computer.

Testing the I2C Smart DC Motor Controller Firmware

In order to test the first version of the I2C Smart DC Motor Controller firmware, I will use the Atmel AVR ATmega328P microcontroller with the AVRJazz 28PIN board. Where we simply connect the AVR ATmega328P TWI (two wire inteface) port SDA (PC4) and SCL (PC5) to the SDA and SCL port of the I2C Smart DC Motor Controler. The following is a complete C code where the AVR ATmega328P microcontroller is configured as the I2C master controller.

//***************************************************************************
//  File Name    : i2cmdemo.c
//  Version      : 0.8
//  Description  : I2C Master Demo for I2C DC Motor Smart Controller
//  Author       : RWB
//  Target       : AVRJazz28PIN Board
//  Compiler     : AVR_8_bit_GNU_Toolchain_3.4.0_663
//  IDE          : Atmel AVR Studio 6.0
//  Programmer   : AVRJazz28PIN STK500 v2.0 Bootloader
//               : Atmel AVR Studio 6.0, STK500 programmer
//  Last Updated : 12 February 2013
//***************************************************************************
#define F_CPU 16000000UL    // AVRJazz28PIN Board Used 16MHz

// Demo I2C Motor Control Debugging Mode, 0-Debug Off, 1-Debug On
#define I2C_MCTL_DEBUG 0

#include <avr/io.h>
#include <avr/io.h>
#include <util/delay.h>
#include <compat/twi.h>

#if I2C_MCTL_DEBUG 
#include <stdio.h>

#define BAUD_RATE 19200
#endif

#define MAX_TRIES 50

#define I2CMCTL_ID    0x40  // I2CMCTL Device Identifier
#define I2CMCTL_ADDR  0x0E  // I2CMCTL Device Address (0x07 << 1)
#define MCONTL 0x00         // MCONTL - Motor Control Register Address
#define MECONT 0x01         // MECONT - Extended Motor Control Register Address
#define MDURA 0x02          // MDURA  - Motor Duration (0-255)
#define MSTEER 0x03         // MSTEER - Motor Steering Register Address (0-200)
#define MPOWER 0x04         // MPOWER - Motor Power Register Address (0-100)
#define MPWMA 0x05          // MPWMA  - Motor A PWM Register Address (0-100)
#define MPWMB 0x06          // MPWMB  - Motor B PWM Register Address (0-100)

#define I2C_START 0
#define I2C_DATA 1
#define I2C_DATA_ACK 2
#define I2C_STOP 3
#define ACK 1
#define NACK 0

#define DATASIZE 32

#if I2C_MCTL_DEBUG 
// UART Functions
void uart_init(void)
{
  UBRR0H = (((F_CPU/BAUD_RATE)/16)-1)>>8;    // set baud rate
  UBRR0L = (((F_CPU/BAUD_RATE)/16)-1);
  UCSR0B = (1<<RXEN0)|(1<<TXEN0);         // enable Rx & Tx
  UCSR0C=  (1<<UCSZ01)|(1<<UCSZ00);              // config USART; 8N1
}

void uart_flush(void)
{
  unsigned char dummy;

  while (UCSR0A & (1<<RXC0)) dummy = UDR0;
}

int uart_putch(char ch,FILE *stream)
{    
   if (ch == '\n')
    uart_putch('\r', stream);

   while (!(UCSR0A & (1<<UDRE0)));
   UDR0=ch;

   return 0;
}

int uart_getch(FILE *stream)
{
   unsigned char ch;

   while (!(UCSR0A & (1<<RXC0)));
   ch=UDR0;  

   // Echo the Output Back to terminal 
   uart_putch(ch,stream);       

   return ch;
}
#endif

// START I2C Routine 
unsigned char i2c_transmit(unsigned char type) { 
  switch(type) {
     case I2C_START:    // Send Start Condition       
       TWCR = (1 << TWINT) | (1 << TWSTA) | (1 << TWEN);
       break;
     case I2C_DATA:     // Send Data with No-Acknowledge
       TWCR = (1 << TWINT) | (1 << TWEN);       
       break;
     case I2C_DATA_ACK: // Send Data with Acknowledge
       TWCR = (1 << TWEA) | (1 << TWINT) | (1 << TWEN);
       break;
     case I2C_STOP:     // Send Stop Condition
       TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO);
       return 0;       
  }

  // Wait for TWINT flag set on Register TWCR
  while (!(TWCR & (1 << TWINT)));

  // Return TWI Status Register, mask the prescaler bits (TWPS1,TWPS0)
  return (TWSR & 0xF8);      
}

char i2c_start(unsigned int dev_id, unsigned int dev_addr, unsigned char rw_type)
{
  unsigned char n = 0; 
  unsigned char twi_status; 
  char r_val = -1;             

i2c_retry:
  if (n++ >= MAX_TRIES) return r_val;

  // Transmit Start Condition    
  twi_status=i2c_transmit(I2C_START);

  // Check the TWI Status
  if (twi_status == TW_MT_ARB_LOST) goto i2c_retry;
  if ((twi_status != TW_START) && (twi_status != TW_REP_START)) goto i2c_quit;

  // Send slave address (SLA_W) 
  TWDR = (dev_id & 0xF0) | (dev_addr & 0x0E) | rw_type;

  // Transmit I2C Data
  twi_status=i2c_transmit(I2C_DATA);      

  // Check the TWSR status
  if ((twi_status == TW_MT_SLA_NACK) || (twi_status == TW_MT_ARB_LOST)) goto i2c_retry;  
  if (twi_status != TW_MT_SLA_ACK) goto i2c_quit;

  r_val=0;

i2c_quit:
  return r_val;
}

void i2c_stop(void)
{
  unsigned char twi_status; 

  // Transmit I2C Data
  twi_status=i2c_transmit(I2C_STOP);   
}

char i2c_write(char data) 
{
  unsigned char twi_status; 
  char r_val = -1;             

  // Send the Data to I2C Bus 
  TWDR = data;

  // Transmit I2C Data
  twi_status=i2c_transmit(I2C_DATA);      

  // Check the TWSR status
  if (twi_status != TW_MT_DATA_ACK) goto i2c_quit;

  r_val=0;

i2c_quit:  
  return r_val;  
}

char i2c_read(char *data,char ack_type) 
{
  unsigned char twi_status; 
  char r_val = -1;               

  if (ack_type) {     
    // Read I2C Data and Send Acknowledge
    twi_status=i2c_transmit(I2C_DATA_ACK);

    if (twi_status != TW_MR_DATA_ACK) goto i2c_quit;
  } else {
    // Read I2C Data and Send No Acknowledge
    twi_status=i2c_transmit(I2C_DATA);

    if (twi_status != TW_MR_DATA_NACK) goto i2c_quit;
  }

  // Get the Data
  *data=TWDR;
  r_val=0;

i2c_quit:
  return r_val;
}

// END I2C Routine 

void Write_I2CMCTL(unsigned char reg_addr,unsigned char data)
{   
   // Start the I2C Write Transmission
   i2c_start(I2CMCTL_ID,I2CMCTL_ADDR,TW_WRITE);

   // Sending the Register Address
   i2c_write(reg_addr);

   // Write data to I2CMCTL Register
   i2c_write(data);

   // Stop I2C Transmission
   i2c_stop();  
}

unsigned char Read_I2CMCTL(unsigned char reg_addr)
{
   char data;

   // Start the I2C Write Transmission
   i2c_start(I2CMCTL_ID,I2CMCTL_ADDR,TW_WRITE);

   // Read data from I2CMCTL Register Address
   i2c_write(reg_addr);

   // Stop I2C Transmission
   i2c_stop();

   // Re-Start the I2C Read Transmission
   i2c_start(I2CMCTL_ID,I2CMCTL_ADDR,TW_READ);

   i2c_read(&data,NACK);

   // Stop I2C Transmission
   i2c_stop();

   return data;
}

void i2c_init(void)
{ 
  // Initial ATMega328P TWI/I2C Peripheral 
  TWSR = 0x00;         // Select Prescaler of 1

  // SCL frequency = 16000000 / (16 + 2 * 72 * 1) ~ 100 kHz
  TWBR = 72;        
}

#if I2C_MCTL_DEBUG 
// Assign I/O stream to UART 
FILE uart_str = FDEV_SETUP_STREAM(uart_putch, uart_getch, _FDEV_SETUP_RW);
#endif

int main(void)
{  
  unsigned char demo_type;

  DDRD=0xFF;          // Set PORTD as Output
  PORTD=0x00;         // Set All PORTD to Low 

#if I2C_MCTL_DEBUG   
  // Define Output/Input Stream  
  stdout = stdin = &uart_str;      

  // Initial UART Peripheral 
  uart_init();  
#endif    

  // Initial Master I2C 
  i2c_init();    
  Write_I2CMCTL(MCONTL,0b00000000);       // Full Stop  

  // Loop Forever    
  demo_type = 0; 
  for (;;) {    
    switch(demo_type) {
      case 0:         // Forward 100% Duty Cycle
        Write_I2CMCTL(MPOWER,100);     
        Write_I2CMCTL(MCONTL,0b00000001);       
        break;
      case 1:         // Backward 80% Duty Cycle
        Write_I2CMCTL(MPOWER,80);     
        Write_I2CMCTL(MCONTL,0b00000010);       
        break;
      case 2:         // Turn Left 70% Duty Cycle
        Write_I2CMCTL(MPOWER,70);     
        Write_I2CMCTL(MCONTL,0b00000100);       
        break;
      case 3:         // Turn Right 70% Duty Cycle
        Write_I2CMCTL(MPOWER,70);     
        Write_I2CMCTL(MCONTL,0b00000101);       
        break;
      case 4:         // Rotate Left 60% Duty Cycle
        Write_I2CMCTL(MPOWER,60);     
        Write_I2CMCTL(MCONTL,0b00000110);       
        break;
      case 5:         // Rotate Right 80% Duty Cycle
        Write_I2CMCTL(MPOWER,80);     
        Write_I2CMCTL(MCONTL,0b00000111);       
        break;
    }

    // Delay 800 ms
    _delay_ms(800);

    Write_I2CMCTL(MCONTL,0b00000011);    // Full Break 500 ms
    _delay_ms(500);        

    // Continue to the next demo
    if (demo_type++ > 5) demo_type=0;    
  } 

  return 0;
}

/* EOF: i2cmdemo.c */

The program start by initializing the AVR ATmega328P microcontroller TWI peripheral in master mode by calling the I2C_init() function where we use prescaler of 1 and assign the TWBR (Two Wire Bit Rate Register) to 72 to activate the I2C master clock at approximately 100 kHz as shown in this following C code:

// Initial ATMega328P TWI/I2C Peripheral
TWSR = 0x00; // Select Prescaler of 1
// SCL frequency = 16000000 / (16 + 2 * 72 * 1) ~ 100 kHz
TWBR = 72;

Next after activate the AVR ATmega328P microcontroller in I2C master mode, then we are ready to communicate with the I2C slave device. The following are all the I2C master communication functions used in this project:

  • i2c_transmit() – This function do the actual data transmission from the I2C master device
  • i2c_start() – Mark the start condition of the I2C communication
  • i2c_stop() – Mark the stop condition of the I2C communication
  • i2c_write() – Write data to the I2C slave device
  • i2c_read() – Read data from the I2C slave device

The Write_I2CMCTL() and Read_I2CMCTL() are the I2C encapsulate functions where we send commands to the I2C slave device and read data returned by the I2C slave device. For example to instruct the I2C Smart DC Motor to rotate left using 65% of its power we simply used these following C code command:

Write_I2CMCTL(MPOWER,65);
Write_I2CMCTL(MCONTL,0b00000110);

The first command we assigned the MPOWER (0x04) register in the I2C Smart DC Motor Control to 65. This command will be interpreted by the I2C Smart DC Motor Control firmware as to generate 65% duty cycle for both the DC motors. The second command we assigned the MCONTL (0x00) register in the I2C Smart DC Motor Control to 0b00000110 (0x05). This command will be interpreted by the I2C Smart DC Motor Control firmware as to rotate left (i.e. steering function). You could use similar principle to other commands as shown on the demo C code above.

Now you could enjoy the following video that showing how this I2C Smart DC Motor Controller in action:

The Final Though

Using the I2C protocol is one of the embedded system solutions to use a multi-microcontroller to solve a complex embedded system tasks. In this project we’ve learned to separate the DC motor control tasks in the Atmel AVR ATmega168 microcontroller and use its sister the Atmel AVR ATmega328P microcontroller as the main controller. In the part 2 of the project, I will add more features to the I2C Smart DC Motor Controller firmware and use different microcontroller type as the I2C master controller.

 

 

Bookmarks and Share


bookmark bookmark bookmark bookmark bookmark bookmark bookmark bookmark bookmark bookmark




One Response to “Building the I2C Smart DC Motor Controller with Atmel AVR Microcontroller – Part 1”

28.08.13#1

Comment by klyx.

Nice !!!
Can’t wait for next part 😉