【ST学习小组】STM32F103的CAN 通信之主控器

来源:互联网 发布:淘宝联盟推广位 编辑:程序博客网 时间:2024/05/15 01:12

原帖地址:http://www.eefocus.com/bbs/article_244_380394.html



本CAN主要实现两个芯片的通讯,主控器通过CAN将获得的从控制发来的数据,通过串口显示在上位机上,在上位机上实时得到一个数据曲线。从控制器通过AD获得数据。

 

以下是主控制器的代码程序:

本主程序主要分为三个,main.c   led.c   usart.c  can.c   

 

main.c

#include "stm32f10x.h" 

#include "misc.h"

#include "led.h"

#include "key.h"

#include "usart.h"

//#include "exti.h"

#include "can.h"

 

void RCC_Configuration(void);  

void Delay(__IO uint32_t nCount);

 

//___________________Global Variable declare________

u8 CAN_TransmitDataBuf[8];

u8 ADC_num=0;

u16 ADC_Data0[10];

u16 ADC_Data1[10];

u16 ADC_Data2[10];

u16 ADC_Data3[10];

 

//______________________________________________

 

 

//___________________________ADC modue__________

 

void  Adc_Init(void)

{    

//先初始化IO口

  RCC->APB2ENR|=1<<2;    //使能PORTA口时钟 

GPIOA->CRL&=0XFFFF0000;//PA0 1 2 3 anolog输入

//通道10/11设置  

RCC->APB2ENR|=1<<9;    //ADC1时钟使能  

RCC->APB2RSTR|=1<<9;   //ADC1复位

RCC->APB2RSTR&=~(1<<9);//复位结束    

RCC->CFGR&=~(3<<14);   //分频因子清零

//SYSCLK/DIV2=12M ADC时钟设置为12M,ADC最大时钟不能超过14M!

//否则将导致ADC准确度下降! 

RCC->CFGR|=2<<14;       

 

ADC1->CR1&=0XF0FFFF;   //工作模式清零

ADC1->CR1|=0<<16;      //独立工作模式  

ADC1->CR1&=~(1<<8);    //非扫描模式  

ADC1->CR2&=~(1<<1);    //单次转换模式

ADC1->CR2&=~(7<<17);   

ADC1->CR2|=7<<17;   //软件控制转换  

ADC1->CR2|=1<<20;      //使用用外部触发(SWSTART)!!!必须使用一个事件来触发

ADC1->CR2&=~(1<<11);   //右对齐 

ADC1->SQR1&=~(0XF<<20);

ADC1->SQR1&=0<<20;   

//设置通道0~3的采样时间

ADC1->SMPR2&=0XFFFFF000;//通道0,1,2,3采样时间清空  

ADC1->SMPR2|=7<<9;      //通道3  239.5周期,提高采样时间可以提高精确度 

ADC1->SMPR2|=7<<6;      //通道2  239.5周期,提高采样时间可以提高精确度 

ADC1->SMPR2|=7<<3;      //通道1  239.5周期,提高采样时间可以提高精确度 

ADC1->SMPR2|=7<<0;      //通道0  239.5周期,提高采样时间可以提高精确度 

 

ADC1->CR2|=1<<0;    //开启AD转换器 

ADC1->CR2|=1<<3;        //使能复位校准  

while(ADC1->CR2&1<<3);  //等待校准结束  

    //该位由软件设置并由硬件清除。在校准寄存器被初始化后该位将被清除。   

ADC1->CR2|=1<<2;        //开启AD校准   

while(ADC1->CR2&1<<2);  //等待校准结束

//该位由软件设置以开始校准,并在校准结束时由硬件清除  

}   

//获得ADC值

//ch:通道值 0~3

u16 Get_Adc(u8 ch)   

{

//设置转换序列     

ADC1->SQR3&=0XFFFFFFE0;//规则序列1 通道ch

ADC1->SQR3|=ch;      

ADC1->CR2|=1<<22;       //启动规则转换通道 

while(!(ADC1->SR&1<<1));//等待转换结束    

return ADC1->DR;//返回adc值

}

 

 

 

 

 

 

//_________________________________________________

 

 

 

 

//_____________________ADC 采样值发送________

void ADC_TransmitByCan(u16 Data_CH1,u16 Data_CH2,u16 Data_CH3)

{

}

 

 

//////////////////////////////////////////////////////////////////////////////////   

