$USD
  • EUR€
  • £GBP
  • $USD
PROJECTS Raspberry PiRobotics

Tank Laser Tag Sherman & Panther

DFRobot Oct 28 2019 877

Project Creator: Arduino “having11” Guy

Create 2 tanks and battle them out, using laser light as the ammo!


Things used in this project

Hardware components

Raspberry Pi Zero Wireless ×2

DFRobot MiniQ Robot Chassis Kit ×2

Texas Instruments Dual H-Bridge motor drivers L293D ×2

Perf Board 6x4cm ×1

5V Regulator ×4

Adafruit Standard LCD - 16x2 White on Blue ×2

HC-05 Bluetooth Module × 2

Thumb Joystick ×4

Adafruit ADS1115 ADC ×2

LED (generic) ×10

Laser Diode ×2

Photoresistor ×8

RobotGeek Continuous Rotation Servo ×2

Servo Micro 9g ×2

1800 mAh LiPo Battery 11.1V 30C ×2

1300 mAh LiPo Battery 7.4V 30C ×2

SparkFun Pushbutton switch 12mm ×2

Toggle Switch ×2

Concave Arcade Button ×2

SPDT 2 Position 3 Terminal Switch ×1

Arduino Nano R3 ×2


Software apps and online services

Arduino IDE

Notepad++


Hand tools and fabrication machines

3D Printer (generic)

CNC Router

Soldering iron (generic)


Story

I would like to thank DFRobot for sponsoring this project. They provided the two MiniQ chassis kits for the tanks.



The Game

The rules of the game are pretty simple. Just shoot your laser at the opposing tank and hit it on one of the 4 sensors. Each sensor corresponds to a crew member: gunner, driver, commander, and machine gunner. If 3/4 of the crew is hit, you lose. If a gunner or driver is hit they can be replaced if you have enough crew remaining. There are also penalties to getting hit. If the gunner is knocked out, the tank can't fire for 6 seconds and the reload time increases. Additionally, if the driver is knocked out it reduces the speed of the tank and prevents movement for 6 seconds. My tank tag game is based off of the video game War Thunder.

The Tank Chassis

DFRobot was generous enough to send me two of their MiniQ Robot chassis. The chassis have plenty of mounting holes that allow you to add brackets. They come with two motors and wheels, along with two sets of caster wheels to add strength. The assembly was easy and simple. All I had to do was attach 2 screws to each motor and caster ball.

Next, I 3D printed 8 rod supporters, which screw into the chassis using a 3mm machine screw and nut. Each pair lines up across the chassis, allowing for a brass rod to span them.

Designing the Tanks

Fusion 360 is my CAD program of choice, so I used it to design the tank bodies. My friend Adam, who goes by “AceOfAces16”, designed a basic Panther hull and turret in Blender, which I then imported into Fusion 360. Next, I designed parts around the basic solid model. This was done once more to create the M4A3E8 Sherman.

Tank Electronics Part 1: Motors and Brains

This was the most arduous step of creating the tanks.

The Raspberry Pi is unable to provide the current and voltage necessary to drive the motors, so a motor driver is needed. I chose the L293d H-bridge driver for its size and simplicity, as it uses only 4 pins from the Raspberry Pi. This driver can supply up to 12v at 1 amp to the motors, making it the perfect choice.

Second, I needed a way to measure the 4 LDRs (variable light resistors) that give a value based on the amount of light hitting them. Lower amounts of light increase the resistance, and higher amounts of light decrease it, making it impossible to read them digitally. The Raspberry Pi has no ADC inputs, so I had to find a chip that could do it. The ADS1115 is an amazing, tiny, 4 channel analog to digital converter that communicates over I2C, so it uses only 2 wires, which frees up some precious few GPIO pins. The ADS1115 also has a Python library that was made by Adafruit, which allows for the gain to be set and read each of the four channels. Optionally, you can add an lm386n if you want sound effects. Just connect IN to pin 18 and VCC to +5v.


Tank Electronics Part 2: Power and Servos

Now there was the question of “How do I power this?” I had to provide power for 2 servos, a Raspberry Pi Zero W, an ADC, a laser diode, and 2 motors. First I divided up each component into voltage requirements. 5V for the Pi, laser, and servos; 3.3V for the ADC and servo driver; 6~12V for the motors.

2, 5V regulators can provide enough current (3 amps) to power all of the 5V components. For a power source, I chose to use a generic RC LiPo battery that could supply 11.7V at 30C and had 1800mAh of capacity.

