Tiger 1 BB airsoft RC Tank


CONTINUED HERE…

Together with a work colleague we have set ourselves a challenge: buy 2 1/16th RC tanks capable of firing BB pellets and transform them such that we can have an AUTONOMOUS BATTLE !

Unboxing

21Apr – the end of V1

After happily splitting the “recycled” motor controller, the FEZ Domino board broke AGAIN !

This time it’s the last drop, I can’t take it anymore, spending more time fixing the .NET board than building my stuff… it’s not that the FEZ Domino is “bad” as every time it’s the voltage regulators that burn, it’s more to do with the fact that it’s too “delicate” for connecting it directly to “not carrefully designed electric circuits”… I admit I’m not always carefull with the voltages and the connections, but on the other hand, I’ve never burnt an Arduino board until now… maybe it’s the 3.3V issue, maybe it’s simply a much more powerfull but delicate processor, possible both…

Anyhow, the new plan (that has always been in the back of my mind !) is to replace it with the Lego NXT, which can be programmed in Java (which I obviously prefer to C# !)…

"Recycled" motor controller cut into pieces

CODE used until now:

1) C# for the now defunct FEZ Domino board

using System;
using System.Threading;

using Microsoft.SPOT;
using Microsoft.SPOT.Hardware;

using GHIElectronics.NETMF.FEZ;

class CONSTANTS
{
    public const FEZ_Pin.PWM TRACK_LEFT_PIN = FEZ_Pin.PWM.Di10;
    public const FEZ_Pin.Digital TRACK_LEFT_BACK_PIN = FEZ_Pin.Digital.Di11;
    public const FEZ_Pin.Digital TRACK_LEFT_ENABLE_PIN = FEZ_Pin.Digital.Di12;

    public const FEZ_Pin.PWM TRACK_RIGHT_PIN = FEZ_Pin.PWM.Di8;
    public const FEZ_Pin.Digital TRACK_RIGHT_BACK_PIN = FEZ_Pin.Digital.Di9;
    public const FEZ_Pin.Digital TRACK_RIGHT_ENABLE_PIN = FEZ_Pin.Digital.Di13;

    public const FEZ_Pin.Digital TURRET_LEFT_PIN = FEZ_Pin.Digital.Di4;
    public const FEZ_Pin.Digital TURRET_RIGHT_PIN = FEZ_Pin.Digital.Di6;
    //public const FEZ_Pin.Digital GUN_UP_PIN = FEZ_Pin.Digital.Di4;
    //public const FEZ_Pin.Digital GUN_DOWN_PIN = FEZ_Pin.Digital.Di11;
    public const FEZ_Pin.Digital FIRE_PIN = FEZ_Pin.Digital.An1;
}

class Program
{
    //SerialLCD _LCD = new SerialLCD();
    RadioI2C _radio;
    TigerTankBB _tank;

    Program()
    {
        _tank = new TigerTankBB();
        _radio = new RadioI2C(newRadioValuesCallback, radioSignalLostCallback);
    }

    private void newRadioValuesCallback(sbyte[] values)
    {
        Log.info(toStr(values));

        _tank.motion(values[0], values[1]);
        _tank.turretMove(values[3]);
    }

    private void radioSignalLostCallback()
    {
        Log.info("S LOST !");
        _tank.motion(0, 0);
        _tank.turretMove(0);
    }

    public static void Main()
    {
        new Program();

        while (true) Thread.Sleep(1000);
    }

    private static string toStr(sbyte[] values)
    {
        string str = "";
        foreach (sbyte value in values) str += value + ", ";
        return str;
    }

}

public static class Log
{
    public static void info(string str)
    {
        Debug.Print(DateTime.Now.ToString() + " INFO: " + str);
    }

    public static void error(string str)
    {
        Debug.Print(DateTime.Now.ToString() + " ERR: " + str);
    }
}

___________________________________________________________________

class TigerTankBB : IDisposable
{
    private Motor _leftTrack = new Motor(new MyPWM(CONSTANTS.TRACK_LEFT_PIN), new MyPWM(CONSTANTS.TRACK_LEFT_BACK_PIN), new OutputPort((Cpu.Pin)CONSTANTS.TRACK_LEFT_ENABLE_PIN, false));
    private Motor _rightTrack = new Motor(new MyPWM(CONSTANTS.TRACK_RIGHT_PIN), new MyPWM(CONSTANTS.TRACK_RIGHT_BACK_PIN), new OutputPort((Cpu.Pin)CONSTANTS.TRACK_RIGHT_ENABLE_PIN, false));
    private Motor _turret = new Motor(new MyPWM(CONSTANTS.TURRET_LEFT_PIN), new MyPWM(CONSTANTS.TURRET_RIGHT_PIN), null);
    //private Motor _gun = new Motor(new MyPWM(CONSTANTS.GUN_DOWN_PIN), new MyPWM(CONSTANTS.GUN_UP_PIN));
    private OutputPort _fire = new OutputPort((Cpu.Pin)CONSTANTS.FIRE_PIN, true);