//int i=0; 

 

//定时器3中断服务程序  

void TIM3_IRQHandler(void)

       

      u8 index=0;

  u16 Max=0;

  u16 Min=0xFF;

  u32 ADC0_sum=0;

if(TIM3->SR&0X0001)//溢出中断

{

   

  // ADC_Data1[1]=Get_Adc(ADC_Channel_1);

 //  ADC_Data2[2]=Get_Adc(ADC_Channel_2);

                  

               ADC_Data0[ADC_num]=Get_Adc(ADC_Channel_0);

               ADC_num++;

  if (ADC_num>=9)

   {    

        ADC_num=0;

   for(index=0;index<9;index++)

   {

   if(ADC_Data0[index]>Max)

   {

   Max=ADC_Data0[index];

   }

if(ADC_Data0[index]<Min)

{

Min=ADC_Data0[index];

}

ADC0_sum+=(u32) (ADC_Data0[index]);

   }

ADC0_sum=(ADC0_sum-Max-Min)/8;

CAN_TransmitDataBuf[1]=(ADC0_sum&0x00ff);

 CAN_TransmitDataBuf[0]=((ADC0_sum>>8)&0x00ff);

  

CAN_TransmitData(2,CAN_TransmitDataBuf,0xAAAA);

   }

                   

}    

TIM3->SR&=~(1<<0);//清除中断标志位   

}

//通用定时器中断初始化

//这里时钟选择为APB1的2倍,而APB1为36M

//arr:自动重装值。

//psc:时钟预分频数

//这里使用的是定时器3!

 

void Timer_init(u16 arr,u16 psc)

{

 

NVIC_InitTypeDef NVIC_InitStructure;

RCC->APB1ENR|=1<<1;//TIM3时钟使能    

  TIM3->ARR=arr;  //设定计数器自动重装值//刚好1ms    

TIM3->PSC=psc;  //预分频器7200,得到10Khz的计数时钟

//这两个东东要同时设置才可以使用中断

TIM3->DIER|=1<<0;   //允许更新中断

TIM3->DIER|=1<<6;   //允许触发中断   

TIM3->CR1|=0x01;    //使能定时器3 

 

  /* Configure the NVIC Preemption Priority Bits */  

  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);    

  

  /* Enable the USART1 Interrupt */

  NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn;       //设置串口中断

  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;

  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;

  NVIC_Init(&NVIC_InitStructure);

}

 

//_______________________________________________

int main(void)

{  

  RCC_Configuration();  //系统时钟配置 

  LED_GPIO_Config();    //led配置

  KEY_GPIO_Config();    //按键配置

  USART_Init_Config();  //串口配置

//  EXTI_Init_Config();

//  Adc_Init();

  CAN_Init_Config();

//Timer_init(50,6400);

  while (1)

  {

LED1_ON;

LED2_ON;

Delay(0xFFFFF);

  Delay(0xFFFFF);

 

  }

}

void RCC_Configuration(void)

{   

  /* Setup the microcontroller system. Initialize the Embedded Flash Interface,  

     initialize the PLL and update the SystemFrequency variable. */

  SystemInit();  

  RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO|RCC_APB2Periph_GPIOB,ENABLE);   //打开重映射时钟

  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); /* GPIOA clock enable */

//RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); /* GPIOB clock enable */

  RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE);   /* CAN Periph clock enable */

}

 

 

void Delay(__IO uint32_t nCount)

{

   for(; nCount != 0; nCount--);

}

 

#ifdef  USE_FULL_ASSERT

/**

  * @brief  Reports the name of the source file and the source line number

  *   where the assert_param error has occurred.

  * @param file: pointer to the source file name

  * @param line: assert_param error line source number

  * @retval : None

  */

 

 

 

void assert_failed(uint8_t* file, uint32_t line)

  /* User can add his own implementation to report the file name and line number,

     ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */

 

  /* Infinite loop */

  while (1)

  {

  }

}

#endif

-------------------------------------------------------------------------------------------------------------------------------

 usart.c

 

 

#include "usart.h"

 

USART_InitTypeDef USART_InitStruct;

USART_ClockInitTypeDef USART_ClockInitStruct;

 

void USART1_GPIO_Config(void)

{

  GPIO_InitTypeDef GPIO_InitStructure;

 

  RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1|RCC_APB2Periph_GPIOA  , ENABLE);

