M.N.S.T.R. (Motion Navigated & Steered Tactical Rover)

Introduction

The M.N.S.T.R. is a rebuild of a Tyco Batman remote control monster truck from 2004. Unlike the original design that used joysticks on a simple RC remote to drive the vehicle, the modifications made allow M.N.S.T.R.’s speed and direction to be wirelessly controlled by the user’s hand motions. The rebuild of the vehicle included installing a new COTS DC motor driver to control the back wheels, as well as a servo driver and servo to control the M.N.S.T.R.’s steering. The servo mount and front-wheel control were redesigned in Fusion 360. An Arduino Nano is used to control both the DC motor driver and the servo driver. A custom remote control was made with a gyroscope breakout board and an Arduino Nano, as well as a pair of SPI antennae for wireless communications.

Mechanical

The M.N.S.T.R. required a fair amount of mechanical reconstruction–far more than most other projects. Almost all of the injection-molded spokes used to hold the PCB and internal battery were removed to provide a large cavity for new electronics. The existing PCB for the monster truck was clearly dated as it was entirely through-hole technology and appears to have used relays for motor control as opposed to MOSFETs. After ripping out the old PCB, I deemed the existing front-axle servo unusable. Replacing the servo required a custom motor-mount and custom “off-axis” attachment. This servo structure can be seen in the picture to the right. These parts were printed with clear PETG filament.

As much as I like Batman, I prefer my cover to the Batmobile-themed cover already on the vehicle. Collectively, all parts of the cover for M.N.S.T.R. took about 28 hours to print and were printed in PLA. This cover was designed in Fusion 360 with modularity in mind. To allow for various attachments, the cover has a 1/2″ grid of 3/8″ holes. These holes have been used for cameras and will possibly have lights in the future.

Electrical

As previously mentioned, the electronics in the monster truck were dated to say the least and the only electronics kept from the original vehicle was the rear drive motor. The original NiMH battery was replaced by a beefy 12V 8Ah SLA tractor battery. In order to tame this battery, a DROK 100W Voltage Regulator was used to bring the 12V motor down to 5V. I was never able to determine the actual voltage of the motor because it was buried by many layers of screws and would require a complete disassembly of the wheel configuration to do proper motor testing. To drive the motor, a DROK 16A PWM H-Bridge was used. The servo was driven using an Adafruit PWM/Servo driver. Most of this project was designed with COTS in mind, and a custom PCB was not designed because of the large size required. Instead, an Arduino Nano was soldered to perfboard and the wires required to control the motor driver and servo were just soldered to the perfboard. For the wireless communication, a set of 2.4GHz nRF24L01+ radio transceivers was used between the vehicle and the controller.

  • (1) – Arduino Nano
  • (1) – DROK 100W Voltage Regulator
  • (1) – DROK H-Bridge Motor Driver
  • (1) – nRF24L01+ Radio Transceiver
  • (1) – MG996R Servo
  • (1) – Adafruit 16-Channel 12-bit PWM/Servo Driver

The controller is pretty minimalistic consisting of an Arduino Nano, voltage regulator, gyroscope, and transceiver. Using a 9V battery and a standard LM7805 5V regulator, the voltage was brought down to the 5V required by the Arduino and other components.

  • (1) – Arduino Nano
  • (1) – LM7805 5V Regulator
  • (1) – MPU6050 Gyroscope Breakout
  • (1) – nRF24L01+ Radio Transceiver

Operation

The operating principle of the M.N.S.T.R. is simple: tilt hand, move vehicle. Specifically, the pitch and roll of one’s hand is detected to determine the drive direction and speed, as well as left or right turn. This information is collected by the Arduino on the controller and relayed to the vehicle with the transceivers. Once the vehicle reads this data, the Arduino on the M.N.S.T.R. determines how hard to drive the vehicle and in what direction, tilting the servo accordingly. Overall, the vehicle is fairly responsive with a small caveat of servo drift.

Arson

You may have noticed the hole in the front cover of the M.N.S.T.R. as well as a firing sequence in the code for the vehicle. Clearly this hole had a purpose and this code is intentional. This feature of M.N.S.T.R. is technically a work-in-progress. The ultimate goal of the M.N.S.T.R. is to attach a flamethrower internal to the vehicle. Though not shown in the picture of the M.N.S.T.R., there are now two brackets on each side of the vehicle for use as clamps to hold small propane tanks. These tanks feed into a hole in the back section of the vehicle to a set of two solenoid valves secured to the inside of the M.N.S.T.R.’s cover. In between these valves is a small tube section. The functional principle behind this tank is for the solenoid closest to the tanks to open, filling the small tube section in the middle with propane. This will then close, sealing off the main gas supply. Following this, the other valve would open to release the gas to the outside world. In conjunction to this gas release, an arc lighter would be triggered to light the gas. This system was tested independently of M.N.S.T.R. and introduced its own challenges. Specifically, there was a tendency for the valve closest to the outside world to literally freeze open due to the freezing temperatures of the decompressing propane gas leaving the small tube section. Clearly this system needs more thought before I strap it to a remote control vehicle.

