sylvie-2024

Unnamed repository; edit this file 'description' to name the repository.
Log | Files | Refs | README | LICENSE

animSkull_PCA9685.ino (15000B)


      1 #include <Wire.h>
      2 #include <Adafruit_PWMServoDriver.h>
      3 
      4 Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();
      5 
      6 #define SERVOMIN  125 //  minimum pulse length count (out of 4096)
      7 #define SERVOMAX  600 // maximum pulse length count (out of 4096)
      8 
      9 uint8_t sg90_1 = 0; // EyeR Y
     10 uint8_t sg90_2 = 1; // EyeL Y
     11 uint8_t sg90_3 = 2; // EyeR X
     12 uint8_t sg90_4 = 3; // EyeL X
     13 
     14 uint8_t sg90_1b = 4;
     15 uint8_t sg90_2b = 5;
     16 uint8_t sg90_3b = 6;
     17 uint8_t sg90_4b = 7;
     18 
     19 uint8_t sg90_brow1 = 8;
     20 uint8_t sg90_brow2 = 9;
     21 
     22 uint8_t sg90_lip = 10;
     23 uint8_t sg90_corner1 = 11;
     24 uint8_t sg90_corner2 = 15;
     25 
     26 uint8_t sg90_jaw = 13;
     27 uint8_t sg90_jaw2 = 14;
     28 
     29 int offset_lid_top_right = -3;
     30 int offset_lid_top_left = 38;
     31 
     32 int offset_lid_bottom_right = -10;
     33 int offset_lid_bottom_left = 35;
     34 
     35 int offset_right_y = 5;
     36 int offset_right_x = 25;
     37 
     38 int offset_left_y = 17;
     39 int offset_left_x = -30;
     40 
     41 int offset_brow1 = -20;
     42 int offset_brow2 = 20;
     43 
     44 int offset_lip = -22;
     45 int offset_corner1 = -14;
     46 int offset_corner2 = 14;
     47 
     48 int offset_jaw = 15;
     49 int offset_jaw2 = 15;
     50 
     51 unsigned long previousTime = 0;  // Previous time the eyes blinked
     52 unsigned long interval = 10000;  // Time interval between blinking
     53 
     54 int angleToPulse(int ang) {
     55   int pulse = map(ang, 0, 180, SERVOMIN, SERVOMAX); // map angle of 0 to 180 to Servo min and Servo max
     56   return pulse;
     57 }
     58 
     59 void move_eyes (int eye_ry, int eye_ly, int eye_rx, int eye_lx) {
     60   pwm.setPWM(sg90_1, 0, angleToPulse(eye_ry + offset_right_y));
     61   pwm.setPWM(sg90_2, 0, angleToPulse(eye_ly + offset_left_y));
     62 
     63   pwm.setPWM(sg90_3, 0, angleToPulse(eye_rx + offset_right_x));
     64   pwm.setPWM(sg90_4, 0, angleToPulse(eye_lx + offset_left_x));  
     65 }
     66 
     67 void move_lids (int lid_tr, int lid_tl, int lid_br, int lid_bl) {
     68   pwm.setPWM(sg90_1b, 0, angleToPulse(lid_tr + offset_lid_top_right));
     69   pwm.setPWM(sg90_2b, 0, angleToPulse(lid_tl + offset_lid_top_left));
     70 
     71   pwm.setPWM(sg90_3b, 0, angleToPulse(lid_br + offset_lid_bottom_right));
     72   pwm.setPWM(sg90_4b, 0, angleToPulse(lid_bl + offset_lid_bottom_left));  
     73 }
     74 
     75 void move_face (int brow1, int brow2, int lip, int corner1, int corner2, int jaw, int jaw2) {
     76   pwm.setPWM(sg90_brow1, 0, angleToPulse(brow1 + offset_brow1));
     77   pwm.setPWM(sg90_brow2, 0, angleToPulse(brow2 + offset_brow2));
     78 
     79   pwm.setPWM(sg90_lip, 0, angleToPulse(lip + offset_lip));
     80   pwm.setPWM(sg90_corner1, 0, angleToPulse(corner1 + offset_corner1));
     81   pwm.setPWM(sg90_corner2, 0, angleToPulse(corner2 + offset_corner2));
     82 
     83   pwm.setPWM(sg90_jaw, 0, angleToPulse(jaw + offset_jaw));
     84   pwm.setPWM(sg90_jaw2, 0, angleToPulse(jaw2 + offset_jaw2));  
     85 }
     86 
     87 void setup() {
     88   pwm.begin();
     89   pwm.setPWMFreq(60);  // Analog servos run at ~60 Hz updates
     90 
     91   move_eyes(90, 90, 90, 90);
     92   move_lids(90, 90, 90, 90);
     93   move_face(90, 90, 90, 90, 90, 90, 90);
     94 
     95   Serial.begin(9600);
     96   Serial.setTimeout(10);
     97 
     98   // Start the I2C Bus as Master
     99   Wire.begin();
    100 }
    101 
    102 long servoState = 0;
    103 int  mouthState = 0;
    104 
    105 ///////////////////////////////////
    106 // Facial animation sets (Start) //
    107 ///////////////////////////////////
    108 
    109 void neutral_reset () {
    110   move_eyes(90, 90, 90, 90);
    111   move_lids(90, 90, 90, 90);
    112   move_face(90, 90, 90, 90, 90, 90, 90);
    113 
    114   if (mouthState == 1 || mouthState == 2) {
    115     move_face(90, 90, 90, 90, 90, 100, 80);	  
    116     delay(30);
    117     move_face(90, 90, 90, 90, 90, 95, 85);    
    118     delay(30);
    119     move_face(90, 90, 90, 90, 90, 92, 88);      
    120     delay(30);
    121     move_face(90, 90, 90, 90, 90, 88, 92);               
    122     delay(30);          
    123   }
    124   move_face(90, 90, 90, 90, 90, 90, 90);  
    125 
    126   mouthState = 0;  
    127 }
    128 
    129 void blink_eyes() {
    130   move_lids(57, 123, 100, 80);
    131   delay(100);
    132   move_lids(90, 90, 90, 90);
    133   move_eyes(90, 90, 90, 90);
    134 }
    135 
    136 void chatter(int rounds1=2, int rounds2=4, bool to_smile=true) {
    137   for (int i=0; i<rounds1; i++) {
    138     Wire.beginTransmission(0x10);
    139     Wire.write(50);
    140     Wire.endTransmission();   
    141 
    142     move_eyes(95, 85, 90, 90);
    143     move_lids(93, 87, 95, 85);
    144     
    145     for (int j=0; j<rounds2; j++) {
    146                    
    147       delay(50);
    148       move_face(90,90,90,90,90,97,83);                     
    149       delay(50);
    150       move_face(90,90,90,90,90,100,80);         
    151       delay(50);
    152       move_face(90,90,90,90,90,105,75);              
    153       delay(50);
    154       move_face(90,90,90,80,100,105,75);         
    155       delay(50);
    156       move_face(100,80,90,80,100,105,75);           
    157       delay(50);
    158       move_face(100,80,95,80,100,105,75);       
    159       delay(20);
    160       move_face(100,80,105,80,100,105,75);                
    161       
    162       delay(100);
    163       
    164       move_face(90,90,90,90,90,100,80);
    165       delay(50);
    166       move_face(90,90,90,90,90,95,85);       
    167       delay(30);
    168       move_face(90,90,90,90,90,92,88);        
    169       delay(30);
    170       move_face(90,90,90,90,90,88,92);                  
    171       delay(30);          
    172       move_face(90,90,90,90,90,90,90); 
    173       
    174       delay(50);
    175     } 
    176     Wire.beginTransmission(0x10);
    177     Wire.write(51);
    178     Wire.endTransmission();  
    179     
    180     move_eyes(90,90,90,90);
    181     move_lids(90,90,90,90);   
    182     delay(350);
    183   }   
    184   move_lids(60,120,100,80); 
    185   delay(100);
    186   move_lids(90,90,90,90);  
    187 
    188   int randexpress = random(2);
    189 
    190   if (randexpress == 0){
    191     if (to_smile==true){
    192       smile();
    193     }else{
    194       move_eyes(90,90,75,110);
    195       delay(1000);      
    196     }
    197   } else if (randexpress == 1) {
    198 	  move_eyes(75,100,110,75);
    199     move_lids(80,100,75,105);
    200     delay(1000);
    201   } else if (randexpress == 2) {
    202 	  move_eyes(75,100,75,110);
    203     move_lids(80,100,75,105);
    204     delay(1000);
    205   }
    206 }
    207 
    208 void nod_head() {
    209   move_lids(60,120,100,80);	
    210   delay(100);
    211   Wire.beginTransmission(0x10);
    212   Wire.write(54);
    213   Wire.endTransmission();    
    214   delay(300);  
    215   Wire.beginTransmission(0x10);
    216   Wire.write(55);
    217   Wire.endTransmission();    
    218   delay(300);
    219   move_lids(90,90,90,90);
    220   move_eyes(90,90,90,90);
    221   delay(1000);
    222 }
    223 
    224 void smile() {
    225   move_face(90, 90, 90, 110, 70, 90, 90);
    226   delay(30);
    227   move_face(90, 90, 90, 120, 60, 95, 85);
    228   delay(30);
    229   move_face(90, 90, 90, 130, 50, 97, 83);
    230   delay(30);
    231   move_face(100, 80, 90, 150, 30, 97, 83);
    232   move_lids(87, 93, 103, 77);
    233   move_face(100, 80, 100, 150, 30, 100, 80);
    234   delay(20);
    235   move_face(95, 85, 100, 150, 30, 100, 80);
    236   delay(2000);
    237   move_face(95, 85, 100, 150, 30, 100, 80);
    238   delay(30);
    239   move_face(95, 85, 100, 130, 50, 97, 83);
    240   delay(30);
    241   move_face(95, 85, 100, 120, 60, 95, 85);  
    242   delay(30);
    243   move_face(95, 85, 100, 110, 70, 90, 90);        
    244   move_face(95, 85, 100, 80, 100, 90, 90);
    245   
    246   neutral_reset();
    247 }
    248 
    249 void thinking_eyes() {
    250   blink_eyes();
    251   delay(300);
    252   move_eyes(100,80,90,90);
    253   move_lids(95,85,100,80);
    254   delay(200);
    255   move_eyes(100,80,75,110);
    256   delay(1000);
    257 }
    258 
    259 /////////////////////////////////
    260 // Facial animation sets (End) //
    261 /////////////////////////////////
    262 
    263 void loop() {
    264   // while (Serial.available() == 0) {}
    265 
    266   unsigned long currentTime = millis();  // Get the current time
    267 
    268   // Check if the time interval has elapsed
    269   if (currentTime - previousTime >= interval) {
    270     previousTime = currentTime;  // Update the previous time
    271 
    272     // Generate a random variation of 5 seconds (5000 milliseconds)
    273     unsigned long variation = random(5000);
    274 
    275     // Calculate the next interval between LED state changes (10-15 seconds + random variation)
    276     interval = 10000 + variation;
    277 
    278     // Toggle the blink state
    279     blink_eyes();
    280   }
    281 
    282   // Handle the Serial commands
    283   if (Serial.available() > 0) {  
    284     servoState = Serial.parseInt();
    285 
    286     Serial.print("Received command: ");
    287     Serial.println(servoState);
    288     
    289     if (servoState > 0) {
    290   
    291       if (servoState == 2) {
    292 		move_lids(57,123,100,80);
    293       }
    294       else if (servoState == 3) {
    295 		move_lids(90,90,90,90);
    296       }
    297       else if (servoState == 4) {
    298 		move_lids(80,100,100,80);
    299       }
    300       else if (servoState == 5) {
    301 		move_lids(90,90,90,90);
    302       }
    303       else if (servoState == 6) {
    304         move_eyes(100,80,90,90);
    305         move_lids(95,85,100,80);
    306       }
    307       else if (servoState == 7) {
    308         move_eyes(75,100,90,90);
    309         move_lids(80,100,75,105);		  
    310       }
    311       else if (servoState == 8) {
    312 		//move_eyes(90,90,75,110);
    313     pwm.setPWM(sg90_3, 0, angleToPulse(75 + offset_right_x));
    314     pwm.setPWM(sg90_4, 0, angleToPulse(110 + offset_left_x));     
    315       }
    316       else if (servoState == 9) {
    317 		//move_eyes(90,90,110,75);
    318     pwm.setPWM(sg90_3, 0, angleToPulse(110 + offset_right_x));
    319     pwm.setPWM(sg90_4, 0, angleToPulse(75 + offset_left_x));      		  
    320       }
    321       else if (servoState == 11) {
    322 		move_lids(60,90,100,90);
    323       }
    324       else if (servoState == 12) {
    325 		move_lids(90,120,90,80);		  
    326       }
    327       else if (servoState == 13) {
    328         Wire.beginTransmission(0x10);
    329         Wire.write(54);
    330         Wire.endTransmission();
    331       }
    332       else if (servoState == 14) {
    333         Wire.beginTransmission(0x10);
    334         Wire.write(55);
    335         Wire.endTransmission();
    336       }
    337       else if (servoState == 15) {
    338         Wire.beginTransmission(0x20);
    339         Wire.write(50);
    340         Wire.endTransmission();
    341       }
    342       else if (servoState == 16) {
    343         Wire.beginTransmission(0x20);
    344         Wire.write(51);
    345         Wire.endTransmission();
    346       }
    347       else if (servoState == 17) {
    348         pwm.setPWM(sg90_brow1, 0, angleToPulse(70 + offset_brow1));
    349         pwm.setPWM(sg90_brow2, 0, angleToPulse(105 + offset_brow2));
    350       }
    351       else if (servoState == 18) {
    352         pwm.setPWM(sg90_brow1, 0, angleToPulse(105 + offset_brow1));
    353         pwm.setPWM(sg90_brow2, 0, angleToPulse(75 + offset_brow2));
    354       }
    355       else if (servoState == 19) {
    356         pwm.setPWM(sg90_lip, 0, angleToPulse(110 + offset_lip));
    357       }
    358       else if (servoState == 20) {
    359         pwm.setPWM(sg90_lip, 0, angleToPulse(90 + offset_lip));
    360       }
    361       else if (servoState == 21) {
    362         pwm.setPWM(sg90_corner1, 0, angleToPulse(60 + offset_corner1));
    363         pwm.setPWM(sg90_corner2, 0, angleToPulse(120 + offset_corner2));
    364         pwm.setPWM(sg90_lip, 0, angleToPulse(90 + offset_lip));
    365   
    366         pwm.setPWM(sg90_1b, 0, angleToPulse(90 + offset_lid_top_right));
    367         pwm.setPWM(sg90_2b, 0, angleToPulse(90 + offset_lid_top_left));
    368         pwm.setPWM(sg90_3b, 0, angleToPulse(90 + offset_lid_bottom_right));
    369         pwm.setPWM(sg90_4b, 0, angleToPulse(90 + offset_lid_bottom_left));  
    370   
    371         pwm.setPWM(sg90_brow1, 0, angleToPulse(80 + offset_brow1));
    372         pwm.setPWM(sg90_brow2, 0, angleToPulse(100 + offset_brow2));  
    373                              
    374         pwm.setPWM(sg90_lip, 0, angleToPulse(90 + offset_lip));
    375   
    376         pwm.setPWM(sg90_jaw, 0, angleToPulse(95 + offset_jaw));
    377         pwm.setPWM(sg90_jaw2, 0, angleToPulse(85 + offset_jaw2));      
    378       }
    379       else if (servoState == 22) {
    380         pwm.setPWM(sg90_corner1, 0, angleToPulse(110 + offset_corner1));
    381         pwm.setPWM(sg90_corner2, 0, angleToPulse(70 + offset_corner2)); 
    382         delay(30);
    383         pwm.setPWM(sg90_corner1, 0, angleToPulse(130 + offset_corner1));
    384         pwm.setPWM(sg90_corner2, 0, angleToPulse(50 + offset_corner2)); 
    385         delay(30);
    386         pwm.setPWM(sg90_corner1, 0, angleToPulse(150 + offset_corner1));
    387         pwm.setPWM(sg90_corner2, 0, angleToPulse(30 + offset_corner2)); 
    388   
    389         pwm.setPWM(sg90_1b, 0, angleToPulse(87 + offset_lid_top_right));
    390         pwm.setPWM(sg90_2b, 0, angleToPulse(93 + offset_lid_top_left));
    391         pwm.setPWM(sg90_3b, 0, angleToPulse(100 + offset_lid_bottom_right));
    392         pwm.setPWM(sg90_4b, 0, angleToPulse(82 + offset_lid_bottom_left));      
    393   
    394         pwm.setPWM(sg90_brow1, 0, angleToPulse(100 + offset_brow1));
    395         pwm.setPWM(sg90_brow2, 0, angleToPulse(80 + offset_brow2));  
    396   
    397         pwm.setPWM(sg90_lip, 0, angleToPulse(97 + offset_lip)); 
    398   
    399         pwm.setPWM(sg90_jaw, 0, angleToPulse(100 + offset_jaw));
    400         pwm.setPWM(sg90_jaw2, 0, angleToPulse(80 + offset_jaw2));                        
    401       }
    402       else if (servoState == 23) {
    403         pwm.setPWM(sg90_jaw, 0, angleToPulse(100 + offset_jaw));
    404         pwm.setPWM(sg90_jaw2, 0, angleToPulse(80 + offset_jaw2));
    405         delay(30);
    406         pwm.setPWM(sg90_jaw, 0, angleToPulse(105 + offset_jaw));
    407         pwm.setPWM(sg90_jaw2, 0, angleToPulse(75 + offset_jaw2));    
    408         delay(30);
    409         pwm.setPWM(sg90_jaw, 0, angleToPulse(110 + offset_jaw));
    410         pwm.setPWM(sg90_jaw2, 0, angleToPulse(70 + offset_jaw2));      
    411         delay(50);
    412         pwm.setPWM(sg90_corner1, 0, angleToPulse(80 + offset_corner1));
    413         pwm.setPWM(sg90_corner2, 0, angleToPulse(100 + offset_corner2)); 
    414         delay(50);
    415         pwm.setPWM(sg90_brow1, 0, angleToPulse(100 + offset_brow1));
    416         pwm.setPWM(sg90_brow2, 0, angleToPulse(80 + offset_brow2));
    417         delay(50);
    418         pwm.setPWM(sg90_lip, 0, angleToPulse(95 + offset_lip));
    419   
    420         mouthState = 2;
    421       }
    422       else if (servoState == 24) {
    423         if (mouthState == 2) {
    424           pwm.setPWM(sg90_jaw, 0, angleToPulse(108 + offset_jaw));
    425           pwm.setPWM(sg90_jaw2, 0, angleToPulse(72 + offset_jaw2));      
    426           delay(30);
    427           pwm.setPWM(sg90_jaw, 0, angleToPulse(105 + offset_jaw));
    428           pwm.setPWM(sg90_jaw2, 0, angleToPulse(75 + offset_jaw2));      
    429           delay(30);        
    430           pwm.setPWM(sg90_jaw, 0, angleToPulse(100 + offset_jaw));
    431           pwm.setPWM(sg90_jaw2, 0, angleToPulse(80 + offset_jaw2));             
    432         }
    433         else {
    434           pwm.setPWM(sg90_jaw, 0, angleToPulse(95 + offset_jaw));
    435           pwm.setPWM(sg90_jaw2, 0, angleToPulse(85 + offset_jaw2)); 
    436           delay(30);        
    437           pwm.setPWM(sg90_jaw, 0, angleToPulse(100 + offset_jaw));
    438           pwm.setPWM(sg90_jaw2, 0, angleToPulse(80 + offset_jaw2));     
    439         }
    440         
    441         pwm.setPWM(sg90_corner1, 0, angleToPulse(90 + offset_corner1));
    442         pwm.setPWM(sg90_corner2, 0, angleToPulse(90 + offset_corner2)); 
    443         
    444         pwm.setPWM(sg90_brow1, 0, angleToPulse(90 + offset_brow1));
    445         pwm.setPWM(sg90_brow2, 0, angleToPulse(90 + offset_brow2));
    446   
    447         pwm.setPWM(sg90_lip, 0, angleToPulse(90 + offset_lip));     
    448         
    449         mouthState = 1;            
    450       }
    451       else if (servoState == 25) {
    452         chatter(1);        	
    453   	  }
    454       else if (servoState == 26) {
    455         blink_eyes();  
    456       }
    457       else if (servoState == 10) {
    458           neutral_reset();
    459       }
    460       else if (servoState == 27) {
    461         Wire.beginTransmission(0x10);
    462         Wire.write(50);
    463         Wire.endTransmission();
    464       }
    465       else if (servoState == 28) {
    466         Wire.beginTransmission(0x10);
    467         Wire.write(51);
    468         Wire.endTransmission();
    469       }    
    470       else if (servoState == 29) {
    471         chatter(2);          
    472       }
    473       else if (servoState == 30) {
    474         chatter(1, 2);  
    475       } 
    476       else if (servoState == 31) {
    477         chatter(2, 2);  
    478       }             
    479       else if (servoState == 32) {
    480         smile();  
    481       }    
    482       else if (servoState == 33) {
    483         chatter(1, 4, false);          
    484       }      
    485       else if (servoState == 34) {
    486         nod_head();        
    487       }
    488       else if (servoState == 35) {
    489         thinking_eyes();
    490       }  
    491     }
    492   }
    493 }