Now that power and power delivery had been taken care of, I moved onto servo driving. At first I tried to use the GPIO PWM class to control the servos directly from the Pi’s GPIO pins, but a microprocessor can’t deliver the exact timings required unlike a dedicated chip. So I went searching, and eventually stumbled upon the PCA9685, an I2C 16 channel servo driver, exactly what I needed. Because it also uses the I2C protocol, I could easily connect it to the ADS1115.

Adafruit also provides a helpful library that controls each channel with a certain pulse. Using a dedicated chip offloads the processing from the Raspberry Pi, freeing up CPU cycles and simplifying the code.

You can find the ADS1115 library here: https://github.com/adafruit/Adafruit_Python_ADS1x15 and the PCA9685 library here: https://github.com/adafruit/Adafruit_Python_PCA9685


Programming

There are two boards that need programs, one is a Raspberry Pi that uses Python, and the other is an Arduino Nano that uses C++. For the Python code, I created a class that handles the motor and servo setup, receiving serial data, and controlling all of the tank’s electronics. All that was left was to create a main file that inputs the GPIO pin numbers and updates the serial buffer. Now for the controller code. The controller’s brain, an Arduino Nano, takes in four analog inputs, sends I2C data, and controls 4 LEDs.

It uses the Arduino Timer library to control how often analog data gets sampled, along with controlling reload speeds and laser firing time. View the attached code to see more.


Setup

After meticulously building each tank and controller, it was finally time to use them in a game, but first I had to pair each tank with its respective controller. To do that, I turned on one controller and then typed bluetoothctl then agent on then default-agent then scan on and after the controller showed up as HC-05 I typed scan off then entered pair MAC_ADDR where MAC_ADDR is the MAC address that showed up for the HC-05 module. It will ask for the PIN to pair, which is 1234. Now just type exit and then run the program by first typing sudo rfcomm bind /dev/rfcomm1 MAC_ADDR . This will bind the Bluetooth port to a serial port, allowing the pyserial library to read the data from the HC-05.


Gameplay

And that’s it! I drove my tank and my dad drove the other one, circling and firing at each other until one of us had our crew knocked out. This is a fun and entertaining take on laser tag, and I would again like to thank DFRobot for supplying the MiniQ Robot Chassis Kits.


Custom parts and enclosures

Thingiverse Link


Schematics

Github Repository

having11 / tanks-in-real-life

Read More

Latest commit to the master branch on 9-8-2017         Download as zip


Code

Robot Code Python Class (Python)       Download

from __future__ import division
import RPi.GPIO as GPIO
from time import sleep
from serial import Serial
import json

import Adafruit_PCA9685

class Car(object):

    def __init__(self, BT_Port, laser_pin):
        GPIO.setmode(GPIO.BCM)
        self.ser = Serial(BT_Port, baudrate=9600,timeout=0)
        self.laser_pin = laser_pin
        self.laser_state = False
        GPIO.setup(self.laser_pin, GPIO.OUT)
        
    def configMotors(self, mL1, mL2, mR1, mR2, invertLR=False):
        self.motor_array = [mL1, mL2, mR1, mR2]
        self.invert = invertLR
        for pin in self.motor_array:
            GPIO.setup(pin, GPIO.OUT)
        #self.motor_pwm.append(GPIO.PWM(pin, 490))
        self.motorL1_pwm = GPIO.PWM(mL1, 100)
        self.motorL2_pwm = GPIO.PWM(mL2, 100)
        self.motorR1_pwm = GPIO.PWM(mR1, 100)
        self.motorR2_pwm = GPIO.PWM(mR2, 100)
        self.motorL1_pwm.start(0)
        self.motorL2_pwm.start(0)
        self.motorR1_pwm.start(0)
        self.motorR2_pwm.start(0)
        
    def configServos(self):
        self.pwm = Adafruit_PCA9685.PCA9685()
        self.servo_min = 150
        self.servo_max = 600
        self.pwm.set_pwm_freq(60)
        
    def deg_to_pulse(self, degree):
        pulse = (degree - 0) * (self.servo_max - self.servo_min) / (180 - 0) + 150 
        print('Pulse: '+str(pulse))
        return int(pulse)
        
    def receive_command(self):
        self.cmd = ""
        if  self.ser.inWaiting():
            self.cmd = self.ser.readline()
            if self.cmd != None:
                try:
                    data = self.cmd.decode('utf-8')
                    data = json.loads(data.strip())
                    print data
                    if data != "":
                        return data
                    else:
                        return ""
                except ValueError:
                    pass
        #except IOError:
            #pass
            
    def turn_wheel(self, motor1, motor2):
            if self.invert:
                temp = motor1
                motor1 = motor2
                motor2 = temp
            motor1 = (motor1 / 2)
            motor2 = (motor2 / 2)
            if motor1<0:
                self.motorL2_pwm.ChangeDutyCycle(motor1*-1)
                self.motorL1_pwm.ChangeDutyCycle(0)#make positive if negative
            else:
                self.motorL1_pwm.ChangeDutyCycle(motor1)
                self.motorL2_pwm.ChangeDutyCycle(0)
        
            if motor2<0:
                self.motorR2_pwm.ChangeDutyCycle(motor2*-1)
                self.motorR1_pwm.ChangeDutyCycle(0)#make positive if negative
            else:
                self.motorR1_pwm.ChangeDutyCycle(motor2)
                self.motorR2_pwm.ChangeDutyCycle(0)
        
    def move_turret(self, turret_deg, barrel_deg):
        self.pwm.set_pwm(0, 0, self.deg_to_pulse(turret_deg))
        self.pwm.set_pwm(1, 0, self.deg_to_pulse(barrel_deg))
            
    def fire_laser(self, state):
        GPIO.output(self.laser_pin, state)

    def update(self): #Run to make the robot work
        self.json_obj = self.receive_command()
        print self.json_obj
        try:
            if "motor" in self.cmd:
                if self.json_obj["motor"] != None:
                    val1 = self.json_obj["motor"][0]
            # if val1 > 0:
                 #    val1 += 10
                    val2 = self.json_obj["motor"][1]
            # if val2 <0:
            #   val2 += 4
                    self.turn_wheel(val1, val2)
            elif "shoot" in self.cmd:
                self.laser_state = self.json_obj["shoot"]
                self.fire_laser(self.json_obj["shoot"])
            elif "turret" in self.cmd:
                val1 = self.json_obj["turret"][0]
                val2 = self.json_obj["turret"][1]
                self.move_turret(val1, val2)
        
        except TypeError:
            pass
    sleep(.01)