    public void motion(sbyte speedPerc, sbyte directionPerc)
    {
        _leftTrack.set(speedPerc + directionPerc / 2);
        _rightTrack.set(speedPerc - directionPerc / 2);
    }

    public void turretMove(sbyte speedPerc)
    {
        _turret.set(speedPerc);
    }

    public void fire(bool startStop)
    {
        _fire.Write(startStop);
    }

    public void Dispose()
    {
        _leftTrack.Dispose();
        _rightTrack.Dispose();
        //_turret.Dispose();
        _fire.Dispose();
    }
}

class Motor : IDisposable
{
    private MyPWM _sens1;
    private MyPWM _sens2;
    private OutputPort _enable;

    public Motor(MyPWM sens1, MyPWM sens2, OutputPort enable)
    {
        _sens1 = sens1;
        _sens2 = sens2;
        _enable = enable;

        if(_enable != null) _enable.Write(true);
    }

    public void set(int percentage)
    {
        bool sens1 = percentage > 0;
        percentage = System.Math.Abs(percentage);

        if (percentage > 100) percentage = 100;

        if (percentage > 10)
        {
            if (_enable != null) _enable.Write(true);
            if (sens1)
            {
                _sens2.set(0);
                _sens1.set(percentage);
            }
            else
            {
                _sens1.set(0);
                _sens2.set(percentage);
            }
        }
        else
        {
            _sens1.set(0);
            _sens2.set(0);
            // stop useless and annoying noise...
            if (_enable != null) _enable.Write(false);
        }
    }

    public void Dispose()
    {
        if (_sens1 != null) _sens1.Dispose();
        if (_sens2 != null) _sens2.Dispose();
    }
}

/**
 * Does native PWM on hardware enabled pins and software PWM (using OutputCompare) on "simple" digital pins
 * */
class MyPWM : IDisposable
{
    // >1000 Hz will likely lead to high losses and more heat dissipation. Better to stay with very low frequencies, 50 to 300Hz.
    private const int PWM_FREQ = 100;
    private const int OC_FREQ = 10000 / PWM_FREQ;

    private PWM _pwm = null;
    private OutputCompare _oc = null;
    private uint[] _ocTimigs = new uint[2];

    public MyPWM(FEZ_Pin.PWM pin)
    {
        _pwm = new PWM((PWM.Pin)pin);
    }

    public MyPWM(FEZ_Pin.Digital pin)
    {
        _oc = new OutputCompare((Cpu.Pin)pin, false, 2);
    }

    public void set(int percentage)
    {
        int value = percentage;
        if (value < 0) value = 0;
        else if (value > 100) value = 100;

        if (_pwm != null)
        {
            if (value == 0) _pwm.Set(false);
            else _pwm.Set(PWM_FREQ, (byte)value);
        }
        else if (_oc != null)
        {
            if (value == 0) _oc.Set(false);
            else
            {
                _ocTimigs[0] = (uint)value * OC_FREQ;
                _ocTimigs[1] = (uint)(100 - value) * OC_FREQ;
                _oc.Set(true, _ocTimigs, 0, 2, true);
            }
        }
    }

    public void Dispose()
    {
        if(_pwm != null) _pwm.Dispose();
        if(_oc != null) _oc.Dispose();
    }
}
______________________________________________________________

public delegate void RadioDelegate(sbyte[] values);
public delegate void RadioSignalLostDelegate();

class RadioI2C : IDisposable
{
    private const byte CHANNELS_COUNT = 6;
    private const byte ADDR_SLAVE = 0xC1 >> 1;
    private const byte NO_NEW_DATA = 233; // if we receive this byte alone -> no new update on the controller's side...
    private const byte BAD_SIGNALS_FOR_LOST_SIGNAL = 5; //how many bad signad to wait until declaring the signal lost

