Showing
1 changed file
with
238 additions
and
0 deletions
1 | +#include <CoDrone.h> // 코드론 라이브러리 | ||
2 | + | ||
3 | +#define ShockLed 12 // 충격 상태 확인을 위한 LED 핀번호 | ||
4 | +#define LeftVib 27 // 왼쪽 진동자 핀번호 | ||
5 | +#define RightVib 28 // 오른쪽 진동자 핀번호 | ||
6 | + | ||
7 | +// 변수 및 상수부 | ||
8 | +long ac_x, ac_y, ac_z, gy_x, gy_y, gy_z; //acc, gyro data (acc, gyro 계산 수식) | ||
9 | +double angle = 0, deg; // angle, deg data (각도계산) | ||
10 | +double dgy_x; // double type acc data | ||
11 | +long int normal_x, normal_y, normal_z, deltha_x[3], deltha_y[3], deltha_z[3], deltha; // 노말라이즈(정규화 데이터), 가속도 변화량 표시 | ||
12 | +long int angle_value; | ||
13 | +const int mapping_value = 5000; | ||
14 | +const int Emergency_value = 10000; // 충격상태로 판단하는 값 | ||
15 | +const int Emergency_angle = 25; // 충격상태로 판단하는 각도(기울기) | ||
16 | +const int Emergency_value2 = 1200;// 충격상태로 판단하는 값 | ||
17 | +const int Emergency_angle2 = 9; // 충격상태로 판단하는 각도(기울기) | ||
18 | +boolean State_Parameter = false; // 충격상태 판단 | ||
19 | +unsigned short int shock_level; // 충격정도 상,중,하 char로 받을 생각 | ||
20 | +const long int sum_count = 4; // 평균 내는 횟수 | ||
21 | +const long interval = 50; // 충격을 감지후 다음 충격을 감지하는 최소 간극 시간 (ms) | ||
22 | +unsigned long previousMillis = 0; // 최초 시작시간 | ||
23 | +long shock_sum = 0; // 누적 충격값 | ||
24 | + | ||
25 | +//사용자지정 함수부 | ||
26 | +void value_init() | ||
27 | +{ | ||
28 | + normal_x = 0; | ||
29 | + normal_y = 0; | ||
30 | + normal_z = 0; | ||
31 | + | ||
32 | + for(int i = 0; i < 3; i++){ | ||
33 | + deltha_x[i] = 0; | ||
34 | + deltha_y[i] = 0; | ||
35 | + deltha_z[i] = 0; | ||
36 | + angle = 0; | ||
37 | + angle_value = 0; | ||
38 | + } | ||
39 | +} | ||
40 | +// 가속도 연산 함수 | ||
41 | +void accel_calculate() | ||
42 | +{ | ||
43 | + ac_x = 0; | ||
44 | + ac_y = 0; | ||
45 | + ac_z = 0; | ||
46 | + normal_x = 0; | ||
47 | + normal_y = 0; | ||
48 | + normal_z = 0; | ||
49 | + | ||
50 | + /* MPU 6050 전용 | ||
51 | + Wire.beginTransmission(mpu_add) ; // 번지수 찾기 | ||
52 | + Wire.write(0x3B) ; // 가속도 데이터 보내달라고 컨트롤 신호 보내기 | ||
53 | + Wire.endTransmission(false) ; // 기달리고, | ||
54 | + Wire.requestFrom(mpu_add, 6, true) ; // 데이터를 받아 처리 | ||
55 | + */ | ||
56 | + | ||
57 | + // Data SHIFT From CoDrone Accelerometer | ||
58 | + ac_x = CoDrone.getAccelerometer().x; | ||
59 | + ac_y = CoDrone.getAccelerometer().y; | ||
60 | + ac_z = CoDrone.getAccelerometer().z; | ||
61 | + | ||
62 | + //맵핑화 시킨 것 - 즉 10000으로 맵핑시킴 | ||
63 | + normal_x = map(int(ac_x), -16384, 16384, -5000, mapping_value); | ||
64 | + normal_y = map(int(ac_y), -16384, 16384, -5000, mapping_value); | ||
65 | + normal_z = map(int(ac_z), -16384, 16384, -5000, mapping_value); | ||
66 | + | ||
67 | + //normal_z = map(int(ac_z), -16384, 16384, -1000, mapping_value); | ||
68 | + | ||
69 | + //각도계산 deg -> 각도 | ||
70 | + deg = atan2(ac_x, ac_z) * 180 / PI ; //rad to deg | ||
71 | + dgy_x = gy_y / 131. ; //16-bit data to 250 deg/sec | ||
72 | + angle = (0.95 * (angle + (dgy_x * 0.001))) + (0.05 * deg) ; | ||
73 | +} | ||
74 | + | ||
75 | +// 충격상태함수 | ||
76 | +void Emergency_state_() | ||
77 | +{ | ||
78 | + digitalWrite(ShockLed , HIGH); // 릴레이핀을 True값으로 바꿔 13번 핀의 LED를 ON시킨다. | ||
79 | + Serial.print("SHOCK level : "); | ||
80 | + Serial.println(shock_level); // Serial 모니터로 확인 | ||
81 | + Serial.print(" x: "); | ||
82 | + Serial.print(deltha_x[0]); | ||
83 | + Serial.print(" y: "); | ||
84 | + Serial.print(deltha_y[0]); | ||
85 | + Serial.print(" z: "); | ||
86 | + Serial.println(deltha_z[0]); | ||
87 | + | ||
88 | + /*Serial.print(" deltha_1 : "); Serial.print(deltha_x[1]); | ||
89 | + Serial.print(" deltha_2 : "); Serial.println(deltha_x[2]);*/ | ||
90 | +} | ||
91 | + | ||
92 | +// 충격 감지함수 | ||
93 | +void Shock_Sensing() | ||
94 | +{ | ||
95 | + State_Parameter = false; // 충격상태 초기화 | ||
96 | + shock_level = 0; // 충격정도 초기화 | ||
97 | + //첫번째 센싱 | ||
98 | + for (int i=0; i < sum_count; i++){ | ||
99 | + accel_calculate(); | ||
100 | + deltha_x[1] = deltha_x[1]+(normal_x); | ||
101 | + deltha_y[1] = deltha_y[1]+(normal_y); | ||
102 | + deltha_z[1] = deltha_z[1]+(normal_z); | ||
103 | + angle_value = angle_value + angle; | ||
104 | + } | ||
105 | + deltha_x[1] = int(deltha_x[1]/sum_count); | ||
106 | + deltha_y[1] = int(deltha_y[1]/sum_count); | ||
107 | + deltha_z[1] = int(deltha_z[1]/sum_count); | ||
108 | + | ||
109 | + //두번째 센싱 | ||
110 | + for (int i=0; i < sum_count; i++) | ||
111 | + { | ||
112 | + accel_calculate(); | ||
113 | + deltha_x[2] = deltha_x[2]+(normal_x); | ||
114 | + deltha_y[2] = deltha_y[2]+(normal_y); | ||
115 | + deltha_z[2] = deltha_z[2]+(normal_z); | ||
116 | + angle_value = angle_value + angle; | ||
117 | + } | ||
118 | + deltha_x[2] = int(deltha_x[2]/sum_count); | ||
119 | + deltha_y[2] = int(deltha_y[2]/sum_count); | ||
120 | + deltha_z[2] = int(deltha_z[2]/sum_count); | ||
121 | + | ||
122 | + //3축 변화량 비교 - 가속도 변화량, 각도 평균 값 | ||
123 | + deltha_x[0] = abs(deltha_x[1]-deltha_x[2]); | ||
124 | + deltha_y[0] = abs(deltha_y[1]-deltha_y[2]); | ||
125 | + deltha_z[0] = abs(deltha_z[1]-deltha_z[2]); | ||
126 | + deltha = deltha_x[0] + deltha_y[0] + deltha_z[0]; | ||
127 | + angle_value = abs(int(angle_value/(sum_count))); | ||
128 | + | ||
129 | + // deltha : 가속도 변화량 | ||
130 | + // angle_value : 각도 값(현재 각도 값) | ||
131 | + if (deltha > Emergency_value){ | ||
132 | + State_Parameter=true; | ||
133 | + } | ||
134 | + shock_level = deltha; // 추후 수정 예정 | ||
135 | + | ||
136 | + /* | ||
137 | + if(deltha > 하){ | ||
138 | + shock_level = 'a'; | ||
139 | + if(deltha > 중){ | ||
140 | + shock_level = 'b'; | ||
141 | + if(deltha > 상){ | ||
142 | + shock_level = 'c'; | ||
143 | + } | ||
144 | + } | ||
145 | + } | ||
146 | + | ||
147 | + */ | ||
148 | + | ||
149 | + | ||
150 | + /*if (angle_value > Emergency_angle){ | ||
151 | + State_Parameter=true; | ||
152 | + } | ||
153 | + if ((deltha > Emergency_value2)&&(angle_value > Emergency_angle2)){ | ||
154 | + State_Parameter=true; | ||
155 | + }*/ | ||
156 | + | ||
157 | + // 충격상태체크 | ||
158 | + if( State_Parameter == true ) | ||
159 | + { | ||
160 | + Emergency_state_(); | ||
161 | + } | ||
162 | + else | ||
163 | + { | ||
164 | + digitalWrite(ShockLed , LOW); | ||
165 | + } | ||
166 | +} | ||
167 | + | ||
168 | +// 진동함수 | ||
169 | +void vibrate() | ||
170 | +{ | ||
171 | + | ||
172 | +} | ||
173 | + | ||
174 | + | ||
175 | + | ||
176 | +// Main 함수부 | ||
177 | +void setup() | ||
178 | +{ | ||
179 | + pinMode(LeftVib,OUTPUT); | ||
180 | + pinMode(RightVib,OUTPUT); | ||
181 | + pinMode(ShockLed,OUTPUT); // 핀모드사용, led로 육안확인 가능하게끔 | ||
182 | + digitalWrite(ShockLed,LOW); // HIGH - LED on, LOW - LED off (DEFAULT : OFF) | ||
183 | + CoDrone.begin(115200); // 드론 플러그의 통신 개시 (115200bps) | ||
184 | + CoDrone.AutoConnect(NearbyDrone); // 가장 가까운 위치의 드론과 연결 | ||
185 | + CoDrone.DroneModeChange(Flight); // 드론을 플라이트 모드로 설정 | ||
186 | +} | ||
187 | + | ||
188 | +void loop() | ||
189 | +{ | ||
190 | + value_init(); //가속도-각도 관련 초기값 선언 | ||
191 | + | ||
192 | + byte bt1 = digitalRead(11); // ■ □ □ □ □ □ □ 밑면 적외선 센서를 입력으로 사용 | ||
193 | + byte bt4 = digitalRead(14); // □ □ □ ■ □ □ □ 밑면 적외선 센서를 입력으로 사용 | ||
194 | + byte bt8 = digitalRead(18); // □ □ □ □ □ □ ■ 밑면 적외선 센서를 입력으로 사용 | ||
195 | + | ||
196 | + if (bt1 && !bt4 && !bt8) // 밑면 센서 가장 끝 11번 센서에 손을 대면 실행합니다. | ||
197 | + { | ||
198 | + CoDrone.FlightEvent(Stop); // 드론을 정지시킵니다. | ||
199 | + } | ||
200 | + | ||
201 | + if (!bt1 && !bt4 && bt8) // 밑면 센서 가장 끝 18번 센서에 손을 대면 실행합니다. | ||
202 | + { | ||
203 | + CoDrone.FlightEvent(Landing); // 드론을 착륙시킵니다. | ||
204 | + } | ||
205 | + | ||
206 | + Shock_Sensing(); | ||
207 | + if(State_Parameter == true){ | ||
208 | + shock_sum += deltha; | ||
209 | + //currentMillis = millis(); | ||
210 | + } | ||
211 | + | ||
212 | + if(State_Parameter == false && shock_sum != 0){ | ||
213 | + //bluetooth.write(char_maker(shock_sum)); // 블루투스로 충격정도 전송 (shock_maker 라는 char 리턴함수를 통해 진동강도 전송) | ||
214 | + Serial.print("누적 충격값 : "); | ||
215 | + Serial.println(shock_sum); // 충격 누적값 전송 | ||
216 | + shock_sum = 0; // 충격의 지속이 끝났으니 원래값인 0으로 초기화 | ||
217 | + } | ||
218 | + | ||
219 | + // 연결(페어링)이 성공한 경우에만 실행 | ||
220 | + if(PAIRING == true) | ||
221 | + { | ||
222 | + | ||
223 | + YAW = -1 * CoDrone.AnalogScaleChange(analogRead(A3)); | ||
224 | + // 아날로그 3번 핀의 값을 YAW 값으로 사용합니다. - 좌우회전 | ||
225 | + | ||
226 | + THROTTLE = CoDrone.AnalogScaleChange(analogRead(A4)); | ||
227 | + // 아날로그 4번 핀의 값을 THROTTLE 값으로 사용합니다. - 승하강 | ||
228 | + | ||
229 | + ROLL = -1 * CoDrone.AnalogScaleChange(analogRead(A5)); | ||
230 | + // 아날로그 5번 핀의 값을 ROLL 값으로 사용합니다. - 좌우이동 | ||
231 | + | ||
232 | + PITCH = CoDrone.AnalogScaleChange(analogRead(A6)); | ||
233 | + // 아날로그 6번 핀의 값을 PITCH 값으로 사용합니다. - 전후진 | ||
234 | + | ||
235 | + CoDrone.Control(SEND_INTERVAL); | ||
236 | + // 제어 신호를 보냅니다. 통신이 안정하게 가도록 시간을 두고 보냄 (최소 50ms) | ||
237 | + } | ||
238 | +} |
-
Please register or login to post a comment