1 | #include "r2ca.h"
|
---|
2 | #include "ESP8266.h"
|
---|
3 |
|
---|
4 | #include <Wire.h>
|
---|
5 | #include <ZumoShield.h>
|
---|
6 |
|
---|
7 | #include <SPI.h>
|
---|
8 | #include <Pixy.h>
|
---|
9 |
|
---|
10 | #include "../examples_gdef.h"
|
---|
11 |
|
---|
12 | #define WMODE_STATION
|
---|
13 |
|
---|
14 | uint16_t pixy_blocks = 0;
|
---|
15 | char pixy_buf[16][128];
|
---|
16 |
|
---|
17 | //==========================================================================
|
---|
18 | //
|
---|
19 | // Pixy Pet Robot
|
---|
20 | //
|
---|
21 | // Adafruit invests time and resources providing this open source code,
|
---|
22 | // please support Adafruit and open-source hardware by purchasing
|
---|
23 | // products from Adafruit!
|
---|
24 | //
|
---|
25 | // Written by: Bill Earl for Adafruit Industries
|
---|
26 | //
|
---|
27 | //==========================================================================
|
---|
28 | // begin license header
|
---|
29 | //
|
---|
30 | // All Pixy Pet source code is provided under the terms of the
|
---|
31 | // GNU General Public License v2 (http://www.gnu.org/licenses/gpl-2.0.html).
|
---|
32 | //
|
---|
33 | // end license header
|
---|
34 | //
|
---|
35 | //==========================================================================
|
---|
36 | //
|
---|
37 | // Portions of this code are derived from the Pixy CMUcam5 pantilt example code.
|
---|
38 | //
|
---|
39 | //==========================================================================
|
---|
40 |
|
---|
41 | #define X_CENTER 160L
|
---|
42 | #define Y_CENTER 100L
|
---|
43 | #define RCS_MIN_POS 0L
|
---|
44 | #define RCS_MAX_POS 1000L
|
---|
45 | #define RCS_CENTER_POS ((RCS_MAX_POS-RCS_MIN_POS)/2)
|
---|
46 |
|
---|
47 | //---------------------------------------
|
---|
48 | // Servo Loop Class
|
---|
49 | // A Proportional/Derivative feedback
|
---|
50 | // loop for pan/tilt servo tracking of
|
---|
51 | // blocks.
|
---|
52 | // (Based on Pixy CMUcam5 example code)
|
---|
53 | //---------------------------------------
|
---|
54 | class ServoLoop
|
---|
55 | {
|
---|
56 | public:
|
---|
57 | ServoLoop(int32_t proportionalGain, int32_t derivativeGain);
|
---|
58 |
|
---|
59 | void update(int32_t error);
|
---|
60 |
|
---|
61 | int32_t m_pos;
|
---|
62 | int32_t m_prevError;
|
---|
63 | int32_t m_proportionalGain;
|
---|
64 | int32_t m_derivativeGain;
|
---|
65 | };
|
---|
66 |
|
---|
67 | // ServoLoop Constructor
|
---|
68 | ServoLoop::ServoLoop(int32_t proportionalGain, int32_t derivativeGain)
|
---|
69 | {
|
---|
70 | m_pos = RCS_CENTER_POS;
|
---|
71 | m_proportionalGain = proportionalGain;
|
---|
72 | m_derivativeGain = derivativeGain;
|
---|
73 | m_prevError = 0x80000000L;
|
---|
74 | }
|
---|
75 |
|
---|
76 | // ServoLoop Update
|
---|
77 | // Calculates new output based on the measured
|
---|
78 | // error and the current state.
|
---|
79 | void ServoLoop::update(int32_t error)
|
---|
80 | {
|
---|
81 | long int velocity;
|
---|
82 | char buf[32];
|
---|
83 | if (m_prevError!=0x80000000)
|
---|
84 | {
|
---|
85 | velocity = (error*m_proportionalGain + (error - m_prevError)*m_derivativeGain)>>10;
|
---|
86 |
|
---|
87 | m_pos += velocity;
|
---|
88 | if (m_pos>RCS_MAX_POS)
|
---|
89 | {
|
---|
90 | m_pos = RCS_MAX_POS;
|
---|
91 | }
|
---|
92 | else if (m_pos<RCS_MIN_POS)
|
---|
93 | {
|
---|
94 | m_pos = RCS_MIN_POS;
|
---|
95 | }
|
---|
96 | }
|
---|
97 | m_prevError = error;
|
---|
98 | }
|
---|
99 | // End Servo Loop Class
|
---|
100 | //---------------------------------------
|
---|
101 |
|
---|
102 | Pixy pixy; // Declare the camera object
|
---|
103 |
|
---|
104 | ServoLoop panLoop(200, 200); // Servo loop for pan
|
---|
105 | ServoLoop tiltLoop(150, 200); // Servo loop for tilt
|
---|
106 |
|
---|
107 | void ScanForBlocks();
|
---|
108 | void FollowBlock(int trackedBlock);
|
---|
109 | int TrackBlock(int blockCount);
|
---|
110 | void task1_setup();
|
---|
111 |
|
---|
112 | //---------------------------------------
|
---|
113 | // Setup - runs once at startup
|
---|
114 | //---------------------------------------
|
---|
115 | void setup()
|
---|
116 | {
|
---|
117 | ZumoInit();
|
---|
118 | buzzer.playOn();
|
---|
119 | Serial.begin(115200);
|
---|
120 | Serial.print("Starting...\n");
|
---|
121 | pixy.init();
|
---|
122 |
|
---|
123 | button.waitForPress();
|
---|
124 | buzzer.playStart();
|
---|
125 |
|
---|
126 | task1_setup();
|
---|
127 | }
|
---|
128 |
|
---|
129 | uint32_t lastBlockTime = 0;
|
---|
130 |
|
---|
131 | //---------------------------------------
|
---|
132 | // Main loop - runs continuously after setup
|
---|
133 | //---------------------------------------
|
---|
134 | void loop()
|
---|
135 | {
|
---|
136 | uint16_t blocks;
|
---|
137 | blocks = pixy.getBlocks();
|
---|
138 |
|
---|
139 | // If we have blocks in sight, track and follow them
|
---|
140 | if (blocks)
|
---|
141 | {
|
---|
142 | int trackedBlock = TrackBlock(blocks);
|
---|
143 | FollowBlock(trackedBlock);
|
---|
144 | lastBlockTime = millis();
|
---|
145 | if(pixy_blocks == 0) {
|
---|
146 | if (blocks > 16) {
|
---|
147 | blocks = 16;
|
---|
148 | }
|
---|
149 | pixy_blocks = blocks;
|
---|
150 | for (int j=0; j<blocks; j++){
|
---|
151 | sprintf(pixy_buf[j], "sig: %d x: %d y: %d width: %d height: %d\n",
|
---|
152 | pixy.blocks[j].signature, pixy.blocks[j].x, pixy.blocks[j].y,
|
---|
153 | pixy.blocks[j].width, pixy.blocks[j].height);
|
---|
154 | }
|
---|
155 | }
|
---|
156 | delay(1);
|
---|
157 | }
|
---|
158 | else if (millis() - lastBlockTime > 100)
|
---|
159 | {
|
---|
160 | motors.setLeftSpeed(0);
|
---|
161 | motors.setRightSpeed(0);
|
---|
162 | ScanForBlocks();
|
---|
163 | }
|
---|
164 | }
|
---|
165 |
|
---|
166 | int oldX, oldY, oldSignature;
|
---|
167 |
|
---|
168 | //---------------------------------------
|
---|
169 | // Track blocks via the Pixy pan/tilt mech
|
---|
170 | // (based in part on Pixy CMUcam5 pantilt example)
|
---|
171 | //---------------------------------------
|
---|
172 | int TrackBlock(int blockCount)
|
---|
173 | {
|
---|
174 | int trackedBlock = 0;
|
---|
175 | long maxSize = 0;
|
---|
176 |
|
---|
177 | Serial.print("blocks =");
|
---|
178 | Serial.println(blockCount);
|
---|
179 |
|
---|
180 | for (int i = 0; i < blockCount; i++)
|
---|
181 | {
|
---|
182 | if ((oldSignature == 0) || (pixy.blocks[i].signature == oldSignature))
|
---|
183 | {
|
---|
184 | long newSize = pixy.blocks[i].height * pixy.blocks[i].width;
|
---|
185 | if (newSize > maxSize)
|
---|
186 | {
|
---|
187 | trackedBlock = i;
|
---|
188 | maxSize = newSize;
|
---|
189 | }
|
---|
190 | }
|
---|
191 | }
|
---|
192 |
|
---|
193 | int32_t panError = X_CENTER - pixy.blocks[trackedBlock].x;
|
---|
194 | int32_t tiltError = pixy.blocks[trackedBlock].y - Y_CENTER;
|
---|
195 |
|
---|
196 | panLoop.update(panError);
|
---|
197 | tiltLoop.update(tiltError);
|
---|
198 |
|
---|
199 | pixy.setServos(panLoop.m_pos, tiltLoop.m_pos);
|
---|
200 |
|
---|
201 | oldX = pixy.blocks[trackedBlock].x;
|
---|
202 | oldY = pixy.blocks[trackedBlock].y;
|
---|
203 | oldSignature = pixy.blocks[trackedBlock].signature;
|
---|
204 | return trackedBlock;
|
---|
205 | }
|
---|
206 |
|
---|
207 | //---------------------------------------
|
---|
208 | // Follow blocks via the Zumo robot drive
|
---|
209 | //
|
---|
210 | // This code makes the robot base turn
|
---|
211 | // and move to follow the pan/tilt tracking
|
---|
212 | // of the head.
|
---|
213 | //---------------------------------------
|
---|
214 | int32_t size = 400;
|
---|
215 | void FollowBlock(int trackedBlock)
|
---|
216 | {
|
---|
217 | int32_t followError = RCS_CENTER_POS - panLoop.m_pos; // How far off-center are we looking now?
|
---|
218 |
|
---|
219 | // Size is the area of the object.
|
---|
220 | // We keep a running average of the last 8.
|
---|
221 | size += pixy.blocks[trackedBlock].width * pixy.blocks[trackedBlock].height;
|
---|
222 | size -= size >> 3;
|
---|
223 |
|
---|
224 | // Forward speed decreases as we approach the object (size is larger)
|
---|
225 | int forwardSpeed = constrain(400 - (size/256), -100, 400);
|
---|
226 |
|
---|
227 | // Steering differential is proportional to the error times the forward speed
|
---|
228 | int32_t differential = (followError + (followError * forwardSpeed))>>8;
|
---|
229 |
|
---|
230 | // Adjust the left and right speeds by the steering differential.
|
---|
231 | int leftSpeed = constrain(forwardSpeed + differential, -400, 400);
|
---|
232 | int rightSpeed = constrain(forwardSpeed - differential, -400, 400);
|
---|
233 |
|
---|
234 | // And set the motor speeds
|
---|
235 | motors.setLeftSpeed(leftSpeed);
|
---|
236 | motors.setRightSpeed(rightSpeed);
|
---|
237 | }
|
---|
238 |
|
---|
239 | //---------------------------------------
|
---|
240 | // Random search for blocks
|
---|
241 | //
|
---|
242 | // This code pans back and forth at random
|
---|
243 | // until a block is detected
|
---|
244 | //---------------------------------------
|
---|
245 | int scanIncrement = (RCS_MAX_POS - RCS_MIN_POS) / 150;
|
---|
246 | uint32_t lastMove = 0;
|
---|
247 |
|
---|
248 | void ScanForBlocks()
|
---|
249 | {
|
---|
250 | if (millis() - lastMove > 20)
|
---|
251 | {
|
---|
252 | lastMove = millis();
|
---|
253 | panLoop.m_pos += scanIncrement;
|
---|
254 | if ((panLoop.m_pos >= RCS_MAX_POS)||(panLoop.m_pos <= RCS_MIN_POS))
|
---|
255 | {
|
---|
256 | tiltLoop.m_pos = random(RCS_MAX_POS * 0.6, RCS_MAX_POS);
|
---|
257 | scanIncrement = -scanIncrement;
|
---|
258 | if (scanIncrement < 0)
|
---|
259 | {
|
---|
260 | motors.setLeftSpeed(-250);
|
---|
261 | motors.setRightSpeed(250);
|
---|
262 | }
|
---|
263 | else
|
---|
264 | {
|
---|
265 | motors.setLeftSpeed(+180);
|
---|
266 | motors.setRightSpeed(-180);
|
---|
267 | }
|
---|
268 | delay(random(250, 500));
|
---|
269 | }
|
---|
270 |
|
---|
271 | pixy.setServos(panLoop.m_pos, tiltLoop.m_pos);
|
---|
272 | }
|
---|
273 | }
|
---|
274 |
|
---|
275 |
|
---|
276 | void task1_setup()
|
---|
277 | {
|
---|
278 | int ret;
|
---|
279 |
|
---|
280 | Serial.println("Echo Server : Start!");
|
---|
281 | ret = WiFi.begin(Serial5, 115200);
|
---|
282 |
|
---|
283 | if(ret == 1) {
|
---|
284 | Serial.print("Cannot communicate with ESP8266.");
|
---|
285 | while(1);
|
---|
286 | } else if(ret == 2) {
|
---|
287 | Serial.println("FW Version mismatch.");
|
---|
288 | Serial.print("FW Version:");
|
---|
289 | Serial.println(WiFi.getVersion().c_str());
|
---|
290 | Serial.print("Supported FW Version:");
|
---|
291 | Serial.print(ESP8266_SUPPORT_VERSION);
|
---|
292 | while(1);
|
---|
293 | } else {
|
---|
294 | Serial.print("begin ok\r\n");
|
---|
295 | }
|
---|
296 |
|
---|
297 | Serial.print("FW Version:");
|
---|
298 | Serial.println(WiFi.getVersion().c_str());
|
---|
299 |
|
---|
300 | #ifdef WMODE_STATION
|
---|
301 | if (WiFi.setOprToStation()) {
|
---|
302 | Serial.print("to station ok\r\n");
|
---|
303 | } else {
|
---|
304 | Serial.print("to station err\r\n");
|
---|
305 | }
|
---|
306 |
|
---|
307 | if (WiFi.joinAP(STA_SSID, STA_PASSWORD)) {
|
---|
308 | Serial.print("Join AP success\r\n");
|
---|
309 | Serial.print("IP: ");
|
---|
310 | Serial.println(WiFi.getLocalIP().c_str());
|
---|
311 | } else {
|
---|
312 | Serial.print("Join AP failure\r\n");
|
---|
313 | while(1);
|
---|
314 | }
|
---|
315 | #else /* !WMODE_STATION */
|
---|
316 | if (WiFi.setOprToSoftAP()) {
|
---|
317 | Serial.print("to softap ok\r\n");
|
---|
318 | } else {
|
---|
319 | Serial.print("to softap err\r\n");
|
---|
320 | }
|
---|
321 | if(WiFi.setSoftAPParam(AP_SSID, AP_PASSWORD, 7, 0)){
|
---|
322 | Serial.print("Set SoftAP success\r\n");
|
---|
323 | Serial.print("IP: ");
|
---|
324 | Serial.println(WiFi.getLocalIP().c_str());
|
---|
325 | }
|
---|
326 | else {
|
---|
327 | Serial.print("Set SoftAP failure\r\n");
|
---|
328 | }
|
---|
329 | #endif /* WMODE_STATION */
|
---|
330 |
|
---|
331 | if (WiFi.enableMUX()) {
|
---|
332 | Serial.print("multiple ok\r\n");
|
---|
333 | } else {
|
---|
334 | Serial.print("multiple err\r\n");
|
---|
335 | while(1);
|
---|
336 | }
|
---|
337 |
|
---|
338 | if (WiFi.startTCPServer(80)) {
|
---|
339 | Serial.print("start tcp server ok\r\n");
|
---|
340 | } else {
|
---|
341 | Serial.print("start tcp server err\r\n");
|
---|
342 | while(1);
|
---|
343 | }
|
---|
344 |
|
---|
345 | if (WiFi.setTCPServerTimeout(60)) {
|
---|
346 | Serial.print("set tcp server timout 60 seconds\r\n");
|
---|
347 | } else {
|
---|
348 | Serial.print("set tcp server timout err\r\n");
|
---|
349 | while(1);
|
---|
350 | }
|
---|
351 |
|
---|
352 | Serial.print("setup end\r\n");
|
---|
353 | }
|
---|
354 |
|
---|
355 | #define MUX_NULL 0xff
|
---|
356 |
|
---|
357 | uint8_t mux_id_ptn;
|
---|
358 |
|
---|
359 | uint8_t mux_id = MUX_NULL;
|
---|
360 | uint8_t task1_mux_id = MUX_NULL;
|
---|
361 |
|
---|
362 | void loop1()
|
---|
363 | {
|
---|
364 | char buf[128];
|
---|
365 | uint8_t pre_mux_id_ptn;
|
---|
366 |
|
---|
367 | /* Check Connection Status */
|
---|
368 | pre_mux_id_ptn = mux_id_ptn;
|
---|
369 |
|
---|
370 | if(!WiFi.getMuxCStatus(&mux_id_ptn)) {
|
---|
371 | Serial.println("getMuxCStatus(&mux_id_ptn) : Error!");
|
---|
372 | }
|
---|
373 | else {
|
---|
374 | if (pre_mux_id_ptn != mux_id_ptn) {
|
---|
375 | Serial.print("Connection Status changed! : 0x");
|
---|
376 | Serial.println(mux_id_ptn, HEX);
|
---|
377 | if (mux_id_ptn & 0x01) {
|
---|
378 | mux_id = 0;
|
---|
379 | }
|
---|
380 | if (mux_id_ptn & 0x02) {
|
---|
381 | task1_mux_id = 1;
|
---|
382 | }
|
---|
383 | }
|
---|
384 | }
|
---|
385 |
|
---|
386 | if (mux_id == MUX_NULL) {
|
---|
387 | return;
|
---|
388 | }
|
---|
389 |
|
---|
390 | if (!WiFi.isConnected(mux_id)) {
|
---|
391 | Serial.print("Echo Server : Port is closed: ");
|
---|
392 | Serial.println(mux_id);
|
---|
393 | mux_id = MUX_NULL;
|
---|
394 | return;
|
---|
395 | }
|
---|
396 |
|
---|
397 | if(pixy_blocks != 0) {
|
---|
398 | sprintf(buf, "Detected %d:\n", pixy_blocks);
|
---|
399 | WiFi.send(mux_id, (uint8_t*)buf, strlen(buf));
|
---|
400 | for (int j=0; j<pixy_blocks; j++){
|
---|
401 | WiFi.send(mux_id, (uint8_t*)pixy_buf[j], strlen(pixy_buf[j]));
|
---|
402 | }
|
---|
403 | pixy_blocks = 0;
|
---|
404 | }
|
---|
405 | }
|
---|