    private readonly RadioDelegate _newValuesCallback;
    private readonly RadioSignalLostDelegate _signalLostCallback;
    private readonly I2CDevice _I2Ccontroller = new I2CDevice(new I2CDevice.Configuration(ADDR_SLAVE, 100));
    private bool _isSignalLost = true;
    private byte[] _values = new byte[CHANNELS_COUNT];

    public RadioI2C(RadioDelegate newValuesCallback, RadioSignalLostDelegate signalLostCallback)
    {
        _newValuesCallback = newValuesCallback;
        _signalLostCallback = signalLostCallback;

        // start the executor thread. ONLY 1 thread, rather than creating and killing them...
        // also the callbacks are called in this thread rather than in the interrupt ISR !
        new Thread(CallbackExecutor).Start();
    }

    private void CallbackExecutor()
    {
        int valuesRead = 0, badValues = 0;
        bool send;

        while (true)
        {
            valuesRead = getValuesFromController();
            if (valuesRead == CHANNELS_COUNT)
            {
                sbyte[] percentagesToSend = new sbyte[CHANNELS_COUNT];
                send = true;
                for (byte i = 0; i < CHANNELS_COUNT; i++)
                {
                    if (_values[i] <= 200)
                    {
                        percentagesToSend[i] = (sbyte)(_values[i] - 100);
                    }else
                    {
                        send = false;
                    }

                }

                if (send)
                {
                    badValues = 0;
                    _newValuesCallback(percentagesToSend);
                }
                else if (badValues >= 0)
                {
                    badValues++;
                }

            }
            else if (valuesRead == 1 && _values[0] == NO_NEW_DATA)
            {
                // NOTHING to do
            }
            else if (valuesRead == 0)
            {
                Log.error("Can't communicate with the I2C bus / 2. Probably the: " + ADDR_SLAVE + " address is wrong ?");
            }else
            {
                Log.error("Communication with I2C controller OK, BUT its answer is WRONG. Data read: " + valuesRead);
            }

            if (badValues >= BAD_SIGNALS_FOR_LOST_SIGNAL)
            {
                badValues = -1; // callback called, do not call again, until we receive something value
                _signalLostCallback();
            }

            //EMPIRICALLY calcualted that it HAS to be > 30ms  !! If we sent TOO many I2C requests we "kill" the controller !!
            Thread.Sleep(50);
        }
    }

    // transforms pulses expresses in ticks into percentages -100 to +100% .
    private int getValuesFromController()
    {
        try
        {
            return _I2Ccontroller.Execute(new I2CDevice.I2CTransaction[] { I2CDevice.CreateReadTransaction(_values) }, 10); // 10ms timeout
        }
        catch (System.ArgumentException e)
        {
            Log.error("Can't communicate with the I2C bus. Probably the: " + ADDR_SLAVE + " address is wrong ?" + e.Message);
            return -1;
        }

    }

    public bool getIsSignalLost()
    {
        return _isSignalLost;
    }

    public void Dispose()
    {
        _I2Ccontroller.Dispose();
    }
}

2) C for the master Arduino, its later replacemen

#include <Wire.h>
#include "RadioI2C.h"
#include "Chassis.h"
#include "Turret.h"

const byte LED_PIN = 13;

RadioI2C _radio;
Chassis _chassis;
Turret _turret;

unsigned long _lastLoop = millis();

void setup(){
    pinMode(LED_PIN, OUTPUT);
}

void loop(){
    // using a 50ms main loop (can't get the radio data much more often that this anyhow...)
    if(millis() - _lastLoop >= 50){
        _lastLoop = millis();
        _turret.clockUpdate(); // the Turret has some internal updates to make
        
        if(_radio.readNewValues() > 0){
            digitalWrite(LED_PIN, LOW);
            _chassis.move(_radio.getChannel(0), _radio.getChannel(1));
            _turret.moveHoriz(_radio.getChannel(3));
            _turret.light(_radio.getChannel(5));
            if(_radio.getChannel(4) > 0) _turret.fire();
        }else if(_radio.isSignalLost()){
            digitalWrite(LED_PIN, HIGH);
            _chassis.move(0, 0);
            _turret.moveHoriz(0);
        }
    }
}

________________________________________________________

#ifndef Chassis_h
#define Chassis_h

#include "Motor.h"

const byte TRACK_LEFT_FORWARD_PIN = 5;
const byte TRACK_LEFT_BACK_PIN = 6;
const byte TRACK_LEFT_ENABLE_PIN = 7;
const byte TRACK_RIGHT_FORWARD_PIN = 9;
const byte TRACK_RIGHT_BACK_PIN = 10;
const byte TRACK_RIGHT_ENABLE_PIN = 8;


