SNAR34 arduino四路舵机nrf遥控套装

来自小钉锤WIKI
跳到导航 跳到搜索

库文件:

代码:

Mirf

遥控器

//作者:小钉锤 MakerBuying SINONING
//www.xiaodingchui.com
//版本:NRF Remoter V1.3
/*
 * 买家朋友们请注意,V1.3版本由于换了大摇杆电位器导致遥控器下载程序不方便,所以遥控器的程序在这个版本通用化了,也就是朋友们可通过遥控器发送过来的数据判断遥控器所有摇杆和按键状态,这个版本增加了两个摇杆按钮。
 * 若朋友们一定要重新上传程序,可把配送的数据线头部塑料剪开去掉,直接把裸露的USB插头塞进去。
 * 遥控器不推动摇杆也不按下任何按键时遥控器不发送数据,以节省电量和减少干扰,否则隔约20MS发送一串8字节的数组:
 * TxBuff[8]:
 * TxBuff[0]——配对编码(拔码开关,两边相同可通信,防止两个遥控器相互干扰)
 * TxBuff[1]——流水号,每发一次自加一,可用来区分数据包顺序
 * TxBuff[2]——左摇杆左右方向,128为中心,255为最左,0为最右,为防止摇杆抖动引起误操作,该数值要>128+20或<128-20时才会发送数据。
 * TxBuff[3]——左摇杆上下方向,128为中心,255为最上,0为最下,为防止摇杆抖动引起误操作,该数值要>128+20或<128-20时才会发送数据。
 * TxBuff[4]——右摇杆左右方向,128为中心,255为最左,0为最右,为防止摇杆抖动引起误操作,该数值要>128+20或<128-20时才会发送数据。
 * TxBuff[5]——右摇杆上下方向,128为中心,255为最上,0为最下,为防止摇杆抖动引起误操作,该数值要>128+20或<128-20时才会发送数据。
 * TxBuff[6]——这个字节表示按键状态,从最高位到最低位分别表示:左摇杆按钮、右摇杆按钮、SW1、SW2、SW3、预留、预留、预留,高电平表示该按键被按下。
 *              如:TxBuff[6]=0101000,表示这个时候右摇杆按键与SW2被按下。
 * TxBuff[7]——最后一个字节是累加校验,即这个字节的值是前面七个字节相加的结果后去掉高字节保留低字节,用于校验数组是否正确接收           
 * 
 */

//NRF24L01硬件连接
//VCC<->3.3V
//GND<->GND
//CE<->D9
//CSN<->D10
//MOSI<->D11
//MISO<->D12
//SCK<->D13
//IRQ<->NULL

#include<SPI.h>
#include<Mirf.h>
#include<nRF24L01.h>
#include<MirfHardwareSpiDriver.h>

#define TxAddr "Robot"
#define RxAddr "Maste"
#define Lx A0
#define Ly A1
#define Rx A2
#define Ry A3
#define Lb A4
#define Rb A5
#define B1 2
#define B2 3
#define B3 4
#define IdPin0 5
#define IdPin1 6
#define IdPin2 7
#define IdPin3 8

#define deviation 20 //电位器判为有效的偏差

byte TxBuff[8];
//byte RxBuff[8];
byte MyId=0;

