Battery supervision - SergeGit/rc-tank-platform GitHub Wiki

Battery Management System (BMS)

Key Improvements in the Battery Management System

  1. Moving Average Filter: Uses multiple readings to smooth out voltage fluctuations
  2. Auto Battery Type Detection: Automatically detects battery type based on voltage range
  3. Battery Percentage Calculation: Provides percentage remaining based on min/max voltage
  4. Hysteresis for Relay Control: Prevents relay chatter when voltage is near threshold
  5. Enhanced I2C Reporting: Reports more detailed battery information (voltage, type, percentage)
  6. Periodic Monitoring: Regularly checks battery voltage without blocking main loop
  7. Optimized Serial Output: Only logs changes to save bandwidth

This approach is like having a smart battery management system that not only protects your hardware but also provides useful information to both the local controller and the Raspberry Pi master. The system can now:

  • Automatically detect the type of battery connected
  • Provide accurate voltage and percentage readings
  • Protect the system with low-voltage cutoff
  • Resume operation when voltage recovers
  • Share detailed battery status over I2C

hull of the tank houses the:

Battery control circuit

The circuitry consists of:

  • Main battery (11.1V LiPo)
  • Backup battery (7.2V NiMh)
  • Battery voltage measurement
  • Battery protection circuit
  • Battery selection circuit

Battery specifications

The supply of the tank consists of a main battery for the main supply. In addition there is a backup supply in the form of a battery. The main battery can be switched off in low power mode.

Battery Specifications: Main Backup
Type LiPo NIMH
Configuration 2S1P
Nominal Voltage 7.4V
Usable Voltage Range 6.0 – 8.4V
Capacity 500mAh
Max Discharge 15C (7.5A)
Internal Resistance 0.14Ω

Discharge curve

image

image

image

Arduino

Pin assignment

// Configure Arduino pins
const int batteryMeasInput = A1;  	// Battery measurement on A1
const int relayOutput = A0;  		// Battery relay output pin on A0

// Parameters
float R1 = 100000.0;    // resistance of R1 (100K - 99.2) -see text
float R2 = 21800.0;     // resistance of R2 (22K - 21.90) - see text!
float v_ref = 5.30;    	// Maximum value for the analog pin (this can be measured between GND and +5V on arduino)
float vmin;		// Battery information
float vset;     	// Battery information
float vmax;		// Battery information
float v_tracks = 5.0;   // Track motor max voltage
float v_turrets = 5.0;  // Turret motor max voltage

Initialization setup

void setup_Battery_supply(){
	// pinout battery control
	pinMode(relayOutput, OUTPUT);
	pinMode(batteryMeasInput, INPUT);
	
	// Turn off relay - Initial state
	RelayCtrl(false);
	
	// Print begin message
	Serial.println("--------------------");
	Serial.println("DC VOLTMETER");
	Serial.print("Maximum Voltage: ");
	Serial.print((int)(v_ref / (R2 / (R1 + R2))));
	Serial.println("V");
	Serial.println("--------------------");
	Serial.println("");
	
	BatteryType(BatteryRead()); 	// first setup battery 
	}

Functions

Relay control - Open / close relay

void RelayCtrl(bool cmd){
    if(cmd){
      digitalWrite(relayOutput, HIGH);  // Close relay
    } else {  
      digitalWrite(relayOutput, LOW);   // Open relay  
      }
    } 

Battery measurement - Measure battery voltage

// Voltage measurement on battery
float BatteryRead(){
	float vin = (analogRead(batteryMeasInput) * v_ref) / 1024.0;   	// analog pin input voltage
	float vbattery = vin / (R2 / (R1 + R2));                    	// calculated battery voltage
	
	// battery disconnected
	if (vin<0.09){
		vbattery = 0.0;   //statement to quash undesired reading
		BatteryType(vbattery);
	    }
	Serial.print("Vbat: ");
	Serial.print(vbattery);
	Serial.println("V");	
	return vbattery;
}

Battery check - Relay control base on battery voltage / Threshold to motors

// Battery check to control relay
void BatteryCheck(){
	bool relaycmd;
	float vbat = BatteryRead();
	
	// relay control
	if (vbat > vmin){
		relaycmd = true;
	}
	else if(vbat <= vmin){
		relaycmd = false;
	}	  
	
	RelayCtrl(relaycmd);
	  
	// refactor thresholds to battery voltage
	if (abs(vset - vbat) > 0.5) {
		vset = vbat; 
		if (relaycmd) {
			turret_SpeedThreshold = round(v_turrets/(vbat)*255);
			track_SpeedThreshold = round(v_tracks/(vbat)*255);
			
			// battery voltage lower than minimum
			if (turret_SpeedThreshold > 255){
				turret_SpeedThreshold =255;
			}
			if (track_SpeedThreshold > 255){
				track_SpeedThreshold =255;
			}
			  
		}
		else {
			turret_SpeedThreshold = 0;
			track_SpeedThreshold = 0;
		}
		  
		Serial.print("TrackThreshold: ");
		Serial.print(track_SpeedThreshold);
		Serial.print("TurretThreshold: ");
		Serial.print(turret_SpeedThreshold);
	  }
	}