//USART1 TX

  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;          

  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;    //复用推挽输出

  GPIO_Init(GPIOA, &GPIO_InitStructure);     //A端口 

   //USART1 RX

  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;          

  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;   //复用开漏输入

  GPIO_Init(GPIOA, &GPIO_InitStructure);  

  

}

 

void USART1_NVIC_Configuration(void)

{

  NVIC_InitTypeDef NVIC_InitStructure;

 

  /* Configure the NVIC Preemption Priority Bits */  

  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);    

  

  /* Enable the USART1 Interrupt */

  NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;     //设置串口中断

  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;

  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;

  NVIC_Init(&NVIC_InitStructure);

}

void USART_Config(USART_TypeDef* USARTx)

{

  USART_InitTypeDef USART_InitStructure; 

  USART_InitStructure.USART_BaudRate = 115200; //速率115200bps

  USART_InitStructure.USART_WordLength = USART_WordLength_8b;//数据位8位

  USART_InitStructure.USART_StopBits = USART_StopBits_1;//停止位1位

  USART_InitStructure.USART_Parity = USART_Parity_No;//无校验位

  USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;   //无硬件流控

  USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;//收发模式

 

  /* Configure USART1 */

  USART_Init(USARTx, &USART_InitStructure); //配置串口参数函数

 

  

  /* Enable USART1 Receive and Transmit interrupts */

 USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);                    //使能接收中断

  //USART_ITConfig(USART1, USART_IT_TXE, ENABLE); //使能发送缓冲空中断

  //USART_ITConfig(USART1, USART_IT_TC, ENABLE); //使能发送完成中断 

  /* Enable the USART1 */

  USART_Cmd(USART1, ENABLE);

}

 

void USART_Init_Config(void)

{

  USART1_GPIO_Config();  //端口配置

  USART_Config(USART1);  //数据格式配置

  USART1_NVIC_Configuration();  //中断配置

}

void Usart_transmitByte(uint8_t Usart_TransmitDatebuf)

{

USART1->DR=Usart_TransmitDatebuf;

while((USART1->SR&0X40)==0);//wait 

}

 

void Usart_TransmitData(u16 Usart_TransmitDataLength,uint8_t * Usart_TransmitDatebuf)

{

u16 Usart_Transmitindex;

 //_____________________send the start byte_______________________

  Usart_transmitByte(0xFF);

  Usart_transmitByte(0x00);

// _____________________send the end byte________________________

for(Usart_Transmitindex=0;Usart_Transmitindex<Usart_TransmitDataLength;Usart_Transmitindex++)

{

if(Usart_TransmitDatebuf[Usart_Transmitindex]==0xFF)

{

if(Usart_TransmitDatebuf[Usart_Transmitindex+1]==0x00)

{

Usart_transmitByte(0xFF);

  Usart_transmitByte(0x00);

Usart_transmitByte(0xFF);

  Usart_transmitByte(0x00);

Usart_Transmitindex++;

}

 else

{

Usart_transmitByte(Usart_TransmitDatebuf[Usart_Transmitindex]);

}

}

else

{

Usart_transmitByte(Usart_TransmitDatebuf[Usart_Transmitindex]);

}

 

}

 

//___________________End Transmit Data________________________

Usart_transmitByte(0xFF);

  Usart_transmitByte(0x00);

  //_____________________date 

Usart_transmitByte(0x00);

 

}

 

-------------------------------------------------------------------------------------------------------------------------------------------------


led.c

 

 #include "led.h"

 
void LED_GPIO_Config(void)
{
  GPIO_InitTypeDef GPIO_InitStructure;
 
  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA|RCC_APB2Periph_GPIOD  , ENABLE);
 
  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;     //LED1  V6   //将V6,V7,V8 配置为通用推挽输出  
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; //口线翻转速度为50MHz
  GPIO_Init(GPIOA, &GPIO_InitStructure); 
  
  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;     //LED1  V6   //将V6,V7,V8 配置为通用推挽输出  
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; //口线翻转速度为50MHz
  GPIO_Init(GPIOA, &GPIO_InitStructure);
}
 

---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------


can.c 

 

 

#include "can.h"

 

u16 ret;

/******************CAN1中断配置函数*********************************************/

//优先级:0

//中断服务程序:USB_LP_CAN1_RX0_IRQn------stm32f10x_it.

void CAN_NVIC_Configuration(void)