void setup() {

  //初始化GPIO
  pinMode(Lx,INPUT);
  pinMode(Ly,INPUT);
  pinMode(Rx,INPUT);
  pinMode(Ry,INPUT);
  pinMode(Lb,INPUT_PULLUP);
  pinMode(Rb,INPUT_PULLUP);
  pinMode(B1,INPUT_PULLUP);
  pinMode(B2,INPUT_PULLUP);
  pinMode(B3,INPUT_PULLUP);
  pinMode(IdPin1,INPUT_PULLUP);
  pinMode(IdPin2,INPUT_PULLUP);
  pinMode(IdPin3,INPUT_PULLUP);
  pinMode(IdPin0,INPUT_PULLUP);
  //获取遥控器ID
  if(!digitalRead(IdPin0)){
    MyId|=0x01;
  }
  if(!digitalRead(IdPin1)){
    MyId|=0x02;
  }
  if(!digitalRead(IdPin2)){
    MyId|=0x04;
  }
  if(!digitalRead(IdPin3)){
    MyId|=0x08;
  }
  TxBuff[0]=MyId;
  //初始化无线模块
  Mirf.cePin = 9;
  Mirf.csnPin = 10;
  Mirf.spi = &MirfHardwareSpi;
  Mirf.init();
  Mirf.setRADDR((byte *)"Maste");//设置接收地址
  Mirf.setTADDR((byte *)"Robot");//设置发送地址
  Mirf.payload = 8;//设置一次收发的字节数
  Mirf.channel = 3;//收发通道两端需一致
  Mirf.config();
}
void loop() {
  int n1,n2;
  int amin=255,amax=0,acc=0,dat;
  byte buff[4];
  
  //读取摇杆,数值做滤波处理,连续取五个值,放弃最大值和最小值求平均
  acc=0;
  amin=255;
  amax=0;
  for(n1=5;n1>0;n1--){
    dat=analogRead(Lx)/4;
    if(dat<amin)
      amin=dat;
    if(dat>amax)
      amax=dat;
    acc+=dat;
    delay(1);
  }
  buff[0]=(acc-amax-amin)/3;

  acc=0;
  amin=255;
  amax=0;
  for(n1=5;n1>0;n1--){
    dat=analogRead(Ly)/4;
    if(dat<amin)
      amin=dat;
    if(dat>amax)
      amax=dat;
    acc+=dat;
    delay(1);
  }
  buff[1]=(acc-amax-amin)/3;

  acc=0;
  amin=255;
  amax=0;
  for(n1=5;n1>0;n1--){
    dat=analogRead(Rx)/4;
    if(dat<amin)
      amin=dat;
    if(dat>amax)
      amax=dat;
    acc+=dat;
    delay(1);
  }
  buff[2]=(acc-amax-amin)/3;

  acc=0;
  amin=255;
  amax=0;
  for(n1=5;n1>0;n1--){
    dat=analogRead(Ry)/4;
    if(dat<amin)
      amin=dat;
    if(dat>amax)
      amax=dat;
    acc+=dat;
    delay(1);
  }
  buff[3]=(acc-amax-amin)/3;

  //读取按键值
  if(digitalRead(Lb)==0){
    TxBuff[6]|=0x80;
  }else{
    TxBuff[6]&=0x7f;
  }
  if(digitalRead(Rb)==0){
    TxBuff[6]|=0x40;
  }else{
    TxBuff[6]&=0xbf;
  }
  if(digitalRead(B1)==0){
    TxBuff[6]|=0x20;
  }else{
    TxBuff[6]&=0xdf;
  }
  if(digitalRead(B2)==0){
    TxBuff[6]|=0x10;
  }else{
    TxBuff[6]&=0xef;
  }
  if(digitalRead(B3)==0){
    TxBuff[6]|=0x08;
  }else{
    TxBuff[6]&=0xf7;
  }
  
  //
  if((buff[0]>(128+deviation))||(buff[0]<(128-deviation)))
    TxBuff[2]=buff[0];
  else
    TxBuff[2]=128;
  if((buff[1]>(128+deviation))||(buff[1]<(128-deviation)))
    TxBuff[3]=buff[1];
  else
    TxBuff[3]=128;
  if((buff[2]>(128+deviation))||(buff[2]<(128-deviation)))
    TxBuff[4]=buff[2];
  else
    TxBuff[4]=128;
  if((buff[3]>(128+deviation))||(buff[3]<(128-deviation)))
    TxBuff[5]=buff[3];
  else
    TxBuff[5]=128;

  //处理数组及发送
  if((TxBuff[2]!=128)||(TxBuff[3]!=128)||(TxBuff[4]!=128)||(TxBuff[5]!=128)||(TxBuff[6]!=0)){
    TxBuff[1]++;
    TxBuff[7]=0;
    for(n1=0;n1<7;n1++){
      TxBuff[7]+=TxBuff[n1];
    }
    Mirf.send(TxBuff);
    while(Mirf.isSending());//等待发送完毕 
  }
  //delay(20);
}

接收器

//作者:Johan
//微信:Error-000
//淘宝店:技术宅物语
//版本:NRF Control board V1.2

//NRF24L01硬件连接
//VCC<->3.3V
//GND<->GND
//CE<->D9
//CSN<->D10
//MOSI<->D11
//MISO<->D12
//SCK<->D13
//IRQ<->NULL

#include<SPI.h>
#include<Mirf.h>
#include<nRF24L01.h>
#include<MirfHardwareSpiDriver.h>
#include <Servo.h>

#define RxAddr "Robot"
#define TxAddr "Maste"


#define LArmAngle_Max 180//夹子最大角度
#define LArmAngle_Mid 90//夹子正常角度
#define LArmAngle_Min 0//夹子最小角度
#define RArmAngle_Max 180//抬臂最大角度
#define RArmAngle_Mid 90//抬臂正常角度
#define RArmAngle_Min 0//抬臂最小角度

#define XArmAngle_Max 180//夹子最大角度
#define XArmAngle_Mid 90//夹子正常角度
#define XArmAngle_Min 0//夹子最小角度
#define YArmAngle_Max 180//抬臂最大角度
#define YArmAngle_Mid 90//抬臂正常角度
#define YArmAngle_Min 0//抬臂最小角度