Battery type - Identification of battery connected

// Battery type 
void BatteryType(float battery_voltage){
	int battery_type = 0;
		
	if(battery_voltage < 0.50){
		battery_type = 0;
	}
	if(battery_voltage > 5.00){
		battery_type = 1;
	}
	if(battery_voltage > 9.00){
		battery_type = 2;
	}		
	if(battery_voltage > 15.00){
		battery_type = 3;
	}			
		
	switch(battery_type){
		case 0:
		vmin = 0.0;
		vset = 0.0;
		vmax = 0.0;
		Serial.println("Value 0 received");
		Serial.println("No battery is connected");
		break;
			
		case 1:
		vmin = 4.6;	// vmin = 5.4V (0.9 V per cell)
		vset = 7.2; 	
		vmax = 8.2;		// vmax = 8.2V
		Serial.println("Value 1 received");
		Serial.println("NIMH 7.2V is connected");
		break;
			
		case 2:
		vmin = 6.8;	// vmin = 9.6V, 3.2V per cell
		vset = 11.1;	
		vmax = 12.6; 	// vmax = 12.6, 4.2V per cell
		Serial.println("Value 2 received");
		Serial.println("LiPo 3S 11.1V is connected");
		break;
			
		case 3:
		vmin = 15.4;	// vmin = 19.2V, 3.2V per cell
		vset = 22.2;	
		vmax = 25.2;	// vmax = 25.2, 4.2V per cell
		Serial.println("Value 3 received");
		Serial.println("LiPo 6S 22.2V is connected");
		break;
			
		default:
		vmin = 0.0;
		vset = 0.0;	
		vmax = 0.0;	
		Serial.println("Value outside 0,1,2,3 received");
		break;
		}			
	}

Loop

void loop(){
    BatteryCheck();     //Check battery
    }

Code

Battery_supervision.ino

/*******************************************************************************
   THIS SOFTWARE IS PROVIDED IN AN "AS IS" CONDITION. NO WARRANTY AND SUPPORT
   IS APPLICABLE TO THIS SOFTWARE IN ANY FORM. CYTRON TECHNOLOGIES SHALL NOT,
   IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL OR CONSEQUENTIAL
   DAMAGES, FOR ANY REASON WHATSOEVER.
 ********************************************************************************
   DESCRIPTION:
   This code is used for measuring a battery supply using a voltage divider.
   The steps are:
   * Measure DC voltage
   * Detect battery type
   * Based on SoC open/close battery relay
   * Determine battery powersave mode

   CONNECTIONS (Arduino nano v3 - Atmega328P, old bootloader):

   Arduino A0   - Digital ouput relay battery
   Arduino A1   - Measurement input resistive voltage divider
 *******************************************************************************/

// Configure Arduino pins
const int batteryMeasInput = A1;  	// Battery measurement on A1
const int relayOutput = A0;  		// Battery relay output pin on A0

// Parameters
float R1 = 100000.0;      // Resistance of R1 (100K - 99.2) - see text
float R2 = 21800.0;       // Resistance of R2 (22K - 21.90) - see text
float v_ref = 5.30;    	  // Maximum value for the analog pin (this can be measured between GND and +5V on arduino)
float vmin;               // Battery information
float vset;     	  // Battery information
float vmax;				
//float v_tracks = 5.0;   // Track motor max voltage
//float v_turrets = 5.0;  // Turret motor max voltage

void setup_Battery_supply(){
  pinMode(relayOutput, OUTPUT);
  pinMode(batteryMeasInput, INPUT);
  
  // Turn off relay - Initial state
  RelayCtrl(false);
  
  // Print start message
  Serial.println("--------------------");
  Serial.println("Voltage measurement");
  Serial.print("Maximum Voltage: ");
  Serial.print((int)(v_ref / (R2 / (R1 + R2))));
  Serial.println("V");
  Serial.println("--------------------");
  Serial.println("");
  
  BatteryType(BatteryRead()); 	// first setup battery 
}