Robot Code Python Main (Python)       Download

import car

bt_port = "/dev/rfcomm3"
laser_pin = 20
rc_car = car.Car(bt_port, laser_pin)

rc_car.configMotors(6,5,19,13, invertLR=True)
rc_car.configServos() #Turret drive servo, barrel servo

while 1:
    rc_car.update()
        

Controller Code (C/C++)       Download

#include "Timer.h"
#include <Wire.h>
#include <LiquidCrystal_I2C.h>

int JS_VALS[2] = {};
int JS_VALS_R[2] = {};

const int JS_PINS[4] = {A0, A1, A2, A3}; //L_X, L_Y, R_X, R_Y
const int led_pins[4] = {4,5,6,7};

const int button_pin = 3;
const int deadzone = 8;
bool laser = false;

const int servo_limits[5] = {0, 180, 50, 95, 75}; //Left, Right, Lower, Upper, Middle limits for the turret
int turret_positions[2] = {90, servo_limits[4]}; //Initial positions

unsigned long last_time = 0;
long motor_delay = 30; //Delay 30 ms between motor control polls
long turret_delay = 150; //Delay 150 ms between turret control polls

long reloadSpeed = 8000;
float driveSpeed = 1.0;
int crewValues[4] = {3,3,2,1};
bool crewLeft[4] = {true,true,true,true};
int crewLeftNum = 4;
int reloadTimer, crewReplaceTimer, fireTimer;
bool is_reloaded= true;
bool can_move = true;
bool can_fire = true;

LiquidCrystal_I2C lcd(0x3F, 16, 2);

Timer t;

void setup() {
  // put your setup code here, to run once:
Serial.begin(9600);
lcd.init();
lcd.backlight();
lcd.print("Begin fighting!");
delay(2000);
lcd.clear();
lcd.home();
pinMode(button_pin, INPUT_PULLUP);
Serial.println("Begin");

t.every(motor_delay, control_motors);
t.every(turret_delay, control_turret);
t.every(50, checkButton);
for(int i=0;i<4;i++){
    pinMode(led_pins[i], OUTPUT);
}
updateCrew();

}

void loop() {
  /*control_motors();
  control_turret();
  delay(150);*/
  t.update();
  if(Serial.available()>0){
      String data = Serial.readStringUntil('\n');
      if(data=="HG"){
          crewLeft[0] = false;
          crewLeftNum -= 1;
          reloadSpeed += 2000;
          can_fire = false;
          crewReplaceTimer = t.after(6000, replaceCrew);
      }
      else if(data=="HD"){
          crewLeft[1] = false;
          crewLeftNum -= 1;
          driveSpeed -= .2;
          can_move = false;
          crewReplaceTimer = t.after(6000, replaceCrew);
      }
      else if(data=="HC"){
          crewLeft[2] = false;
          crewLeftNum -= 1;
          driveSpeed -= .1;
          reloadSpeed += 1500;
          crewReplaceTimer = t.after(6000, replaceCrew);
      }
      else if(data=="HM"){
          crewLeft[3] = false;
          crewLeftNum -= 1;
          crewReplaceTimer = t.after(6000, replaceCrew);
      }
      updateCrew();
  }
  if(crewLeftNum<=1){
      lcd_clear();
      lcd.print("You lose");
      while(1);
  }
}

