diff --git a/serial/serial.ino b/serial/serial.ino
new file mode 100644
index 0000000000000000000000000000000000000000..3e4958153d41e425246d7c3b976b508de94e1626
--- /dev/null
+++ b/serial/serial.ino
@@ -0,0 +1,142 @@
+#include <Servo.h>
+
+// Create servo objects
+Servo index_finger;
+Servo middle_finger;
+Servo ring_finger;
+Servo pinky_finger;
+
+// Servo pins - adjust according to your Arduino connections
+const int INDEX_PIN = 2;
+const int MIDDLE_PIN = 3;
+const int RING_PIN = 4;
+const int PINKY_PIN = 5;
+
+// Current positions of each finger
+int index_pos = 90;
+int middle_pos = 90;
+int ring_pos = 90;
+int pinky_pos = 90;
+
+// Buffer for incoming serial data
+String inputBuffer = "";
+bool commandReady = false;
+
+void setup() {
+  // Initialize serial communication at 9600 bps
+  Serial.begin(9600);
+  while (!Serial) {
+    ; // Wait for serial port to connect (needed for native USB)
+  }
+  
+  // Attach servos to their pins
+  index_finger.attach(INDEX_PIN);
+  middle_finger.attach(MIDDLE_PIN);
+  ring_finger.attach(RING_PIN);
+  pinky_finger.attach(PINKY_PIN);
+  
+  // Initialize all fingers to neutral position
+  index_finger.write(index_pos);
+  middle_finger.write(middle_pos);
+  ring_finger.write(ring_pos);
+  pinky_finger.write(pinky_pos);
+  
+  // Show startup message
+  Serial.println("InMoov Hand Controller Ready");
+  Serial.println("Format: [finger]:[angle]");
+  Serial.println("Example: index:180");
+}
+
+void loop() {
+  // Check for incoming serial data
+  while (Serial.available() > 0) {
+    // Read incoming byte
+    char incomingByte = Serial.read();
+    
+    // Add to buffer if not end of line
+    if (incomingByte != '\n') {
+      inputBuffer += incomingByte;
+    } else {
+      // End of line, set flag to process command
+      commandReady = true;
+    }
+  }
+  
+  // Process command if ready
+  if (commandReady) {
+    Serial.print("Received command: ");
+    Serial.println(inputBuffer);
+    
+    processCommand(inputBuffer);
+    
+    // Clear buffer and reset flag
+    inputBuffer = "";
+    commandReady = false;
+  }
+  
+  // Small delay to avoid hogging CPU
+  delay(10);
+}
+
+void processCommand(String command) {
+  // Parse command in format: "finger:angle"
+  int colonIndex = command.indexOf(':');
+  
+  if (colonIndex != -1) {
+    String finger = command.substring(0, colonIndex);
+    String angleStr = command.substring(colonIndex + 1);
+    int angle = angleStr.toInt();
+    
+    // Constrain angle to valid range
+    angle = constrain(angle, 0, 180);
+    
+    // Update finger position based on command
+    if (finger == "index") {
+      index_pos = angle;
+      index_finger.write(index_pos);
+      Serial.print("Index finger moved to: ");
+      Serial.println(angle);
+    }
+    else if (finger == "middle") {
+      middle_pos = angle;
+      middle_finger.write(middle_pos);
+      Serial.print("Middle finger moved to: ");
+      Serial.println(angle);
+    }
+    else if (finger == "ring") {
+      ring_pos = angle;
+      ring_finger.write(ring_pos);
+      Serial.print("Ring finger moved to: ");
+      Serial.println(angle);
+    }
+    else if (finger == "pinky") {
+      pinky_pos = angle;
+      pinky_finger.write(pinky_pos);
+      Serial.print("Pinky finger moved to: ");
+      Serial.println(angle);
+    }
+    else if (finger == "all") {
+      // Move all fingers to the same position
+      index_pos = angle;
+      middle_pos = angle;
+      ring_pos = angle;
+      pinky_pos = angle;
+      
+      index_finger.write(index_pos);
+      middle_finger.write(middle_pos);
+      ring_finger.write(ring_pos);
+      pinky_finger.write(pinky_pos);
+      
+      Serial.print("All fingers moved to: ");
+      Serial.println(angle);
+    }
+    else {
+      Serial.print("Unknown finger command: ");
+      Serial.println(finger);
+    }
+  } else {
+    Serial.print("Invalid command format. Received: ");
+    Serial.println(command);
+    Serial.println("Format should be: finger:angle");
+  }
+}
\ No newline at end of file