class Chassis {
    private:
        Motor _leftTrack;
        Motor _rightTrack;
    
    public:
        Chassis() : _leftTrack(TRACK_LEFT_FORWARD_PIN, TRACK_LEFT_BACK_PIN, TRACK_LEFT_ENABLE_PIN),
                    _rightTrack(TRACK_RIGHT_FORWARD_PIN, TRACK_RIGHT_BACK_PIN, TRACK_RIGHT_ENABLE_PIN){}
        void move(int speedPerc, int dirPerc);
};



void Chassis::move(int speedPerc, int dirPerc){
    _leftTrack.set(speedPerc + dirPerc / 2);
    _rightTrack.set(speedPerc - dirPerc / 2);
}

#endif

__________________________________________________________________________

#ifndef Motor_h
#define Motor_h

const byte NO_ENABLE_PIN = 99;

class Motor {
    private:
        byte _sens1Pin;
        byte _sens2Pin;
        byte _enablePin;
        void init(byte, byte, byte);
    
    public:
        Motor(byte sens1Pin, byte sens2Pin) {init(sens1Pin, sens2Pin, NO_ENABLE_PIN);}
        Motor(byte sens1Pin, byte sens2Pin, byte enablePin) {init(sens1Pin, sens2Pin, enablePin);}
        void set(int);
};


void Motor::init(byte sens1Pin, byte sens2Pin, byte enablePin){
    _sens1Pin = sens1Pin;
    _sens2Pin = sens2Pin;
    _enablePin = enablePin;
    if(_enablePin != NO_ENABLE_PIN) pinMode(_enablePin, OUTPUT);
}

void Motor::set(int percentage){
    boolean sens1 = percentage > 0;
    // limit to a valid percentage [-100, 100] AND take the absolute value
    byte value = abs(constrain(percentage, -100, 100));
    // scale to [0..255] which is what analogWrite wants
    value = value * 2.55;
    
    if(value > 10){
        if(_enablePin != NO_ENABLE_PIN) digitalWrite(_enablePin, HIGH);
        if(sens1){
            analogWrite(_sens2Pin, 0);
            analogWrite(_sens1Pin, value);
        }else{
            analogWrite(_sens1Pin, 0);
            analogWrite(_sens2Pin, value);            
        }
    }else{
        analogWrite(_sens1Pin, 0);
        analogWrite(_sens2Pin, 0);
        if(_enablePin != NO_ENABLE_PIN) digitalWrite(_enablePin, LOW);
    }
}

#endif

____________________________________________________________________

#ifndef RadioI2C_h
#define RadioI2C_h

#include <WProgram.h>

const byte CHANNELS_COUNT  = 6;
const byte ADDR_SLAVE = 0xC1 >> 1;
const byte NO_NEW_DATA = 233; // if we receive this byte alone -> no new update on the controller's side...
const byte BAD_SIGNALS_FOR_LOST_SIGNAL = 5; //how many bad signad to wait until declaring the signal lost

class RadioI2C {
    private:
        char _values[CHANNELS_COUNT];
        byte _signalLostCount;
    
    public:
        RadioI2C(){Wire.begin();}
        char readNewValues();
        char getChannel(byte channelNo);
        boolean isSignalLost() {return _signalLostCount >= BAD_SIGNALS_FOR_LOST_SIGNAL;}
};


char RadioI2C::getChannel(byte channelNo){
    return _values[channelNo];
}

// should NOT be called more often than every 30ms !
char RadioI2C::readNewValues(){
    int retVal = -2; // comm or protocol problem
    byte currVal;
    Wire.beginTransmission(ADDR_SLAVE);
    Wire.requestFrom(ADDR_SLAVE, CHANNELS_COUNT);
    if(Wire.available() == CHANNELS_COUNT){
        retVal = 1; // new data received
        for(byte i=0; i<CHANNELS_COUNT; i++) {
            currVal = Wire.receive();
            if(currVal > 200) {
                retVal = -1; // signal lost
            }else{
                _values[i] = currVal - 100;
            }
        }
        if(retVal != 1) _signalLostCount ++; //increment only once per all channels data
        else _signalLostCount = 0;
    }else if(Wire.available() == 1 && Wire.receive() == NO_NEW_DATA) retVal = 0; //NO NEW data

    Wire.endTransmission();
    return retVal;
}

#endif

________________________________________________________________________

#ifndef Turret_h
#define Turret_h