#define ServoLArm_PIN 2//定义夹子控制引脚
#define ServoRArm_PIN 3//定义抬臂控制引脚
#define ServoXArm_PIN 4//定义夹子控制引脚
#define ServoYArm_PIN 5//定义抬臂控制引脚

byte TxBuff[8];
byte RxBuff[8];
byte MyId=0;

int LArmAngle,RArmAngle,XArmAngle,YArmAngle;

Servo ServoLArm;//夹子舵机
Servo ServoRArm;//抬臂舵机
Servo ServoXArm;//夹子舵机
Servo ServoYArm;//抬臂舵机

void setup() {
  //初始化GPIO
  pinMode(ServoLArm_PIN,OUTPUT);
  pinMode(ServoRArm_PIN,OUTPUT);
  pinMode(ServoXArm_PIN,OUTPUT);
  pinMode(ServoYArm_PIN,OUTPUT);

  ServoLArm.attach(ServoLArm_PIN);
  ServoRArm.attach(ServoRArm_PIN);
  ServoXArm.attach(ServoXArm_PIN);
  ServoYArm.attach(ServoYArm_PIN);
  LArmAngle=LArmAngle_Mid; 
  RArmAngle=RArmAngle_Mid;
  XArmAngle=XArmAngle_Mid; 
  YArmAngle=YArmAngle_Mid;
  ServoLArm.write(LArmAngle);
  ServoRArm.write(RArmAngle);
  ServoXArm.write(XArmAngle);
  ServoYArm.write(YArmAngle);

  Mirf.cePin = 9;
  Mirf.csnPin = 10;
  Mirf.spi = &MirfHardwareSpi;
  Mirf.init();
  
  Mirf.setTADDR((byte *)"Maste");//设置发送地址
  Mirf.setRADDR((byte *)"Robot");//设置接收地址
  Mirf.payload = 8;//设置一次收发的字节数
  Mirf.channel = 3;//收发通道两端需一致
  Mirf.config();

  //Serial.begin(9600);
}
 
int x1=0,n1;
int acc=0,dat;
byte acc1;
void loop() {
 
  //等待接收数据准备好
  if(Mirf.dataReady()){
    Mirf.getData(RxBuff);//接收数据到数组
    //if(MyId==RxBuff[0]){//ID校验
    if(1){//不检查ID
      acc1=0;
      for(n1=0;n1<7;n1++){
        acc1+=RxBuff[n1];
      }
      if(acc1==RxBuff[7]){//累加校验
        RxBuff[7]--;

        //摆臂控制
        if(RxBuff[2]>128){//夹持
          if(XArmAngle>XArmAngle_Min+2){
            XArmAngle-=2;
            ServoXArm.write(XArmAngle);
          }
        }else if(RxBuff[2]<128){//释放
          if(XArmAngle<XArmAngle_Max-2){
            XArmAngle+=2;
            ServoXArm.write(XArmAngle);
          } 
        }
        if(RxBuff[3]>128){//抬起
           if(YArmAngle>YArmAngle_Min+2){
            YArmAngle-=2;
            ServoYArm.write(YArmAngle);
          }
        }else if(RxBuff[3]<128){//放下
          if(YArmAngle<YArmAngle_Max-2){
            YArmAngle+=2;
            ServoYArm.write(YArmAngle);
          }
        }
        if(RxBuff[6]&0x80){//复位
          XArmAngle=XArmAngle_Mid; 
          YArmAngle=YArmAngle_Mid;
          ServoXArm.write(XArmAngle);
          ServoYArm.write(YArmAngle);
        } 
        if(RxBuff[4]>128){//夹持
          if(LArmAngle>LArmAngle_Min+2){
            LArmAngle-=2;
            ServoLArm.write(LArmAngle);
          }
        }else if(RxBuff[4]<128){//释放
          if(LArmAngle<LArmAngle_Max-2){
            LArmAngle+=2;
            ServoLArm.write(LArmAngle);
          } 
        }
        if(RxBuff[5]>128){//抬起
           if(RArmAngle>RArmAngle_Min+2){
            RArmAngle-=2;
            ServoRArm.write(RArmAngle);
          }
        }else if(RxBuff[5]<128){//放下
          if(RArmAngle<RArmAngle_Max-2){
            RArmAngle+=2;
            ServoRArm.write(RArmAngle);
          }
        }
        if(RxBuff[6]&0x40){//复位
          LArmAngle=LArmAngle_Mid; 
          RArmAngle=RArmAngle_Mid;
          ServoLArm.write(LArmAngle);
          ServoRArm.write(RArmAngle);
        } 
      }
      //反馈数据
      TxBuff[1]++;
      TxBuff[7]=0;
      for(n1=0;n1<7;n1++){
        TxBuff[7]+=TxBuff[n1];
      }
    }
  }
  delay(10);
}