{

  NVIC_InitTypeDef NVIC_InitStructure;

 

  /* Enable CAN1 RX0 interrupt IRQ channel */

  NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;

  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;

  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;

  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;

  NVIC_Init(&NVIC_InitStructure);

}

/******************CAN1端口配置函数*********************************************/

//引脚:CAN1RX-PA8、CAN1Tx-PB8

//说明:开启端口B的时钟、CAN1的时钟

void CAN_GPIO_Configuration(void)

{

  GPIO_InitTypeDef GPIO_InitStructure;

 

  /* Configure CAN pin: RX */

  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;

  GPIO_InitStructure.GPIO_Speed=GPIO_Speed_50MHz;

  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;

  GPIO_Init(GPIOA, &GPIO_InitStructure);

  

  /* Configure CAN pin: TX */

  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;

  GPIO_InitStructure.GPIO_Speed=GPIO_Speed_50MHz;

  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;

  GPIO_Init(GPIOA, &GPIO_InitStructure);

     /*端口重映射到PB8、PB9上*/

 

 // GPIO_PinRemapConfig(GPIO_Remap2_CAN1, ENABLE);        //配置CAN总线为从映射

 

  RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE);   /* CAN Periph clock enable */

 

}

 

/******************CAN1查询接受配置函数*****************************************/

//波特率:SJW-1tq、BS1-8tq、BS2-7tq、Prescaler-5;

//

u8 CAN_Polling(void)

{

  CAN_InitTypeDef        CAN_InitStructure;

  CAN_FilterInitTypeDef  CAN_FilterInitStructure;

  CanTxMsg TxMessage;

  CanRxMsg RxMessage;

  uint32_t i = 0;

  uint8_t TransmitMailbox = 0;

 

  /* CAN register init */

  CAN_DeInit(CAN1);

  CAN_StructInit(&CAN_InitStructure);

 

  /* CAN cell init */

  CAN_InitStructure.CAN_TTCM=DISABLE;

  CAN_InitStructure.CAN_ABOM=DISABLE;

  CAN_InitStructure.CAN_AWUM=DISABLE;

  CAN_InitStructure.CAN_NART=DISABLE;

  CAN_InitStructure.CAN_RFLM=DISABLE;

  CAN_InitStructure.CAN_TXFP=DISABLE;

  CAN_InitStructure.CAN_Mode=CAN_Mode_LoopBack;

  CAN_InitStructure.CAN_SJW=CAN_SJW_1tq;

  CAN_InitStructure.CAN_BS1=CAN_BS1_8tq;

  CAN_InitStructure.CAN_BS2=CAN_BS2_7tq;

  CAN_InitStructure.CAN_Prescaler=5;

  CAN_Init(CAN1, &CAN_InitStructure);

 

  /* CAN filter init */

  CAN_FilterInitStructure.CAN_FilterNumber=0;

  CAN_FilterInitStructure.CAN_FilterMode=CAN_FilterMode_IdMask;

  CAN_FilterInitStructure.CAN_FilterScale=CAN_FilterScale_32bit;

  CAN_FilterInitStructure.CAN_FilterIdHigh=0x0000;

  CAN_FilterInitStructure.CAN_FilterIdLow=0x0000;

  CAN_FilterInitStructure.CAN_FilterMaskIdHigh=0x0000;

  CAN_FilterInitStructure.CAN_FilterMaskIdLow=0x0000;

  CAN_FilterInitStructure.CAN_FilterFIFOAssignment=0;

  CAN_FilterInitStructure.CAN_FilterActivation=ENABLE;

  CAN_FilterInit(&CAN_FilterInitStructure);

 

  /* transmit */

  TxMessage.StdId=0x11;

  TxMessage.RTR=CAN_RTR_DATA;

  TxMessage.IDE=CAN_ID_STD;

  TxMessage.DLC=2;

  TxMessage.Data[0]=0xAA;

  TxMessage.Data[1]=0xAA;

 

  TransmitMailbox=CAN_Transmit(CAN1, &TxMessage);

  i = 0;

  while((CAN_TransmitStatus(CAN1, TransmitMailbox) != CANTXOK) && (i != 0xFF))

  {

    i++;

  }

 

  i = 0;

  while((CAN_MessagePending(CAN1, CAN_FIFO0) < 1) && (i != 0xFF))

  {

    i++;

  }

 

  /* receive */

  RxMessage.StdId=0x00;

  RxMessage.IDE=CAN_ID_STD;

  RxMessage.DLC=0;

  RxMessage.Data[0]=0x00;

  RxMessage.Data[1]=0x00;

  CAN_Receive(CAN1, CAN_FIFO0, &RxMessage);

 

  if( (RxMessage.StdId!=0x11)|(RxMessage.StdId!=0x12) )

  {

    return 1;  

  }

 

  if (RxMessage.IDE!=CAN_ID_STD)

  {

    return 1;

  }

 

  if (RxMessage.DLC!=2)

  {

    return 1;  

  }

 

  if ((RxMessage.Data[0]<<8|RxMessage.Data[1])!=0xCAFE)

  {

    return 1;

  }

  

  return 0; /* Test Passed */

}