#include "Motor.h"

const byte TURRET_LEFT_PIN = 11;
const byte TURRET_RIGHT_PIN = 3;
const byte TURRET_FIRE_PIN = 4;
const byte TURRET_LIGHT_PIN = 12;

const int  FIRE_TIME = 2000; // milliseconds


class Turret {
    private:
        Motor _horizontalMotor;
        byte _firePin;
        byte _lightPin;
        unsigned long _fireStartTime;
    
    public:
        Turret() :  _horizontalMotor(TURRET_LEFT_PIN, TURRET_RIGHT_PIN),
                    _firePin(TURRET_FIRE_PIN),
                    _lightPin(TURRET_LIGHT_PIN),
                    _fireStartTime(0)
                    {
                        pinMode(_firePin, OUTPUT);
                        digitalWrite(_firePin, LOW);
                        pinMode(_lightPin, OUTPUT);
                        digitalWrite(_lightPin, HIGH);                        
                    }
        
        void clockUpdate();            
        void moveHoriz(int speedPerc);
        boolean fire();
        void light(int intensityPerc);
};


void Turret::moveHoriz(int speedPerc){
    _horizontalMotor.set(speedPerc);
}


void Turret::clockUpdate(){
    // we are in the process of firing and the necessary delay lapsed 
    if(_fireStartTime != 0 && (millis() - _fireStartTime >= FIRE_TIME)){
        digitalWrite(_firePin, LOW); // stop the canon
        _fireStartTime = 0; // we are not firing anymore 
    }
}

boolean Turret::fire(){
    if(_fireStartTime == 0){
        // the canon is actually NOT firin
        digitalWrite(_firePin, HIGH); // start the canon
        _fireStartTime = millis();  // record when we started, to know when to stop !
        return true; // we started firing
    }else{
        return false; // couldn't fire, another fire operation in progress !
    }
}

void Turret::light(int intensityPerc){
    // percentage is [-100..100] and analogWrite wants [0..255]
    analogWrite(_lightPin, map(constrain(intensityPerc, -100, 100), -100, 100, 0, 255));
}

#endif

3) C for the slave Arduino, dealing with the PPM radio signal

#include <Wire.h>

#define LED 13
#define MAX_CHANNELS    6  // Number of radio channels to read. Has to be <= to what the receiver outputs in its PPM signal
#define I2C_SLAVE_ADDR  0x08
const byte BAD_VALUE_PERC = 222;
byte NO_NEW_DATA[] = {233};

// can only send positive bytes, so shift the (-100, 100) to (0, 200)
byte _percentages[MAX_CHANNELS]; 
byte _sentPercentages[MAX_CHANNELS];


void setup(){
    pinMode(LED, OUTPUT);
    digitalWrite(LED, HIGH);
    
    Wire.begin(I2C_SLAVE_ADDR); //join as slave
    Wire.onRequest(onI2CRequest);
    
    setup_radio();

}

void onI2CRequest(){
    digitalWrite(LED, LOW);
    populatePercentages();
    if(havePercentagesChanged()){
        Wire.send(_percentages, MAX_CHANNELS);
        // remember what we've sent
        for(byte i=0; i<MAX_CHANNELS; i++) _sentPercentages[i] = _percentages[i];
    }else{
        // everything is OK here, BUT nothing new...
        Wire.send(NO_NEW_DATA, 1);
    }
    
    digitalWrite(LED, HIGH);
}

void loop(){
    delay(100);
}


boolean havePercentagesChanged(){
    for(byte i=0; i<MAX_CHANNELS; i++) if(_percentages[i] != _sentPercentages[i]) return true;
    return false;
}

_________________________________________________________________

#define PPM_PIN	 2          // External Interrupt 0 - Input Capture Pin (PPM Rx signal reading)

const int TIMER_MULT =  F_CPU / 1000000;        // Ticks per MicroSec. PRESCALER is 1. Otherwise it should also appear here !

#define TIMER_COUNT TCNT1   // use TIMER 1, 16 bits  
const int MIN_VALID_PULSE = 900 * TIMER_MULT; //a valid pulse must be at least 900uS
const int MAX_VALID_PULSE = 2100 * TIMER_MULT; //a valid pulse must be less than  2100uS
const int MIN_PULSE = 1100 * TIMER_MULT; 
const int MAX_PULSE = 1900 * TIMER_MULT;
const double DELTA_PULSE_PERC = 200 / (double)(MAX_PULSE - MIN_PULSE);


