Arduino Sensors & Actuators

Progressive Learning: Servo, Water Sensor, DC Motor & Integration

Introduction

This tutorial teaches Arduino programming through progressive examples, starting with individual components and building up to a complete integrated system. Each example is standalone and ready to run.

📚 Learning Approach
  • Example 1: Servo motor control - learn basic actuator programming
  • Example 2: Water level sensor - learn analog input and data processing
  • Example 3: DC motor with L298N - learn motor driver control and PWM
  • Example 4: Complete integration - combine all components into automated system

Required Components (All Examples)

Arduino Uno

Main microcontroller board

Servo Motor (SG90)

180° positioning servo

Water Level Sensor

Analog liquid detector

DC Motor + L298N

Motor and driver module

12V Power Supply

For motor driver (1A min)

Breadboard & Wires

For prototyping

Example 1: Servo Motor Control

1Start with the simplest actuator - a servo motor. Learn positioning, sweeping, and angle control.

Wiring Diagram - Servo Only

ARDUINO UNO GND 5V D9 SERVO MOTOR GND VCC SIG

Pin Connections

Servo Pin Arduino Pin Wire Color
GND (Brown/Black) GND Black/Brown
VCC (Red) 5V Red
Signal (Orange/Yellow) D9 Orange/Yellow/White

Arduino Code - Servo Example

example_1_servo.ino
/*
 * Example 1: Servo Motor Control
 * Learn: Basic servo positioning and sweeping motion
 */

#include <Servo.h>

// Create servo object
Servo myServo;

// Pin definition
const int SERVO_PIN = 9;

void setup() {
  // Initialize serial communication
  Serial.begin(9600);
  
  // Attach servo to pin 9
  myServo.attach(SERVO_PIN);
  
  Serial.println("=== Servo Motor Test ===");
  Serial.println("Starting sweep motion...");
}

void loop() {
  // Sweep from 0 to 180 degrees
  Serial.println("Sweeping 0° to 180°");
  for (int angle = 0; angle <= 180; angle += 5) {
    myServo.write(angle);
    Serial.print("Position: ");
    Serial.print(angle);
    Serial.println("°");
    delay(50);  // Wait for servo to reach position
  }
  
  delay(500);  // Pause at 180°
  
  // Sweep back from 180 to 0 degrees
  Serial.println("Sweeping 180° to 0°");
  for (int angle = 180; angle >= 0; angle -= 5) {
    myServo.write(angle);
    Serial.print("Position: ");
    Serial.print(angle);
    Serial.println("°");
    delay(50);
  }
  
  delay(500);  // Pause at 0°
  
  Serial.println("---");
}
💡 What You'll Learn
  • servo.attach(pin): Initializes servo on specified PWM pin
  • servo.write(angle): Positions servo at angle (0-180 degrees)
  • Sweep motion: Using for loops to create smooth movement
  • delay(): Giving servo time to physically reach position

Expected Behavior

The servo will continuously sweep from 0° to 180° and back, with position updates printed to Serial Monitor every 50ms.

Example 2: Water Level Sensor

2Learn analog input by reading a water level sensor. Understand ADC conversion and data mapping.

Wiring Diagram - Water Sensor Only

ARDUINO UNO GND 5V A0 WATER LEVEL SENSOR S + -

Pin Connections

Sensor Pin Arduino Pin Function
- (GND) GND Ground
+ (VCC) 5V Power (5V)
S (Signal) A0 Analog output

Arduino Code - Water Sensor Example

example_2_water_sensor.ino
/*
 * Example 2: Water Level Sensor
 * Learn: Analog input, ADC conversion, data mapping
 */

// Pin definition
const int WATER_SENSOR_PIN = A0;

// Variables
int sensorValue = 0;       // Raw ADC reading (0-1023)
int waterPercentage = 0;   // Converted to percentage

// Calibration values (adjust for your sensor)
const int SENSOR_MIN = 0;    // Value when sensor is dry
const int SENSOR_MAX = 700;  // Value when fully submerged

void setup() {
  // Initialize serial communication
  Serial.begin(9600);
  
  Serial.println("=== Water Level Sensor Test ===");
  Serial.println("Reading sensor values...");
  Serial.println();
}