void checkButton(){
    if(digitalRead(button_pin)==0){
        fire_laser();
    }
}

void replaceCrew(){
    if(crewLeft[0]==false){
        if(crewLeft[2]==true){
            crewLeft[2] = false;
            crewLeft[0] = true;
            can_fire = true;
        }
        else if(crewLeft[3]==true){
            crewLeft[3] = false;
            crewLeft[0] = true;
            can_fire = true;
        }
    }
    else if(crewLeft[1]==false){
        if(crewLeft[2]==true){
            crewLeft[2] = false;
            crewLeft[1] = true;
            can_move = true;
        }
        else if(crewLeft[3]==true){
            crewLeft[3] = false;
            crewLeft[1] = true;
            can_move = true;
        }
    }
    updateCrew();
    t.stop(crewReplaceTimer);
}

void updateCrew(){
    for(int i=0;i<4;i++){
        digitalWrite(led_pins[i],crewLeft[i]);
    }
}

void lcd_clear(){
    lcd.clear();
    lcd.home();
}

void fire_laser(){
  if(is_reloaded){
      if(can_fire){
        lcd.clear();
        lcd.print("Firing laser");
        is_reloaded = false;
        String json_string = "{\"motor\":[" + String(0)+","+String(0)+"]}"; //Stop tank before firing
        Serial.println(json_string);
        laser = true;
        fireTimer = t.after(2000, stopLaser);
        
      }
    }
}

void stopLaser(){
    t.stop(fireTimer);
    laser = false;
    lcd_clear();
    lcd.print("Reloading");
    reloadTimer = t.after(reloadSpeed, reloadGun);
}

void reloadGun(){
    lcd_clear();
    lcd.print("Reloaded");
    is_reloaded = true;
    t.stop(reloadTimer);
}

void control_motors(){
  JS_VALS[0] = analogRead(JS_PINS[0]);
  JS_VALS[1] = analogRead(JS_PINS[1]);
  int x = map(JS_VALS[0], 0, 1023, -50, 50);
  x = constrain(x, -100, 100);
  int y = map(JS_VALS[1], 0, 1023, -50, 50);
  y = constrain(y, -100, 100);
  int motor1 = x+y;
  int motor2 = y-x;
  motor1 = constrain(motor1, -100, 100);
  motor2 = constrain(motor2, -100, 100);
  if(abs(motor1) <= deadzone){
    motor1 = 0;
  }
  if(abs(motor2) <= deadzone){
    motor2 = 0;
  }
  
  motor1 = int(float(motor1)*driveSpeed);
  motor2 = int(float(motor2)*driveSpeed);
  
  if(can_move==false){
      motor1 = 0;
      motor2 = 0;
  }
  
  String json_string = "{\"motor\":[" + String(motor1)+","+String(motor2)+"]}";
  Serial.println(json_string);
  String json_string2;
  if(laser){
    json_string2 = "{\"shoot\":1}";
    Serial.println(json_string2);
  }
  else if(!laser){
    json_string2 = "{\"shoot\":0}";
    Serial.println(json_string2);
  }
}

void control_turret(){
  JS_VALS_R[0] = analogRead(JS_PINS[2]); //Get X values
  JS_VALS_R[1] = analogRead(JS_PINS[3]); //Get Y values
  int x = map(JS_VALS_R[0]+10, 0, 1023, 5, -5);
  x = constrain(x, -5, 5); //Catch outliers
  int y = map(JS_VALS_R[1], 0, 1023, 2, -2);
  y = constrain(y, -2, 2);

  turret_positions[0] += x;
  turret_positions[1] += y;

  if(turret_positions[0] <= servo_limits[0]){
    turret_positions[0] = servo_limits[0];
  }
  else if(turret_positions[0] >= servo_limits[1]){
    turret_positions[0] = servo_limits[1];
  }
  if(turret_positions[1] <= servo_limits[2]){
    turret_positions[1] = servo_limits[2];
  }
  else if(turret_positions[1] >= servo_limits[3]){
    turret_positions[1] = servo_limits[3];
  }
  
  String json_string = "{\"turret\":[" + String(turret_positions[0])+","+String(turret_positions[1])+"]}";
  Serial.println(json_string);
  
}


REVIEW