M.N.S.T.R. Code

/*---------------------------------------------------------------
Even Industries
M.N.S.T.R.
Engineer: Joseph Even
Description: Complete code for M.N.S.T.R. 
----------------------------------------------------------------*/


//Servo
#include 
#include 
Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();

//Radio
#include 
#include 
#include 
RF24 radio(8, 10); // CE, CSN
unsigned long i = 0;
const byte address[6] = "00001";

float strictMap(float val, float inmin, float inmax, float outmin, float outmax);

void fill_stage();
void fire_stage();

//------------------------- PIN ASSIGNMENTS ----------------------------------------------------------------------------------//

// Radio
//D8 - CE
//D10 - CSN
//D11 - MOSI
//D12 - MISO
//D13 - SCK


//Steering Motor (I2C)
// A4 - SDA
// A5 - SCL

//Rear Motor
byte PWM1 = 3; // Rear Motor PWM      (D3) (to DROK PWM1)
byte D1   = 2; // Rear Motor H-Bridge (D2) (to DROK D1) ( 1 = Forward, 0 = Backward)

//Mount
byte valve1 = 4;    // Chamber Valve  (D3)  (to transistor for solenoid 1)
byte valve2 = 5;    // Outlet Valve   (D4)  (to transistor for solenoid 2)
byte spark  = 6;    // Lighter Control  (D3)  (to transistor for lighter)

//Misc.



//------------------------- End PIN ASSIGNMENTS --------------------------------------------------------------------------------//




//------------------------- VARIABLES -----------------------------------------------------------------------------------------//

//Radio
byte steer_in = 0;
byte speed_in = 0;
byte fire_in = 0;

//Steering Motor
int servo_max = 430;
int servo_min = 200;
int servo_out = 0;


//Rear Motor
int speed_out = 0;


//Mount
bool fire = 0;
byte fire_state = 0;
int fire_delay = 10000; // Amount of time between firing cycles
int fill_time = 2000;   // Amount of time for gas to fill chamber
int spark_delay = 500;  // Amount of time after gas released before spark
int spark_time = 1000;  // Amount of time lighter is on
int fire_time = 3000;   // Amount of time for gas to be released

// TIMERS
unsigned long previousMillis  = 0;
unsigned long currentMillis   = 0;


unsigned long successCommMillis = 0;
unsigned long comms_timeout = 3000; //Amount of time radios can not retrieve signal before timing out

unsigned long previousFireMillis   = 0;
unsigned long startFillMillis   = 0;
unsigned long startFireMillis   = 0;
unsigned long fireButtonMillis  = 0;

//------------------------- END VARIABLES -------------------------------------------------------------------------------------//




void setup() {

  Serial.begin(115200);
  currentMillis = millis();

  // Radio Setup
  radio.begin();
  radio.openReadingPipe(0, address);
  radio.setPALevel(RF24_PA_MIN);
  radio.startListening();


  // Steering Setup
    pwm.begin();
    pwm.setPWMFreq(50);  // Analog servos run at ~50 Hz updates
    delay(10);

  // Motor Setup
    pinMode(PWM1, OUTPUT);
    pinMode(D1, OUTPUT);

} // End setup