volatile int8_t  _rx_ch = 0;
volatile int _pulses[MAX_CHANNELS];  // pulses width in ticks for performance. Finished array.
volatile int _currentPulses[MAX_CHANNELS + 1]; //array on which the actual work is done.

void setup_radio(){
    // PPM signal initialisation
    pinMode(PPM_PIN, INPUT);
    
    // TIMER 2   Pins 5 & 6  will have PPM disabled  TCNT2 increments every 16uS
    TCCR1A = 0x00;
    TCCR1B = 1 << CS10; // NO pre-scaling 
    TIMSK1 = 1 << TOIE1; //Timer1 Overflow Interrupt Enable
    
    // whenever there is a raise in the PPM signal, deal with it
    attachInterrupt(0, changeInSignalISR, RISING);
}

// Timer1 Overflow 
// this gets called every 65536 (16bit counter) x TIMER_MULT microsecs 
// this is 4096uS for a 16MZHz clock or 5888uS for a 11MHz clock
ISR(TIMER1_OVF_vect){
    // This is definitely more than a normal pulse(as long as the F_CPU < 25MHz) so we can consider this as a sync gap, between a new PPM signal
    _rx_ch = 0;
}

void changeInSignalISR(){
    if(_rx_ch >= 0) _currentPulses[_rx_ch ++] = TIMER_COUNT;  //pulse for one of the channels
    
    // always re-init the times as we always start counting "something" on a rising change
    TIMER_COUNT = 0;

    // this should be the last pulse, don't accept other pulses until we get a new SYNC signal
    if(_rx_ch > MAX_CHANNELS){
        _rx_ch = -1;
        // done with a signal, "publish" it
        for(byte i = 0; i<  MAX_CHANNELS; i ++) _pulses[i] = _currentPulses[i+1];
    }
}



void populatePercentages(){
    for(byte i=0; i < MAX_CHANNELS; i++){
        if((_pulses[i] > MIN_VALID_PULSE) && (_pulses[i] < MAX_VALID_PULSE)){
             _percentages[i] = constrain(int((_pulses[i] -  MIN_PULSE) * DELTA_PULSE_PERC), 0, 200);
        }else{
            _percentages[i] = BAD_VALUE_PERC; //ERROR
        }
    }
}


20Apr – turret and gun firing

Today I spent several long and frustrating hours trying to find a solution to drive the 2 turret and gun firing motors.

I had 3 controllers, a L293D based one, a pololu serial one and an standard RC ESC, and for some un-explained reason none of them worked…

So I decided to embark onto my first attempt at builing a H-Bridge from scratch!

Quite interesting task and, as usual, I’ve learnt a lot… but also, as usual, “experience is what you get when you don’t get what you want”… so the result is not satisfying…

Right before going to bed however, and after spending some more money ordering several brushed ESCs (I decided that L298 based motor controllers are a pain as too big and getting too hot, whereas for the same price you can get 10 times more Amps from a standard RC ESC !) I realised that I could salvage the old board from an old toy tank :

RX-5 based board from an older tank - only the motor controlling part is interestig...

18Apr – Mechanical upgrades

I’ll be quick today… my wife is waiting for me to go for a tea at Claridge’s… can’t make her wait… !

Today it’s all about some upgrades, or rather downgrades…

Yesterday everything was working quite well, but I noticed how hot the motor controllers get, mainly because the tank is so heavy ! The original battery doesn’t even work (great job Taigen, they left the same battery I guess from the plastic model, for ts 5-6Kg metal one !!!)  it basically runs out of juice in 30 seconds…

So I started replacing some of the metal parts with plastic ones, from this other tank that I bought 1 year ago.

Quite heavy....

Not worth replacing the wheels… too much pain, even though I liked the plastic ones better : there are 3 of them per axle, and have some rubber around !

Metal double wheel

Plastic triple wheel

And now, the real culprit

Metal track... yes youre reading right: 0.7Kg !!!!

Plastic track

So, nearly 1.5Kg of tracks !!!!   It’s definitely worth reducing them to 300g, even if it looses the “cool factor”… I was really “feeling” for the poor motors and controllers, but now, while still quite intense, it seems much better !

17Apr – More work on the chassis

Remember 2 days ago, when I burnt turret motor controller, but was happy for the FEZ board… I was wrong !

FEZDomino burnt IC3 (LM1117MP-5)

It turns out the 5V voltage regulator on the board smoked too, and, if you can notice that little 1mm wide dent, you’ll know that it’s KO ! I thought it was fine initially, as the board stillworks, but ONLY when on USB power.

