⭐ 欢迎来到虫虫下载站! | 📦 资源下载 📁 资源专辑 ℹ️ 关于我们
⭐ 虫虫下载站

📄 复件 main.c

📁 基于ATMEGA48单片机的
💻 C
📖 第 1 页 / 共 2 页
字号:
// This file has been prepared for Doxygen automatic documentation generation.
/*! \file ********************************************************************
*
* Atmel Corporation
*
* - File              : main.c
* - Compiler          : IAR EWAAVR 2.28a/3.10c
*
* - Support mail      : avr@atmel.com
*
* - Supported devices : ATmega48/88/168
*
* - AppNote           : AVR444 - Sensorless control of three-phase brushless
*                       DC motors with ATmega48.
*
* - Description       : Example of how to use the ATmega48 for sensorless
*                       control of a three phase brushless DC motor.
*
* $Revision: 1.1 
* $Date: Monday, October 10, 2005 11:15:46 UTC 
*****************************************************************************/
/*
编译器:GCC
CPU:ATMEGA128
频率:4M
编译平台:VC++
程序流程:
主程序:
1. 端口初始化
   详见P9页
2. 定时器初始化
TC0:升序时,比较匹配发生时,OC0B清零,降序比较匹配发生时置位;相位修正PWM模式
    TOP值为OCR0A=200
TC1:8分频
3. ADC初始化
参考电压AREF;转换结果左对齐
定时器/计数器0溢出触发ADC自动转换
允许模拟比较器中断(上升沿)
4. 换相控制数据表格
5. 首次换相输出--共8次,然后打开TIMSK1的比较器A.
6. 全局中断开,进入循环
7.循环程序.

BMEF检测的思路:
**进入TC1的比较器A中断,换相并复位换相定时器,设定HOLD-OFF定时器,打开TC1 的比较器B中断;
打开TCO中断,关闭TC1中断,准备零点检测
**进入TC0溢出中断,取出ADC检测的电压值(周期中未通电相),根据上升或下降沿以及和标定值比较判断
是否为过零点.
如果是过零点,则对换相数据进行处理,更新TC1的OCR1A,之后关闭TC0,打开TC1,转入电流检测通道,打开ADC转换完成中断.
如果不是过零点,检测电流过后,恢复到BMEF电压检测状态,打开ADC转换完成中断.(等待下一次TC0中断)

*/
/*

疑问:
1.为何程序中多处出现清中断标志位命令:TIFRN.
2.看门狗的GCC中断程序怎么写
3.为了快速存取,在GCC中如何定义寄存器变量
IAR是这样定义的.
__regvar __no_init volatile unsigned int filteredTimeSinceCommutation @14;
4.感觉过零点检测失败应该恢复至定时器/计数器0溢出触发ADC自动转换
  */
#include "BLDC.h"

#include <avr/io.h>
#include <avr/signal.h>
#include <avr/interrupt.h>

//! Array of power stage enable signals for each commutation step.
//驱动功率管的信号组
unsigned char driveTable[6];

//! Array of ADC channel selections for each commutation step.
//ADC通道选择组
unsigned char ADMUXTable[6];

//! Array holding the inter commutation delays used during startup.
unsigned int startupDelays[STARTUP_NUM_COMMUTATIONS];//8 启动期间的变换次数

/*! \brief Filtered commutation timer variable and speed indicator.
 *  This value equals half the time of one commutation step. It is filtered
 *  through an IIR filter, so the value stored is not the most recent measuremnt.
 *  The variable is stored in registers R14-R15 for quicker access.
 */
//该变量数值为变换步阶时间的一半,是通过IIR得出的。所以储存的值不是最新测量的数值
//为了快速存取,将这个变量被放入R14,R15寄存器中
//__regvar __no_init volatile unsigned int filteredTimeSinceCommutation @14;
volatile unsigned int filteredTimeSinceCommutation;
/*! \brief The power stage enable signals that will be output to the motor drivers
 *  at next commutation.
 *
 *  This variable holds the pattern of enable signals that will be output to the
 *  power stage at next commutation. It is stored in register R13 for quick access.
 */
//该变量为下一时刻功率管的驱动信号
//为了快速存取,将这个变量被放入R13寄存器中
//__regvar __no_init volatile unsigned char nextDrivePattern @13;
volatile unsigned char nextDrivePattern;
/*! \brief Polarity of the expected zero crossing.
 *
 *  The polarity of the expected zero crossing.
 *  Could be eiter \ref EDGE_FALLING or \ref EDGE_RISING.
 */