void loop() {
  // Read analog value from sensor (0-1023)
  sensorValue = analogRead(WATER_SENSOR_PIN);
  
  // Convert to percentage (0-100%)
  waterPercentage = map(sensorValue, SENSOR_MIN, SENSOR_MAX, 0, 100);
  
  // Constrain to valid range
  waterPercentage = constrain(waterPercentage, 0, 100);
  
  // Display results
  Serial.print("Raw Value: ");
  Serial.print(sensorValue);
  Serial.print("  |  Water Level: ");
  Serial.print(waterPercentage);
  Serial.print("%  |  ");
  
  // Status indicator
  if (waterPercentage < 20) {
    Serial.println("Status: LOW ⬇️");
  } else if (waterPercentage < 50) {
    Serial.println("Status: MEDIUM ➡️");
  } else if (waterPercentage < 80) {
    Serial.println("Status: HIGH ⬆️");
  } else {
    Serial.println("Status: FULL ✓");
  }
  
  // Update every second
  delay(1000);
}
💡 What You'll Learn
  • analogRead(): Reads voltage on analog pins, returns 0-1023 (10-bit ADC)
  • map(): Converts values from one range to another (sensor reading to percentage)
  • constrain(): Limits value within specified range to prevent errors
  • Calibration: Adjusting SENSOR_MIN/MAX for accurate readings

Calibration Instructions

🔧 How to Calibrate
  1. Upload code with SENSOR_MIN=0, SENSOR_MAX=1023
  2. Keep sensor completely dry, note the raw value (this is your SENSOR_MIN)
  3. Fully submerge sensor in water, note the raw value (this is your SENSOR_MAX)
  4. Update the constants in code with your measured values
  5. Re-upload and test - percentage should now be accurate

Example 3: DC Motor Control

3Control a DC motor using the L298N motor driver. Learn PWM speed control and direction changes.

Wiring Diagram - DC Motor Only

ARDUINO UNO GND D5 D6 D7 L298N DRIVER ENA IN1 IN2 GND MOTOR OUT1 OUT2 12V POWER 1A min +12V GND

Pin Connections

L298N Pin Arduino Pin Function
ENA D5 PWM speed control (0-255)
IN1 D6 Direction control 1
IN2 D7 Direction control 2
GND GND Common ground
+12V External 12V supply Motor power
GND (Power) External supply GND Power ground
⚠️ Important Safety Notes
  • Remove the 5V jumper on L298N when using 12V supply
  • Ensure ENA jumper is in place for PWM control
  • Connect Arduino GND to L298N GND (common ground required)
  • Never power motor from Arduino 5V pin
  • External power supply must provide at least 1A current

Arduino Code - DC Motor Example

example_3_dc_motor.ino
/*
 * Example 3: DC Motor Control with L298N
 * Learn: Motor driver operation, PWM speed control, direction changes
 */

// Pin definitions
const int MOTOR_ENA = 5;  // PWM speed control pin
const int MOTOR_IN1 = 6;  // Direction pin 1
const int MOTOR_IN2 = 7;  // Direction pin 2

void setup() {
  // Initialize serial communication
  Serial.begin(9600);
  
  // Configure motor driver pins as outputs
  pinMode(MOTOR_ENA, OUTPUT);
  pinMode(MOTOR_IN1, OUTPUT);
  pinMode(MOTOR_IN2, OUTPUT);
  
  // Start with motor stopped
  stopMotor();
  
  Serial.println("=== DC Motor Control Test ===");
  Serial.println("Testing speed and direction...");
  Serial.println();
}

void loop() {
  // Test 1: Forward at different speeds
  Serial.println("Forward - Low Speed (100 PWM)");
  runMotorForward(100);
  delay(3000);
  
  Serial.println("Forward - Medium Speed (180 PWM)");
  runMotorForward(180);
  delay(3000);
  
  Serial.println("Forward - Full Speed (255 PWM)");
  runMotorForward(255);
  delay(3000);
  
  // Stop
  Serial.println("Stopping...");
  stopMotor();
  delay(2000);
  
  // Test 2: Reverse at different speeds
  Serial.println("Reverse - Low Speed (100 PWM)");
  runMotorReverse(100);
  delay(3000);
  
  Serial.println("Reverse - Full Speed (255 PWM)");
  runMotorReverse(255);
  delay(3000);
  
  // Stop
  Serial.println("Stopping...");
  stopMotor();
  delay(2000);
  
  Serial.println("--- Cycle Complete ---\n");
  delay(1000);
}

// Function: Run motor forward at specified speed
void runMotorForward(int speed) {
  // Set direction: IN1 = HIGH, IN2 = LOW
  digitalWrite(MOTOR_IN1, HIGH);
  digitalWrite(MOTOR_IN2, LOW);
  
  // Set speed (0-255)
  analogWrite(MOTOR_ENA, speed);
}

// Function: Run motor in reverse at specified speed
void runMotorReverse(int speed) {
  // Set direction: IN1 = LOW, IN2 = HIGH
  digitalWrite(MOTOR_IN1, LOW);
  digitalWrite(MOTOR_IN2, HIGH);
  
  // Set speed (0-255)
  analogWrite(MOTOR_ENA, speed);
}