FEZDomino burnt IC3 Desoldered

Here’s the “beast” after some tricky de-soldering… The plan is to replace it with whatever I can find right now, as I can’t wait 2 days to order it on the Internet…

FEZDomino IC3 Replaced (LM7805) - ugly but it works...

And this is a LM7805, which I happen to have… it does the exact same thing (5V regulato, from up to 12V input).

It’s much uglier as you can see, but I hope more resistant, and especially it DOES the job ! (actually, only after nother hour spent “debugging” and realising that the IC4 – 3.3V regulator- had an issues too… just re-soldering it seems to have solved the problem !).

Now, the other problem is that the PPM Radio signal decoding, DOES WORK on the FEZ board, BUT it’s un-reliable. I think it’s because of the managed C# code being not real time, I end up getting plenty of rubbis data…

So I had to use a stand alone, home made duino, that all it does is reading the PPM signal, and then waiting for I2C requests from the master FEZ board and aswering with the data…

Here’s the Arduino code:

Main file


#include <Wire.h>

#define LED 13
#define MAX_CHANNELS    6  // Number of radio channels to read. Has to be <= to what the receiver outputs in its PPM signal
#define I2C_SLAVE_ADDR  0xC0 >> 1
const byte BAD_VALUE_PERC = 222;
byte NO_NEW_DATA[] = {233};

// can only send positive bytes, so shift the (-100, 100) to (0, 200)
byte _percentages[MAX_CHANNELS];  // pulses width in ticks for performance
byte _sentPercentages[MAX_CHANNELS];  // pulses width in ticks for performance

void setup(){
pinMode(LED, OUTPUT);

Wire.begin(I2C_SLAVE_ADDR); //join as slave
Wire.onRequest(onI2CRequest);

setup_radio();

}

void onI2CRequest(){
digitalWrite(LED, HIGH);
populatePercentages();
if(havePercentagesChanged()){
Wire.send(_percentages, MAX_CHANNELS);
// remember what we've sent
for(byte i=0; i<MAX_CHANNELS; i++) _sentPercentages[i] = _percentages[i];
}else{
// everything is OK here, BUT nothing new...
Wire.send(NO_NEW_DATA, 1);
}

digitalWrite(LED, LOW);
}

void loop(){
delay(100);
}

boolean havePercentagesChanged(){
for(byte i=0; i<MAX_CHANNELS; i++) if(_percentages[i] != _sentPercentages[i]) return true;
return false;
}

Radio PPM file


#define PPM_PIN     2          // External Interrupt 0 - Input Capture Pin (PPM Rx signal reading)

const int TIMER_MULT =  F_CPU / 1000000;        // Ticks per MicroSec. PRESCALER is 1. Otherwise it should also appear here !

#define TIMER_COUNT TCNT1   // use TIMER 1, 16 bits
const int MIN_VALID_PULSE = 900 * TIMER_MULT; //a valid pulse must be at least 900uS
const int MAX_VALID_PULSE = 2100 * TIMER_MULT; //a valid pulse must be less than  2100uS
const int MIN_PULSE = 1100 * TIMER_MULT;
const int MAX_PULSE = 1900 * TIMER_MULT;
const double DELTA_PULSE_PERC = 200 / (double)(MAX_PULSE - MIN_PULSE);

volatile int8_t  _rx_ch = 0;
volatile int _pulses[MAX_CHANNELS];  // pulses width in ticks for performance. Finished array.
volatile int _currentPulses[MAX_CHANNELS + 1]; //array on which the actual work is done.

void setup_radio(){
// PPM signal initialisation
pinMode(PPM_PIN, INPUT);

// TIMER 2   Pins 5 & 6  will have PPM disabled  TCNT2 increments every 16uS
TCCR1A = 0x00;
TCCR1B = 1 << CS10; // NO pre-scaling
TIMSK1 = 1 << TOIE1; //Timer1 Overflow Interrupt Enable

// whenever there is a raise in the PPM signal, deal with it
attachInterrupt(0, changeInSignalISR, RISING);
}

// Timer1 Overflow
// this gets called every 65536 (16bit counter) x TIMER_MULT microsecs
// this is 4096uS for a 16MZHz clock or 5888uS for a 11MHz clock
ISR(TIMER1_OVF_vect){
// This is definitely more than a normal pulse(as long as the F_CPU < 25MHz) so we can consider this as a sync gap, between a new PPM signal
_rx_ch = 0;
}