//过零点的斜率(极性)
//为了快速存取,将这个变量被放入R12寄存器中
//__regvar __no_init volatile unsigned char zcPolarity @ 12;
volatile unsigned char zcPolarity;
/*! \brief The commutation step that starts at next commutation.
 *
 *  The commutation step that starts at next commutation. This is used to keep
 *  track on where in the commutation cycle we are. Stored in register R11 for
 *  quick access
 */
//下一个变换步阶,用于追踪现在所处的位置
//为了快速存取,将这个变量被放入R11寄存器中
//__regvar __no_init volatile unsigned char nextCommutationStep @11;
volatile unsigned char nextCommutationStep;
//! ADC reading of external analog speed reference.
//外部速度比较输入信号
volatile unsigned char speedReferenceADC;

//! ADC reading of shunt voltage.
//外部分压输入信号
volatile unsigned char shuntVoltageADC = 0;

//! ADC reading of the known external reference voltage.
//外部参考电压输入信号
volatile unsigned char referenceVoltageADC;

//! Flag that specifies whether a new external speed reference 
//! and a motor speed measurement is available.
//速度量测结束标志
volatile unsigned char speedUpdated = FALSE;

//! Flag that specifies whether a new current measurement is available.
// 电流量测结束标志
volatile unsigned char currentUpdated = FALSE;


/*! \brief Program entry point.
 *
 *  Main initializes all peripheral units used and calls the startup procedure.
 *  All commutation control from that point is done in interrupt routines.
 */
void main(void)
{
  // Initialize all sub-systems.
  //ResetHandler();
  InitPorts();
  InitTimers();
  InitADC();
  MakeTables();
  InitAnalogComparator();

  // Run startup procedure.
  StartMotor();

  // Turn on watchdog for stall-detection.
  //WatchdogTimerEnable();
  //__enable_interrupt();
  sei();
  for(;;)
  {
    PWMControl();
  }
}


/*! \brief Examines the reset source and acts accordingly.
 *
 *  This function is called early in the program to disable watchdog timer and
 *  determine the source of reset.
 *
 *  Actions can be taken, based on the reset source. When the watchdog is used as
 *  stall protection, a stall can be detected here. It is possible to e.g. store
 *  a variable in EEPROM that counts the number of failed restart attempts. After a
 *  certain number of attempts, the motor could simply refuse to continue until
 *  an external action happens, indicating that the rotor lock situation could be
 *  fixed.
 */
//将启动失败的尝试次数写入EEPROM,达到一定次数禁止启动,等待处理。
/*static void ResetHandler(void)
{
  __eeprom unsigned static int restartAttempts;
  // Temporary variable to avoid unnecessary reading of volatile register MCUSR.
  unsigned char tempMCUSR;

  tempMCUSR = MCUSR;
  MCUSR = tempMCUSR & ~((1 << WDRF) | (1 << BORF) | (1 << EXTRF) | (1 << PORF));

  // Reset watchdog to avoid false stall detection before the motor has started.
  __disable_interrupt();
  __watchdog_reset();
  WDTCSR |= (1 << WDCE) | (1 << WDE);
  WDTCSR = 0x00;

  // Examine the reset source and take action.
  switch (tempMCUSR & ((1 << WDRF) | (1 << BORF) | (1 << EXTRF) | (1 << PORF)))
  {
  case (1 << WDRF):
    restartAttempts++;
    if (restartAttempts >= MAX_RESTART_ATTEMPTS)
    {
      // Do something here. E.g. wait for a button to be pressed.
	//可在此输入处理 程序,比如按键解除。
      for (;;)
      {

      }
    }

    // Put watchdog reset handler here.
    break;
  case (1 << BORF):
    //Put brownout reset handler here.
    break;
  case (1 << EXTRF):
    restartAttempts = 0;
    // Put external reset handler here.
    break;
  case (1 << PORF):
    restartAttempts = 0;
    // Put power-on reset handler here.
    break;
  }
}
*/

/*! \brief Initializes I/O ports.
 *
 *  Initializes I/O ports.
 */

static void InitPorts(void)
{
  // Init DRIVE_DDR for motor driving.
  DRIVE_DDR = (1 << UL) | (1 << UH) | (1 << VL) | (1 << VH) | (1 << WL) | (1 << WH);
  //DDRB=0b00111111;
  // Init PORTD for PWM on PD5.
  DDRD = (1 << PD5);
  //DDRD=0b00100000;
  // Disable digital input buffers on ADC channels.
  //关闭ADC输入数字缓冲器
  DIDR0 = (1 << ADC4D) | (1 << ADC3D) | (1 << ADC2D) | (1 << ADC1D) | (1 << ADC0D);
  //DIDR0=0b00011111;
}