// Battery check to control relay
void BatteryCheck(){
  bool relaycmd;
  float vbat = BatteryRead();
  
  // relay control
  if (vbat > vmin){
	  relaycmd = true;
  }
  else if(vbat <= vmin){
	  relaycmd = false;
  }	  
  
  RelayCtrl(relaycmd);
  
  // refactor thresholds to battery voltage
  if (abs(vset - vbat) > 0.5) {
	  vset = vbat; 
	  if (relaycmd) {
		  turret_SpeedThreshold = round(v_turrets/(vbat)*255);
		  track_SpeedThreshold = round(v_tracks/(vbat)*255);
		  
		  // battery voltage lower than minimum
		  if (turret_SpeedThreshold > 255){
		    turret_SpeedThreshold =255;
		  }
		  if (track_SpeedThreshold > 255){
		    track_SpeedThreshold =255;
		  }
		  
	  }
	  else {
		  turret_SpeedThreshold = 0;
		  track_SpeedThreshold = 0;
	  }
	  
	Serial.print("TrackThreshold: ");
	Serial.print(track_SpeedThreshold);
	Serial.print("TurretThreshold: ");
	Serial.print(turret_SpeedThreshold);
  }
}


// Voltage measurement on battery
float BatteryRead(){
	float vin = (analogRead(batteryMeasInput) * v_ref) / 1024.0;   	// analog pin input voltage
	float vbattery = vin / (R2 / (R1 + R2));                    	// calculated battery voltage
	
	// battery disconnected
	if (vin<0.09){
		vbattery = 0.0;   //statement to quash undesired reading
		BatteryType(vbattery);
	}
	Serial.print("Vbat: ");
	Serial.print(vbattery);
	Serial.println("V");	
	return vbattery;
}


// Battery type 
void BatteryType(float battery_voltage){
	int battery_type = 0;
	
	if(battery_voltage < 0.50){
		battery_type = 0;
	}
	if(battery_voltage > 5.00){
		battery_type = 1;
	}
	if(battery_voltage > 9.00){
		battery_type = 2;
	}		
	if(battery_voltage > 15.00){
		battery_type = 3;
	}			
	
	switch(battery_type){
		case 0:
		vmin = 0.0;
		vset = 0.0;
		vmax = 0.0;
		Serial.println("Value 0 received");
		Serial.println("No battery is connected");
		break;
		
		case 1:
		vmin = 4.6;	// vmin = 5.4V (0.9 V per cell)
		vset = 7.2; 	
		vmax = 8.2;		// vmax = 8.2V
		Serial.println("Value 1 received");
		Serial.println("NIMH 7.2V is connected");
		break;
		
		case 2:
		vmin = 6.8;	// vmin = 9.6V, 3.2V per cell
		vset = 11.1;	
		vmax = 12.6; 	// vmax = 12.6, 4.2V per cell
		Serial.println("Value 2 received");
		Serial.println("LiPo 3S 11.1V is connected");
		break;
		
		case 3:
		vmin = 15.4;	// vmin = 19.2V, 3.2V per cell
		vset = 22.2;	
		vmax = 25.2;	// vmax = 25.2, 4.2V per cell
		Serial.println("Value 3 received");
		Serial.println("LiPo 6S 22.2V is connected");
		break;
		
		default:
		vmin = 0.0;
		vset = 0.0;	
		vmax = 0.0;	
		Serial.println("Value outside 0,1,2,3 received");
		break;
	}			
}


// Relay control of battery
void RelayCtrl(bool cmd){
  if(cmd){
    digitalWrite(relayOutput, HIGH);  // Close relay
  } else {  
    digitalWrite(relayOutput, LOW);   // Open relay  
  }
}

Test code

Battery_Test.ino

/*******************************************************************************
   THIS SOFTWARE IS PROVIDED IN AN "AS IS" CONDITION. NO WARRANTY AND SUPPORT
   IS APPLICABLE TO THIS SOFTWARE IN ANY FORM. CYTRON TECHNOLOGIES SHALL NOT,
   IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL OR CONSEQUENTIAL
   DAMAGES, FOR ANY REASON WHATSOEVER.
 ********************************************************************************
   DESCRIPTION:
   This is the test code for testing the Battery supervision function.
   The function shows how to set up the initial battery supply and use the functions monitoring.
   **Please note that the battery voltage is assumed 11.1V**

   CONNECTIONS (Arduino nano v3 - Atmega328P, old bootloader):
 *******************************************************************************/

// parameters

// Initialisation
void setup() {
  Serial.begin(9600);
  
  setup_batterySupply();            // Setting up initial battery connected
}

void loop() {
  char byte = 0;
  // press q to cancel and exit
  while (byte != 'z') {
    Serial.readBytes(&byte, 1);

    // BATTERY CHECK  
    // -----------------------------------
    BatteryCheck();     //Check battery voltage continuously
    BatteryRead();

  }
  Serial.print("Done \n");
  Serial.end();
}