void loop() {
  currentMillis = millis();

  if (radio.available()) {
    byte control[3];
    radio.read(&control, sizeof(control));
    steer_in = control[0];
    speed_in = control[1];
    fire_in = control[2];
    
    successCommMillis = millis();
  }

  /*
  if { // Unsuccessful Comms
    if ( (currentMillis - successCommMillis) > comms_timeout) { 
      // With unsuccesful comms, set rover to stationary
        digitalWrite(D1, HIGH);
        speed_out = 0;
        analogWrite(PWM1, speed_out);
    }
  }
*/
 

//------------------------- SERVO CONTROL (Will be receiving raw value of 0 - 255 from Wireless)-------------------------------//
    
    
    servo_out = strictMap(steer_in, 0, 255, servo_min, servo_max);

    if ( ( steer_in < 143 ) && ( steer_in > 112 ) ) { // Adds a range of centered wheels
      servo_out = ( ( servo_max + servo_min ) / 2 ); // Middle servo position
    }

    pwm.setPWM(15, 0, servo_out);
//------------------------- END SERVO CONTROL --------------------------------------------------------------------------------//





//------------------------- MOTOR CONTROL (Will be receiving raw value of 0 - 255 from Wireless)-------------------------------//
    
    // Forward
    if ( speed_in > 143 )  {
      // H-Bridge Control
      digitalWrite(D1, HIGH);
      speed_out = strictMap(speed_in, 143, 255, 10, 255); // Makes valid PWM range
      analogWrite(PWM1, speed_out);
    } // End forward

    // Backward
    else if ( speed_in < 112 ) {       // H-Bridge Control       
digitalWrite(D1, LOW);       
speed_in = abs( speed_in - 112 );       
speed_out = strictMap(speed_in, 0, 112, 10, 255); // Makes valid PWM range       
analogWrite(PWM1, speed_out); 
    }  // End Backward     
// Stationary     
else {       
digitalWrite(D1, HIGH);       
speed_out = 0;       
analogWrite(PWM1, speed_out); 
} // End Stationary 
//------------------------- END MOTOR CONTROL --------------------------------------------------------------------------------// 

//-------------------------MOUNT CONTROL -------------------------------------------------------------------------------------// 
if ( (fire_in = 1) &&  (currentMillis - previousFireMillis) > fire_delay ) {
  fire_state = 1;
  fireButtonMillis = millis(); 
} 

switch(fire_state) {
  case 0: // Wait State
  break;
  
  case 1: // Fill Stage
    fill_stage();
  break; 
    
  case 2: // Fire Stage
    fire_stage();
  break;
  
  default : fire_state = 0;

} // End Switch

//-------------------------SERIAL PRINT -------------------------------------------------------------------------------------//
    Serial.print("Steer In: ");Serial.print(steer_in);
    Serial.print("  Steer Out: ");Serial.print(servo_out);
    Serial.print("  Speed In: ");Serial.print(speed_in);
    Serial.print("  Speed Out: ");Serial.print(speed_out);
    
    Serial.print("  Fire In: ");Serial.print(fire_in);
    Serial.print("  Fire Out: ");Serial.print(fire_in);
    Serial.println();
    
    
   
    
    previousMillis = currentMillis;
    delay(20);
} // End Loop





void fill_stage() {
  digitalWrite(valve1, HIGH); // Open Valve 1
  if ( (currentMillis - fireButtonMillis) > fill_time ) {
    digitalWrite(valve1, LOW);  // Close Valve 1
    delay(20);
    fire_state = fire_state + 1;
  }

} // End fill_stage



void fire_stage() {
  digitalWrite(valve2, HIGH); // Open Valve 2
  if ( (currentMillis - fireButtonMillis) > (fill_time + spark_delay) ) {
    // For single start of lighter during firing state
    digitalWrite(spark, HIGH);
    if ( (currentMillis - fireButtonMillis) > (fill_time + spark_delay + spark_time) ) {
      digitalWrite(spark, LOW);
  }

    /* For repetitive starts of lighter during firing state
    for (int i=0; i <= spark_cycles ; i++){       
digitalWrite(spark, HIGH);       
delay(5);       
digitalWrite(spark, LOW);      
delay(5);     
}     */     
}   
if ( (currentMillis - fireButtonMillis) > (fill_time + spark_delay + spark_time + fire_time) ) {
    digitalWrite(valve2, LOW);  // Close Valve 2
    fire_state = 0;
  }
  
  previousFireMillis = millis(); 

}  // End fire_stage

float strictMap(float val, float inmin, float inmax, float outmin, float outmax) {
  if (val <= inmin) return outmin;   if (val >= inmax) return outmax;
  return (val - inmin)*(outmax - outmin)/(inmax - inmin) + outmin;
}






M.N.S.T.R. Controller Code

/*---------------------------------------------------------------
Even Industries
M.N.S.T.R.
Engineer: Joseph Even
Description: Complete code for M.N.S.T.R. Remote Control
----------------------------------------------------------------*/

//MPU
  #include 
  #include 
  MPU6050 mpu;

//Radio
  #include 
  #include 
  #include 
  
  RF24 radio(10, 8); // CE, CSN
  
  const byte address[6] = "00001";

float strictMap(float val, float inmin, float inmax, float outmin, float outmax);

//------------------------- PIN ASSIGNMENTS ----------------------------------------------------------------------------------//

// Radio
//D8 - CE
//D10 - CSN
//D11 - MOSI
//D12 - MISO
//D13 - SCK

//MPU 6050 (I2C)
// A4 - SDA
// A5 - SCL