/*! \brief Initializes timers (for commutation timing and PWM).
 *
 *  This function initializes Timer/counter0 for PWM operation for motor speed control
 *  and Timer/counter1 for commutation timing.
 */
static void InitTimers(void)
{
  // Set up Timer/counter0 for PWM, output on OCR0B, OCR0A as TOP value, prescaler = 1.
  //比较匹配A不与OC0A连接
  //TCCROA=0x;//升序时,比较匹配发生时,OC0B清零,降序比较匹配发生时置位;相位修正PWM模式。
  TCCR0A = (0 << COM0A1) | (0 << COM0A0) | (1 << COM0B1) | (0 << COM0B0) | (0 << WGM01) | (1 << WGM00);
  TCCR0B = (1 << WGM02) | (0 << CS02) | (0 << CS01) | (1 << CS00);//CLK 无分频
  OCR0A = PWM_TOP_VALUE;//8m/20k/2=200 设置TOP值(TOP=OCR0A)
  TIFR0 = TIFR0;//意义何在?
  TIMSK0 = (0 << TOIE0);//TC0溢出中断禁止

  // Set up Timer/counter1 for commutation timing, prescaler = 8.
  TCCR1B = (1 << CS11) | (0 << CS10);//为何没有把CS12加进去?
}


/*! \brief Initializes the AD-converter.
 *
 *  This function initializes the AD-converter and makes a reading of the external
 *  reference voltage.
 */
static void InitADC(void)
{
  // First make a measurement of the external reference voltage.
  //参考电压AREF;转换结果左对齐;选取电源通道5
  ADMUX = ADMUX_REF_VOLTAGE;//  ((0 << REFS1) | (0 << REFS0))|(1<<ADLAR)|0X05;
  //ADC使能;ADC开始转换;读出电源电压                         
  ADCSRA = (1 << ADEN) | (1 << ADSC) | (1 << ADIF) | (ADC_PRESCALER_16);
  while (ADCSRA & (1 << ADSC))
  {

  }
  referenceVoltageADC = ADCH;//读入VCC电压值

  // Initialize the ADC for autotriggered operation on PWM timer overflow.
  //ADC使能|ADC开始转换禁止|自动触发使能|清中断标志|ADC中断禁止
  ADCSRA = (1 << ADEN) | (0 << ADSC) | (1 << ADATE) | (1 << ADIF) | (0 << ADIE) | ADC_PRESCALER_8;
  //定时器/计数器0溢出触发ADC转换
  ADCSRB = ADC_TRIGGER_SOURCE;
  
}


/*! \brief Initializes the analog comparator.
 *
 *  This function initializes the analog comparator for overcurrent detection.
 */
static void InitAnalogComparator(void)
{
#ifdef ANALOG_COMPARATOR_ENABLE
  // Enable analog comparator interrupt on rising edge.
  //允许模拟比较器中断(上升沿)
  ACSR = (0 << ACBG) | (1 << ACI) | (1 << ACIE) | (1 << ACIS1) | (1 << ACIS0);
#endif
}


/*! \brief Initializes the watchdog timer
 *
 *  This function initializes the watchdog timer for stall restart.
 */
/*static void WatchdogTimerEnable(void)
{
  __disable_interrupt();
  __watchdog_reset();

  WDTCSR |= (1 << WDCE) | (1 << WDE);

  WDTCSR = (1 << WDIF) | (1 << WDIE) | (1 << WDE) | (1 << WDP2);
  __enable_interrupt();
}
*/

/*! \brief Initializes arrays for motor driving and AD channel selection.
 *
 *  This function initializes the arrays used for motor driving and AD channel
 *  selection that changes for each commutation step.
 */
static void MakeTables(void)
{
#if DIRECTION_OF_ROTATION == CCW//如果定义了方向为CCW,则执行CCW程序。
  driveTable[0] = DRIVE_PATTERN_STEP1_CCW;//UY
  driveTable[1] = DRIVE_PATTERN_STEP2_CCW;//UW
  driveTable[2] = DRIVE_PATTERN_STEP3_CCW;//YW
  driveTable[3] = DRIVE_PATTERN_STEP4_CCW;//YU
  driveTable[4] = DRIVE_PATTERN_STEP5_CCW;//WY
  driveTable[5] = DRIVE_PATTERN_STEP6_CCW;//WY

  ADMUXTable[0] = ADMUX_W;
  ADMUXTable[1] = ADMUX_V;
  ADMUXTable[2] = ADMUX_U;
  ADMUXTable[3] = ADMUX_W;
  ADMUXTable[4] = ADMUX_V;
  ADMUXTable[5] = ADMUX_U;
#else
  driveTable[0] = DRIVE_PATTERN_STEP1_CW;
  driveTable[1] = DRIVE_PATTERN_STEP2_CW;
  driveTable[2] = DRIVE_PATTERN_STEP3_CW;
  driveTable[3] = DRIVE_PATTERN_STEP4_CW;
  driveTable[4] = DRIVE_PATTERN_STEP5_CW;
  driveTable[5] = DRIVE_PATTERN_STEP6_CW;

  ADMUXTable[0] = ADMUX_U;
  ADMUXTable[1] = ADMUX_V;
  ADMUXTable[2] = ADMUX_W;
  ADMUXTable[3] = ADMUX_U;
  ADMUXTable[4] = ADMUX_V;
  ADMUXTable[5] = ADMUX_W;

#endif

  startupDelays[0] = 200;//启动延时数组附值
  startupDelays[1] = 150;
  startupDelays[2] = 100;
  startupDelays[3] = 80;
  startupDelays[4] = 70;
  startupDelays[5] = 65;
  startupDelays[6] = 60;
  startupDelays[7] = 55;
}


