Ros小车-电机测速02_实现

/*
 * 测速实现:
 *  阶段1:脉冲数统计
 *  阶段2:速度计算
 * 
 * 阶段1:
 *  1.定义所使用的中断引脚,以及计数器(使用 volatile 修饰)
 *  2.setup 中设置波特率,将引脚设置为输入模式
 *  3.使用 attachInterupt() 函数为引脚添加中断出发时机以及中断函数
 *  4.中断函算算法,数编写计并打印
 *    A.单频统计只需要统计单相上升沿或下降沿
 *    B.2倍频统计需要统计单相的上升沿和下降沿
 *    C.4倍频统计需要统计两相的上升沿和下降沿
 *  5.上传并查看结果
 *  
 * 
 */
int motor_A = 2;//中端口是2
int motor_B = 3;//中断口是3
volatile int count = 0;//如果是正转,那么每计数一次自增1,如果是反转,那么每计数一次自减1 


int reducation = 90;//减速比,根据电机参数设置,比如 15 | 30 | 60
int pulse = 11; //编码器旋转一圈产生的脉冲数该值需要参考商家电机参数
int per_round = pulse * reducation * 4;//车轮旋转一圈产生的脉冲数 
long start_time = millis();//一个计算周期的开始时刻,初始值为 millis();
long interval_time = 50;//一个计算周期 50ms
double current_vel;

void count_A(){
  //单频计数实现
  //手动旋转电机一圈,输出结果为 一圈脉冲数 * 减速比
  /*if(digitalRead(motor_A) == HIGH){

    if(digitalRead(motor_B) == LOW){//A 高 B 低
      count++;  
    } else {//A 高 B 高
      count--;  
    }


  }*/

  //2倍频计数实现
  //手动旋转电机一圈,输出结果为 一圈脉冲数 * 减速比 * 2
  if(digitalRead(motor_A) == HIGH){

    if(digitalRead(motor_B) == HIGH){//A 高 B 高
      count++;  
    } else {//A 高 B 低
      count--;  
    }


  } else {

    if(digitalRead(motor_B) == LOW){//A 低 B 低
      count++;  
    } else {//A 低 B 高
      count--;  
    }  

  }

}

//与A实现类似
//4倍频计数实现
//手动旋转电机一圈,输出结果为 一圈脉冲数 * 减速比 * 4
void count_B(){
  if(digitalRead(motor_B) == HIGH){

    if(digitalRead(motor_A) == LOW){//B 高 A 低
      count++;
    } else {//B 高 A 高
      count--;
    }


  } else {

    if(digitalRead(motor_A) == HIGH){//B 低 A 高
      count++;
    } else {//B 低 A 低
      count--;
    }

  }

}

//获取当前转速的函数
void get_current_vel(){
  long right_now = millis();  
  long past_time = right_now - start_time;//计算逝去的时间
  if(past_time >= interval_time){//如果逝去时间大于等于一个计算周期
    //1.禁止中断
    noInterrupts();
    //2.计算转速 转速单位可以是秒,也可以是分钟... 自定义即可
    current_vel = (double)count / per_round / past_time * 1000 * 60;
    //3.重置计数器
    count = 0;
    //4.重置开始时间
    start_time = right_now;
    //5.重启中断
    interrupts();

    Serial.println(current_vel);

  }
}

void setup() {
  Serial.begin(57600);//设置波特率  
  pinMode(motor_A,INPUT);
  pinMode(motor_B,INPUT);
  attachInterrupt(2,count_A,CHANGE);//当电平发生改变时触发中断函数
  //四倍频统计需要为B相也添加中断
  attachInterrupt(0,count_B,CHANGE);
}


void loop() {
  //测试计数器输出
  // delay(2000);
  // Serial.println(count);
  delay(10);
  get_current_vel();

}

//现在四倍频,减速比为30,编码器为13线,单倍频计数,一圈输出390个脉冲


  • 0
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值