// Function: Stop motor
void stopMotor() {
  // Set both direction pins LOW
  digitalWrite(MOTOR_IN1, LOW);
  digitalWrite(MOTOR_IN2, LOW);
  
  // Set speed to 0
  analogWrite(MOTOR_ENA, 0);
}
💡 What You'll Learn
  • H-Bridge Control: IN1 and IN2 determine motor direction through transistor switching
  • PWM Speed Control: analogWrite(ENA, 0-255) varies average voltage to control speed
  • Direction Logic:
    • IN1=HIGH, IN2=LOW → Forward
    • IN1=LOW, IN2=HIGH → Reverse
    • Both LOW → Stop
  • Functions: Organizing code into reusable motor control functions

Expected Behavior

The motor will run through a test sequence: forward at increasing speeds, stop, reverse at different speeds, then repeat. Each step is announced via Serial Monitor.

Example 4: Complete System Integration

4Combine all components into an intelligent water tank management system with automated pump control.

Complete Wiring Diagram

ARDUINO UNO GND 5V A0 D9 D5 D6 D7 L298N DRIVER ENA IN1 IN2 GND PUMP OUT1 OUT2 12V SERVO WATER LEVEL

Arduino Code - Full System Integration

example_4_complete_system.ino
/*
 * Example 4: Complete Water Tank Management System
 * Integrates: Water Level Sensor + DC Motor Pump + Servo Valve
 * 
 * System Logic:
 * - Monitors water level continuously
 * - Activates pump when level drops below 30%
 * - Runs pump at reduced speed between 30-80%
 * - Stops pump when level exceeds 80%
 * - Servo indicates water level position (0° = empty, 180° = full)
 */

#include <Servo.h>

// ========== PIN DEFINITIONS ==========
// Water Level Sensor
const int WATER_SENSOR_PIN = A0;

// Servo Motor (Valve)
const int SERVO_PIN = 9;

// DC Motor (Pump) via L298N
const int MOTOR_ENA = 5;   // PWM speed control
const int MOTOR_IN1 = 6;   // Direction 1
const int MOTOR_IN2 = 7;   // Direction 2

// ========== OBJECTS ==========
Servo valveServo;

// ========== VARIABLES ==========
int waterLevel = 0;          // Raw sensor value (0-1023)
int waterPercentage = 0;     // Water level percentage (0-100%)
int valvePosition = 0;       // Servo angle (0-180°)
int pumpSpeed = 0;           // Motor PWM (0-255)
bool pumpRunning = false;    // Pump state

// ========== CONFIGURATION ==========
// Sensor calibration (adjust for your sensor)
const int SENSOR_MIN = 0;      // Dry reading
const int SENSOR_MAX = 700;    // Submerged reading

// Control thresholds
const int LEVEL_LOW = 30;      // Start pump below 30%
const int LEVEL_HIGH = 80;     // Stop pump above 80%

// Motor speeds
const int PUMP_SPEED_FULL = 255;   // Maximum speed
const int PUMP_SPEED_LOW = 150;    // Reduced speed

void setup() {
  // Initialize serial for monitoring
  Serial.begin(9600);
  
  // Configure motor pins
  pinMode(MOTOR_ENA, OUTPUT);
  pinMode(MOTOR_IN1, OUTPUT);
  pinMode(MOTOR_IN2, OUTPUT);
  
  // Initialize servo
  valveServo.attach(SERVO_PIN);
  
  // Start with safe states
  stopPump();
  valveServo.write(0);
  
  // Startup message
  Serial.println("=========================================");
  Serial.println("  WATER TANK MANAGEMENT SYSTEM v1.0    ");
  Serial.println("=========================================");
  Serial.println("System Status: ONLINE");
  Serial.println("Monitoring water level...");
  Serial.println();
  
  delay(2000);
}