/******************CAN1中断接受配置函数*****************************************/

//波特率:SJW-1tq、BS1-8tq、BS2-7tq、Prescaler-5;

//

void  CAN_Interrupt(void)

{

  CAN_InitTypeDef        CAN_InitStructure;

  CAN_FilterInitTypeDef  CAN_FilterInitStructure;

 

  /* CAN register init */

  CAN_DeInit(CAN1);

  CAN_StructInit(&CAN_InitStructure);

 

  /* CAN cell init */

  CAN_InitStructure.CAN_TTCM=DISABLE;

  CAN_InitStructure.CAN_ABOM=DISABLE;

  CAN_InitStructure.CAN_AWUM=DISABLE;

  CAN_InitStructure.CAN_NART=DISABLE;

  CAN_InitStructure.CAN_RFLM=DISABLE;

  CAN_InitStructure.CAN_TXFP=DISABLE;

  CAN_InitStructure.CAN_Mode=CAN_Mode_Normal; //Normal  

  CAN_InitStructure.CAN_SJW=CAN_SJW_1tq;

  CAN_InitStructure.CAN_BS1=CAN_BS1_8tq;

  CAN_InitStructure.CAN_BS2=CAN_BS2_7tq;

  CAN_InitStructure.CAN_Prescaler=1;

  CAN_Init(CAN1, &CAN_InitStructure);

 

  /* CAN filter init */

  CAN_FilterInitStructure.CAN_FilterNumber=1;

  CAN_FilterInitStructure.CAN_FilterMode=CAN_FilterMode_IdMask;

  CAN_FilterInitStructure.CAN_FilterScale=CAN_FilterScale_32bit;

  CAN_FilterInitStructure.CAN_FilterIdHigh=0x0000;

  CAN_FilterInitStructure.CAN_FilterIdLow=0x0000;

  CAN_FilterInitStructure.CAN_FilterMaskIdHigh=0x0000;

  CAN_FilterInitStructure.CAN_FilterMaskIdLow=0x0000;

  CAN_FilterInitStructure.CAN_FilterFIFOAssignment=CAN_FIFO0;

  CAN_FilterInitStructure.CAN_FilterActivation=ENABLE;

  CAN_FilterInit(&CAN_FilterInitStructure);

 

  /* CAN FIFO0 message pending interrupt enable */ 

  CAN_ITConfig(CAN1, CAN_IT_FMP0, ENABLE); //CAN 中断使能

 

 

}

 

/******************CAN1数据传送函数*******************************************/

//

//

void CAN_TransmitData(u8 DataLength,u8 *Data_Buf,u32 ID)  /* transmit 1 message */

{

  CanTxMsg TxMessage;

  u8 CAN_Transmitindex=0;

  TxMessage.StdId=ID;

  TxMessage.ExtId=ID;

  TxMessage.IDE=CAN_ID_EXT;

  TxMessage.RTR=CAN_RTR_DATA;

  //_______________Set Data length _________________

  TxMessage.DLC=DataLength;

  for(CAN_Transmitindex=0;CAN_Transmitindex<DataLength;CAN_Transmitindex++)

   {

     TxMessage.Data[CAN_Transmitindex]=Data_Buf[CAN_Transmitindex];

   }

  

  //_____________________________________________

  CAN_Transmit(CAN1, &TxMessage);

}

 

void CAN_Init_Config(void)

{

  CAN_NVIC_Configuration();  //中断配置

  CAN_GPIO_Configuration();  //端口配置

  CAN_Interrupt();  //中断接受配置

 

}


0 0
原创粉丝点击