/*! \brief Executes the motor startup sequence.
 *
 *  This function locks the motor into a known position and fires off a
 *  commutation sequence controlled by the Timer/counter1 overflow interrupt.
 */
static void StartMotor(void)
{
  unsigned char i;
  //OCR0B =130;TOP=OCR0A=200--在定时器初始化中定义
  SET_PWM_COMPARE_VALUE(STARTUP_PWM_COMPARE_VALUE);

  nextCommutationStep = 0;

  //Preposition.
  DRIVE_PORT = driveTable[nextCommutationStep];
  StartupDelay(STARTUP_LOCK_DELAY);//第一次变换持续时间
  nextCommutationStep++;
  nextDrivePattern = driveTable[nextCommutationStep];

  for (i = 0; i < STARTUP_NUM_COMMUTATIONS; i++)
  {
    DRIVE_PORT = nextDrivePattern;
    StartupDelay(startupDelays[i]);
    //参考电压VREF,左对齐,选取零点检测通道
    ADMUX = ADMUXTable[nextCommutationStep];

    // Use LSB of nextCommutationStep to determine zero crossing polarity.
    zcPolarity = nextCommutationStep & 0x01;//大概是判断零点斜率

    nextCommutationStep++;
    if (nextCommutationStep >= 6)
    {
      nextCommutationStep = 0;
    }
    nextDrivePattern = driveTable[nextCommutationStep];
  }

  // Switch to sensorless commutation.
  // 启动结束,进入无传感器模式正常运行
  TCNT1 = 0;
  //输出比较匹配A中断使能,行使换相功能,复位换相定时器,启动HOLD-OFF准备定时比较器
  TIMSK1 = (1 << OCIE1A);

  // Set filteredTimeSinceCommutation to the time to the next commutation.
  filteredTimeSinceCommutation = startupDelays[STARTUP_NUM_COMMUTATIONS - 1] * (STARTUP_DELAY_MULTIPLIER  / 2);
  //不清楚其含义
}


/*! \brief Timer/counter0 bottom overflow. Used for zero-cross detection.
 *
 *  This interrupt service routine is called every time the up/down counting
 *  PWM counter reaches bottom. An ADC reading on the active channel is
 *  automatically triggered at the same time as this interrupt is triggered.
 *  This is used to detect a zero crossing.
 *
 *  In the event of a zero crossing, the time since last commutation is stored
 *  and Timer/counter1 compare A is set up to trigger at the next commutation
 *  instant.
 */
//当PWM计数器归零时引起中断,同时触发AD转换,零点检测服务程序
SIGNAL(SIG_OVERFLOW1)
{
  unsigned char temp;

  // Disable ADC auto-triggering. This must be done here to avoid wrong channel being sampled on manual samples later.
  //ADC自动触发禁止;ADC中断禁止,开始手动转换
  ADCSRA &= ~((1 << ADATE) | (1 << ADIE));
  
  // Wait for auto-triggered ADC sample to complete.
  
  while (!(ADCSRA & (1 << ADIF)))
  {// 等待自动ADC采样结束
  
	  }
  temp = ADCH;
  if (((zcPolarity == EDGE_RISING) && (temp > ADC_ZC_THRESHOLD)) || ((zcPolarity == EDGE_FALLING) && (temp < ADC_ZC_THRESHOLD)))
  {//上升沿且检测点电压高于设定零点极限电压或处在下降沿且低于零点极限电压时
    unsigned int timeSinceCommutation;

⌨️ 快捷键说明

复制代码 Ctrl + C
搜索代码 Ctrl + F
全屏模式 F11
切换主题 Ctrl + Shift + D
显示快捷键 ?
增大字号 Ctrl + =
减小字号 Ctrl + -