adapter_motor.ino 4.83 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
//timer setup for timer4
//For arduino Mega

//timer4 will interrupt at 20Hz

//storage variable
const byte INTERRUPT_NOISE_THRESHOLD = 5 ;

const word MOTOR_CENTER = 1000 ;
const word MOTOR_RIGHT = 1300 ;
const word MOTOR_LEFT = 700 ;
const byte MOTOR_THRESHOLD = 10 ;
const word MOTOR_RANGE = MOTOR_RIGHT - MOTOR_LEFT ;

const word RADIO_CENTER = 1500 ;
const word RADIO_RIGHT = 1900 ;
const word RADIO_LEFT = 1100 ;
const byte RADIO_THRESHOLD = 10 ;
const word RADIO_RANGE = RADIO_RIGHT - RADIO_LEFT ;

const int _kp = 1;

const byte interrupt_pin = 2 ;
static volatile uint32_t delta_us ;
static volatile uint32_t prev_change_date_us = 0 ;
static volatile uint32_t pos = 0;
static volatile byte count = 0;
static volatile uint32_t recv = 0;

bool first = true;
bool started = false;
static volatile int scale_pos = 50;
static volatile int scale_radio = 50;
byte speed_command = 0;
//***********************************************************************//
void setup(){
// put your setup code here, to run once:
  Serial.begin(9600); //usb pc
  Serial1.begin(9600); //sabertooth driver
  Serial2.begin(115200); //multiplexer
  Serial1.write(speed_command);
  while(!Serial){
    
  }
  cli(); //stop interrupts
  
  //set timer4 interrupt at 20Hz
  TCCR4A = 0;// set entire TCCR4A register to 0
  TCCR4B = 0;// same for TCCR4B
  TCNT4  = 0;//initialize counter value to 0
  // set compare match register for 20hz increments
  OCR4A = 311/1;// = (16*10^6) / (20*1024) - 1 (must be <65536) // 780 = 200hz / // turn on CTC mode
  TCCR4B |= (1 << WGM12);
  // Set CS12 and CS10 bits for 1024 prescaler
  TCCR4B |= (1 << CS12) | (1 << CS10);  
  // enable timer compare interrupt
  TIMSK4 |= (1 << OCIE4A);
  
  sei();//allow interrupts

  attachInterrupt(digitalPinToInterrupt(interrupt_pin),pwm,CHANGE);
  //delay(5);
}//end setup

ISR(TIMER4_COMPA_vect){
  //Serial.print("radio: ");
  //Serial.println(scale_radio);
  Serial2.write(0x43);
  count = 0;
  first = true;
}
//***********************************************************************//
void loop(){
 //do other things here
}
//***********************************************************************//
void pwm() {
  //Serial.print("change");
  uint32_t curr_date = micros () ;
  bool state_us ;

  delta_us = curr_date - prev_change_date_us ;
  
  if (delta_us < INTERRUPT_NOISE_THRESHOLD) return ;
  /* Record the previous pin state since it has just changed. */
  state_us = ! digitalRead (interrupt_pin) ;
  /* Ensure that we have detected a falling edge, i.e. the previous level
     of the pin was HIGH. */
  if (state_us) {
    //Serial.print("radio: ");
    //Serial.println(delta_us);
    if (delta_us <= RADIO_CENTER + RADIO_THRESHOLD && delta_us >= RADIO_CENTER - RADIO_THRESHOLD){
      scale_radio = 50;
    }
    else if (delta_us <= RADIO_LEFT + RADIO_THRESHOLD){
      scale_radio = 0;
    }
    else if (delta_us >= RADIO_RIGHT - RADIO_THRESHOLD){
      scale_radio = 100;
    } else {
      scale_radio = (delta_us - RADIO_LEFT) * 100 / (RADIO_RANGE);
    }
    //Serial.print("scale_radio: ");
    //Serial.println(scale_radio);
  }
  /* Change the date anyway. */
  prev_change_date_us = curr_date ;
}
//***********************************************************************//
void serialEvent2() {
  while(Serial2.available()){
    if (first) {
      recv = Serial2.read();
      first = false;
    }
    else {
      recv = (recv << 8) + Serial2.read();
    }
    count++;
  }
  if (count == 4) {
    pos = recv;
    //Serial.print("scale_pos: ");
    //Serial.println(pos);
    count = 0;
    speed_command = 64;
    first = true;
    if (!started) {
      if (pos > MOTOR_CENTER + MOTOR_THRESHOLD || pos < MOTOR_CENTER - MOTOR_THRESHOLD){
        if(pos < MOTOR_LEFT) speed_command = 127;
        else if(pos > MOTOR_RIGHT) speed_command = 1;
        else if(pos < MOTOR_CENTER - MOTOR_THRESHOLD) speed_command = 100;
        else if(pos > MOTOR_CENTER + MOTOR_THRESHOLD) speed_command = 28;
      } else {
        //Serial.print("centered");
        speed_command = 64;
        started = true;
      }
      Serial1.write(speed_command);
    }
    else {
      scale_pos = (pos - MOTOR_LEFT)* 100/(MOTOR_RANGE);
      
      //Serial.print("scale_pos: ");
      //Serial.println(scale_pos);
      
      int error_pos = scale_radio - scale_pos;
      int v = _kp * error_pos;
      if (v >= -1 && v <= 1){
        speed_command = 64;
      }
      else if (v >= 30) {
        speed_command = 127;
      }
      else if (v <= -30) {
        speed_command = 1;
      }
      else {
        speed_command = (1.26) * (v - 50) + 127;
      }
      //Serial.print("v: ");
      //Serial.println(v);
      //Serial.print("speed_command: ");
      //Serial.println(speed_command);
    }
    Serial1.write(speed_command);
  }
}
//***********************************************************************//
void serialEvent(){
  started = true;
  Serial1.write(0);
}