void loop() {
  // ========== READ WATER LEVEL ==========
  waterLevel = analogRead(WATER_SENSOR_PIN);
  waterPercentage = map(waterLevel, SENSOR_MIN, SENSOR_MAX, 0, 100);
  waterPercentage = constrain(waterPercentage, 0, 100);
  
  // ========== AUTOMATIC PUMP CONTROL ==========
  if (waterPercentage < LEVEL_LOW && !pumpRunning) {
    // Water level is LOW - Start pump at FULL speed
    startPump(PUMP_SPEED_FULL);
    Serial.println("🔵 ACTION: Pump STARTED (Water LOW)");
  } 
  else if (waterPercentage > LEVEL_HIGH && pumpRunning) {
    // Water level is HIGH - Stop pump
    stopPump();
    Serial.println("🟢 ACTION: Pump STOPPED (Water HIGH)");
  }
  else if (waterPercentage >= LEVEL_LOW && waterPercentage <= LEVEL_HIGH && pumpRunning) {
    // Water level in MIDDLE range - Reduce pump speed
    startPump(PUMP_SPEED_LOW);
  }
  
  // ========== VALVE POSITION CONTROL ==========
  // Map water level to servo angle (visual indicator)
  valvePosition = map(waterPercentage, 0, 100, 0, 180);
  valveServo.write(valvePosition);
  
  // ========== DISPLAY STATUS ==========
  Serial.print("📊 Raw: ");
  Serial.print(waterLevel);
  Serial.print(" | Level: ");
  Serial.print(waterPercentage);
  Serial.print("%");
  
  Serial.print(" | Pump: ");
  if (pumpRunning) {
    Serial.print("ON (");
    Serial.print(pumpSpeed);
    Serial.print(" PWM)");
  } else {
    Serial.print("OFF");
  }
  
  Serial.print(" | Valve: ");
  Serial.print(valvePosition);
  Serial.println("°");
  
  // Alert messages
  if (waterPercentage < 20) {
    Serial.println("⚠️  ALERT: Water level CRITICAL!");
  } else if (waterPercentage > 90) {
    Serial.println("⚠️  WARNING: Near maximum capacity!");
  }
  
  Serial.println("----------------------------------------");
  
  // Update every second
  delay(1000);
}

// ========== MOTOR CONTROL FUNCTIONS ==========

void startPump(int speed) {
  // Set direction: Forward (IN1=HIGH, IN2=LOW)
  digitalWrite(MOTOR_IN1, HIGH);
  digitalWrite(MOTOR_IN2, LOW);
  
  // Set speed via PWM
  analogWrite(MOTOR_ENA, speed);
  
  pumpSpeed = speed;
  pumpRunning = true;
}

void stopPump() {
  // Stop motor: Both direction pins LOW
  digitalWrite(MOTOR_IN1, LOW);
  digitalWrite(MOTOR_IN2, LOW);
  
  // Set speed to 0
  analogWrite(MOTOR_ENA, 0);
  
  pumpSpeed = 0;
  pumpRunning = false;
}
🎯 System Features
  • Automatic Operation: Pump activates/deactivates based on water level thresholds
  • Variable Speed: Full speed when low, reduced speed during filling to prevent overshoot
  • Visual Feedback: Servo position indicates current water level (0°-180°)
  • Real-time Monitoring: Complete status displayed via Serial Monitor
  • Safety Alerts: Warnings for critical low or high water levels
  • Hysteresis Control: Separate ON/OFF thresholds prevent rapid cycling

System Behavior

Water Level Pump Status Pump Speed Valve Position
0-30% ON (Starting) 255 PWM (Full) 0°-54°
30-80% ON (Filling) 150 PWM (Reduced) 54°-144°
80-100% OFF 0 PWM (Stopped) 144°-180°

Troubleshooting Guide

Example 1: Servo Issues

🔧 Servo not moving or jittering
  • Check all three wires are properly connected (GND, VCC, Signal)
  • Verify servo is connected to pin 9 (PWM capable)
  • Power servo from external 5V if Arduino can't provide enough current
  • Add small delay after servo.write() command (10-20ms)

Example 2: Water Sensor Issues

🔧 Incorrect or unstable readings
  • Calibrate SENSOR_MIN and SENSOR_MAX values for your specific sensor
  • Clean sensor surface with isopropyl alcohol
  • Use tap water or saltwater for better conductivity (not distilled water)
  • Check for loose wire connections
  • Implement averaging: read 10 times and use average value

Example 3: DC Motor Issues

🔧 Motor not running
  • Verify 12V external power supply is connected and ON
  • Ensure ENA jumper is installed on L298N
  • Remove 5V regulator jumper if using 12V supply
  • Check Arduino GND is connected to L298N GND (common ground)
  • Test motor directly with power supply to confirm it works
  • Verify correct pin connections (ENA to D5, IN1 to D6, IN2 to D7)

Example 4: Integration Issues

🔧 System behaves erratically
  • Check all grounds are connected together (common ground)
  • Ensure external power supply has sufficient current (1A minimum)
  • Separate power for motor from Arduino/sensors
  • Add capacitors: 100-1000µF across motor driver power input
  • Keep motor wires away from sensor signal wires to reduce EMI
  • Review Serial Monitor output to identify which component is failing

General Debugging Tips

🛠️ Systematic Debugging Approach
  1. Test individually: Use Examples 1-3 to verify each component works alone
  2. Check connections: Disconnect power, verify all wiring matches diagrams
  3. Use Serial Monitor: Monitor output to identify exactly what's failing
  4. Measure voltages: Use multimeter to verify 5V and 12V at components
  5. Incremental integration: Add one component at a time to the system
  6. Check power draw: Ensure total current doesn't exceed supply capacity