//Mount
byte trigger = 2; // Button for Mount Control (D2) (Wired With Button)

//Misc.
byte comms = 3; // Light blinks confirming successful communication between controller and MNSTR

//------------------------- VARIABLES -----------------------------------------------------------------------------------------//

  //Generic Timer
    int currentMillis = 0;  
    int previousMillis = 0;
    
  // MPU6050 (GY-521)
    
    // Timers
      unsigned long timer = 0;
      float timeStep = 0.01;
      
    // Pitch, Roll and Yaw values
      float pitch = 0;
      float roll = 0;
      float yaw = 0;
  
  // Steering Motor (ROLL)
    unsigned long last_direction = 0; 
    int direction_period = 100;
    float roll_old = 0;
    float roll_new = 0;
    int steer_out = 127;
    
  
  //Rear Motor (PITCH)
    float speed_jitter_threshold = 3; 
    float pitch_old = 0;
    float pitch_new = 0;
    int pitch_map = 0;
    int speed_out = 127;
    
  
  //Mount
   byte fire = 0;
  
//------------------------- SETUP -----------------------------------------------------------------------------------------//
void setup() {
  int previousMillis = millis();
  
  // Serial Comms
  Serial.begin(115200);

  // Mount Control
  pinMode(trigger, INPUT_PULLUP);
  
  
  // MPU6050

    // Initialize MPU6050
    while(!mpu.begin(MPU6050_SCALE_2000DPS, MPU6050_RANGE_2G))
    {
      Serial.println("Could not find a valid MPU6050 sensor, check wiring!");
      delay(500);
    }
    
    // Calibrate gyroscope. The calibration must be at rest.
    // If you don't want calibrate, comment this line.
    mpu.calibrateGyro();
  
    // Set threshold sensivty. Default 3.
    // If you don't want use threshold, comment this line or set 0.
    mpu.setThreshold(3);


  // Radio
    radio.begin();
    radio.openWritingPipe(address);
    radio.setPALevel(RF24_PA_MIN);
    radio.stopListening();
  
}

//------------------------- LOOP -----------------------------------------------------------------------------------------//
void loop() {
    
  currentMillis = millis();
  
  int fire = 0; // Reduces chance of misfires
  
  //MPU6050
  timer = millis();
  
  Vector normAccel = mpu.readNormalizeAccel();

  // Calculate Pitch & Roll
  int pitch = (atan2(normAccel.XAxis, sqrt(normAccel.YAxis*normAccel.YAxis + normAccel.ZAxis*normAccel.ZAxis))*180.0)/M_PI;
  int roll = -(atan2(normAccel.YAxis, normAccel.ZAxis)*180.0)/M_PI;

 
  
 //------------------------- SERVO CONTROL -----------------------------------------------------------------------------------//
  
  roll_new = roll;
  
  if ( (currentMillis - last_direction)  >  direction_period ) {
    // If statement used to reduce servo jitter 
    steer_out = strictMap(roll_new, -45, 45, 0, 255);// Makes valid byte size for transmission with constraints
    roll_old = roll_new;
    last_direction = millis();
  }

//------------------------- MOTOR CONTROL ------------------------------------------------------------------------------------// 
  pitch_new = pitch;
  
  if ( abs( abs(pitch_new) - abs(pitch_old) ) >  speed_jitter_threshold ) {
    // If statement used to reduce jitter in motor speed
    speed_out = strictMap(pitch_new, -45, 45, 0, 255);// Makes valid byte size for transmission with constraints
    pitch_old = pitch_new;
  }
  

//-------------------------MOUNT CONTROL -------------------------------------------------------------------------------------//
  if (digitalRead(trigger) == LOW) {
    fire = 1;
  }
    

//-------------------------RADIO CONTROL -------------------------------------------------------------------------------------//
  byte control[3]; //Create byte to send wireless data
  control[0]= steer_out; 
  control[1]= speed_out;
  control[2]= fire;
  radio.write(&control, sizeof(control));

  

//-------------------------SERIAL COMMS-------------------------------------------------------------------------------------//

Serial.print("Steer: "); Serial.print(steer_out);
Serial.print("  Speed: "); Serial.print(speed_out);
Serial.print("  Fire: "); Serial.println(fire);
Serial.println("");


  previousMillis = currentMillis;
  
}

//------------------------- END LOOP -----------------------------------------------------------------------------------------//





float strictMap(float val, float inmin, float inmax, float outmin, float outmax) {
  if (val <= inmin) return outmin; if (val >= inmax) return outmax;
  return (val - inmin)*(outmax - outmin)/(inmax - inmin) + outmin;
}