void changeInSignalISR(){
if(_rx_ch >= 0) _currentPulses[_rx_ch ++] = TIMER_COUNT;  //pulse for one of the channels

// always re-init the times as we always start counting "something" on a rising change
TIMER_COUNT = 0;

// this should be the last pulse, don't accept other pulses until we get a new SYNC signal
if(_rx_ch > MAX_CHANNELS){
_rx_ch = -1;
// done with a signal, "publish" it
for(byte i = 0; i<  MAX_CHANNELS; i ++) _pulses[i] = _currentPulses[i+1];
}
}

void populatePercentages(){
for(byte i=0; i < MAX_CHANNELS; i++){
if((_pulses[i] > MIN_VALID_PULSE) && (_pulses[i] < MAX_VALID_PULSE)){
_percentages[i] = constrain(int((_pulses[i] -  MIN_PULSE) * DELTA_PULSE_PERC), 0, 200);
}else{
_percentages[i] = BAD_VALUE_PERC; //ERROR
}
}
}

And the good news is that it works quite well right now…

Tank chassis working

16Apr – Wiring the turret / firing mechanism

After some quick experimentation, here’s the explanation for each of the 8 wires going from the main chassis to the turret (1 thing that I really like is that the Heng Long guys, have neatly bundled all these 8 wires into 1 single connector, making it “clean” and easy to remove the turret from the chassis):

8 wires going to the turret

After some more soldering work here’s the result:

Turret motor controller and wires

The white connector is the 8 wire original one that plugs beneath the turret.

I use 7 out of the 8 wires (for some reason the green and orange seem to be doing the same thing ?).  2 of them (for the white LED) go directly to the controller board, the other 5 go to 1 double motor controller.

For now, I only want to control the turrent left/right and fire, I don’t care too much about up/down.

And here’s what happens if one is not careful with how the wires are connected (for some reason I’m having troubles making the L293D based board work, which is really silly as it should be really straight forward…).

The good part here is that there was smoke from the FEZ board too (! lol 🙂 ) but luckily it seems to have successfully withstood the “test” 🙂

Burnt L293D motor controller, after some dodge wiring…

09Apr – Initial steps

Opened tank

Closer look at original electronics

Empty chasis

Original electronics removed

Parts that I want to replace

Closer look at the original Heng Long RX-18 board

Had to remove 1 track so that I can un screw the speaker unit...

My own electronics installed

New wiring for the tracks motors

Wires that go from the FEZ board to the tracks motors controllers

Finally, after some work, here’s the chassis with the newly wired motors, their motor controllers, the FEZ Domino controller board, and the “proper” Rx/Tx combination that I want to use:

Tracks motors, their controllers, the FEZ Domino board and the Graupner/JR Rx/Tx

7 Responses to Tiger 1 BB airsoft RC Tank

  1. judith says:

    Radio controll tank
    is a very popular toy for children. The above RC tank is looking simply awesome and also seems very easy to operate. Its design is very impressive. Thanks for sharing.

  2. Pingback: Tiger 1 BB airsoft RC Tank – V3 « Robotics / Electronics / Physical Computing

  3. Nice article mate, it’s good to see other tank enthusiasts pushing the limit. You have put a lot of effort into your rc tank posts and they are very informative! I was going toupgrade my tracks but after reading this I think I’ll leave it! I am going to link from my site to quite a few of your posts if you don’t mind?

    • trandi says:

      Thanks, of course, no problem to link to my pages, on the contrary…

      Regarding the tracks, I would say 2 things:

      1) it is maybe a matter of quality: the Taigen tank I bought, had all the possible options, but the quality is quite bad ! I suspect that the whole chassis and motors are under-dimensioned for such heavy tracks. Also, the quality of the gears and other mechanisms being low, it also makes a lot of noise and requires a lot of energy to move them…
      Maybe on a higher built quality machine, metal tracks would run smoother…

      2) i’ve only used the tank inside, and even just the NOISE of the metal tracks is enough to drive one crazy… but I can see how outside, in the dirt, one would prefer them ….

      dan

      P.S. your website looks strange, there’s no link on it, only 1 page… !?

  4. Pingback: Tiger 1 BB airsoft RC Tank – V2 « Robotics / Electronics / Physical Computing

  5. Pingback: My first H-bridge « Robotics / Electronics / Physical Computing

  6. Pingback: Graupner R700 FM receiver – get the PPM signal « Robotics / Electronics / Physical Computing

Leave a comment