[mortenbs.com home]
Music
Music
IT
IT
Videos
Videos
Contact
Contact
[icon] Robots and robotics | mortenbs.com
Last updated Jan 2012.

[icon] Project is active, and updates coming regularly...

Robotic vehicle, 24 volt DC, 2 x 400W 22A motors
Purpose of this project is to build a remotely controlled machine, strong enough -
to carry heavy things like cases of beer or even a person.
[Image] 
The robot is currently being rebuilt. Two new motors arrived from Monster Scooter parts.

Making of 24 volt robotic vehicle, mortenbs.com
How the 24 volt robotic vehichle was made. New changes and updates. Redesigning the robo, two new motors, new updated motor control, and changes of how the remote control works. Body changes, painting, welding and more. Showing the first motor control test.

[Ico] [Making of 24 volt robotic vehicle, mortenbs.com]

Mechanical parts
[Image] [Image] [Image] [Image] [Image] 

[pil] 1 x Robot body metal-skeleton
[pil] 4 x Wheels (for handtruck), bought from [Flag] primusdanmark.dk
[pil] 4 x Rear sprocket (for thin chain), bought from [Flag] skagen-pocketbike.dk
[pil] 4 x Thin chain (for pocket bike/mini crosser), bought from [Flag] skagen-pocketbike.dk
[pil] 4 x Couplings (for thin chain), bought from [Flag] skagen-pocketbike.dk
[pil] 2 x Round steel 20 mm (for shaft), bought from [Flag] egtvedstaal.dk

Electrical parts
[Image] [Image] [Image] [Image] [Image] 

[pil] 2 x Currie Technologies XYD-6D motor, 24 VDC 400W (22A), bought from [Flag] monsterscooterparts.com
[pil] 3 x Battery GF 12 22Y, Maintenance free, Motive power (from electric forklift)
[pil] 1 x Arduino Mega, bought from [Flag] electrozone.dk
[pil] 1 x E-Fly 2.4 GHz DSM transmitter
[pil] 1 x E-Fly er61-2.4 GHz DSM 6ch receiver (Using 4 of 6 channels...)
[pil] 1 x 24 volt DC motor control for two motors. (Made from power-inverter cabinet)

The 24 volt DC motor control for two motors
[Image] [Image] [Image] [Image] [Image] 

[pil] 1 x Power inverter cabinet (Aluminum)
[pil] 2 ch. analog circuit (To control the speed of the two motors from Arduino PWM signals)
[pil] 2 ch. relay H-Bridge circuit (To reverse the two motors)
[pil] 16 ch. 5v to 12v switch circuit (To control the H-Bridge from an Arduino, other relays and other 12 volt equipment)
[pil] 5 volt regulator circuit (Built into the cabinet for external 5 volt output)

[icon] Read more about the motor control in my page about DC motor control and H-Bridge...

[Animation]
Motor control wiring
ItemColorWireDestination
Ground1x black(thick)Ground
24 volt input1x red(thick)24 volt battery
12 volt input1x red(thick)12 volt battery
5 volt output1x brown(medium)External 5 volt power
Main power SW (remote)1x blue(medium)Main power switch (12v)
Motor L output2x blue(thick)Motor L power
Motor R output2x blue(thick)Motor R power
Motor L speed1x orange(thin)Arduino PWM signal
Motor R speed1x orange/white(thin)Arduino PWM signal
Motor L reverse1x brown/white(thin)Arduino digital signal
Motor R reverse1x green/white(thin)Arduino digital signal
Motor L brake1x orange/white(thin)Arduino digital signal
Motor R brake1x orange(thin)Arduino digital signal

Arduino PIN-assignments (temp while testing)
ItemPinWireTypeRangeDestination
RMT axis2-(PWM input)WORD-
RMT axis3-(PWM input)WORD-
RMT axis4-(PWM input)WORD-
RMT axis5-(PWM input)WORD-
Motor L speed6-(PWM output)BYTE [00..FF]PWM/Analog
Reverse L7brown/white(Digital output)BOOL [no/yes]Reversing relays L
Reverse R8green/white(Digital output)BOOL [no/yes]Reversing relays R
Motor R speed9-(PWM output)BYTE [00..FF]PWM/Analog
Brake L12orange/white(Digital output)BOOL [no/yes]Braking relay L
Brake R13orange(Digital output)BOOL [no/yes]Braking relay R

Robotic vehicle, 24 volt DC, Arduino source code
//Robotic vehicle motor control v1.0.00100, mortenbs.com/it/robotics
//Controlling two 24 volt DC motors from remote control, using H-Bridge.
//Project is active, and updates coming regularly...

//Currently using Duemilanove while testing, because my Arduino Mega board was damaged.
//Not enough pins on the Duemilanove for lights, so not currently in use...

//-------------|------------------------|--------------------|-----------------------------------------
const boolean  RMT_ALIGNMENT_MODE       = false;             //Use to align remote control, see below..
const boolean  USE_SERIAL_DATA          = true;              //Use serial data for status and align.
const boolean  USE_LIGHTS               = false;             //Use lights for status.
const boolean  FULL_SPEED_RELAY_ONLY    = false;             //Turn off transistors and only use extra relays when full speed
const int      SERIAL_DATA_RATE         = 9600;              //Serial data rate if enabled above
const byte     RMT_SNAPPING_PCT         = 5;                 //Snap remote values at pct: 0%, 50%, 100%
const int      LOOP_DELAY_TIME_MS       = 10;                //Main loop delay time (pause)
//-------------|------------------------|--------------------|-----------------------------------------
const byte     NONE                     = 0x00;              //Motor free run, no power
const byte     FWD                      = 0x01;              //Motor forward
const byte     REVERSE                  = 0x02;              //Motor reverse
const byte     BRAKE                    = 0x03;              //Motor brake (handbrake)
//-------------|------------------------|--------------------|-----------------------------------------
const byte     FLASHER_NONE             = NONE;              //No flash lights
const byte     FLASHER_LEFT             = 0x01;              //Flash to the left
const byte     FLASHER_RIGHT            = 0x02;              //Flash to the right
const byte     FLASHER_CATASTROPHE      = 0x03;              //Flash catastrophe / problem
const byte     FLASHER_SHIFTING         = 0x04;              //Flash shifting between left and right
//-------------|------------------------|--------------------|-----------------------------------------
const byte     PIN_MOTOR_L_SPEED        =    6;              //PWM OUTPUT, power transistor for motor
const byte     PIN_MOTOR_L_BRAKE        =   12;              //DIGITAL OUTPUT, external relay
const byte     PIN_MOTOR_L_FULL_SPEED   = NONE;              //DIGITAL OUTPUT, external relay
const byte     PIN_MOTOR_L_REVERSE      =    7;              //DIGITAL OUTPUT, internal 2st. relay
const byte     PIN_MOTOR_R_SPEED        =    9;              //PWM OUTPUT, power transistor for motor
const byte     PIN_MOTOR_R_BRAKE        =   13;              //DIGITAL OUTPUT, external relay
const byte     PIN_MOTOR_R_FULL_SPEED   = NONE;              //DIGITAL OUTPUT, external relay
const byte     PIN_MOTOR_R_REVERSE      =    8;              //DIGITAL OUTPUT, internal 2st. relay
const byte     PIN_REMOTE_CH1           =    2;              //PWM INPUT, remote control receiver ch.1
const byte     PIN_REMOTE_CH2           =    3;              //PWM INPUT, remote control receiver ch.2
const byte     PIN_REMOTE_CH3           =    4;              //PWM INPUT, remote control receiver ch.3
const byte     PIN_REMOTE_CH4           =    5;              //PWM INPUT, remote control receiver ch.4
const byte     PIN_BUZZER               = NONE;              //Buzzer (small horn)
const byte     PIN_HEADLIGHTS           =   13;              //Headlights (and rear lights)
const byte     PIN_PARKING_LIGHTS       = NONE;              //Parking lights (FRONT+REAR L+R)
const byte     PIN_FLASH_LIGHT_L        = NONE;              //Flash lights L (FRONT+REAR L)
const byte     PIN_FLASH_LIGHT_R        = NONE;              //Flash lights R (FRONT+REAR R)
const byte     PIN_BRAKE_LIGHTS         = NONE;              //Brake lights (REAR L+R)
const byte     PIN_HIGH_BEAM_LIGHTS     = NONE;              //High beam lights (FRONT L+R)
//-------------|------------------------|--------------------|-----------------------------------------
const byte     RMT_AXIS_A_HORI          = PIN_REMOTE_CH1;    //lf..rh
const byte     RMT_AXIS_A_VERT          = PIN_REMOTE_CH2;    //dn..up
const byte     RMT_AXIS_B_HORI          = PIN_REMOTE_CH4;    //lf..rh
const byte     RMT_AXIS_B_VERT          = PIN_REMOTE_CH3;    //dn..up
//-------------|------------------------|--------------------|-----------------------------------------
//Use alignment mode to adjust following settings of your remote control configuration
const int      RMT_AXIS_AH_MIN          = 1892;              //Value of ctrl when moved entirely left
const int      RMT_AXIS_AH_MAX          = 1155;              //Value of ctrl when moved entirely right
const int      RMT_AXIS_AV_MIN          = 1099;              //Value of ctrl when moved entirely down
const int      RMT_AXIS_AV_MAX          = 1876;              //Value of ctrl when moved entirely up
const int      RMT_AXIS_BH_MIN          = 1791;              //Value of ctrl when moved entirely left
const int      RMT_AXIS_BH_MAX          = 1247;              //Value of ctrl when moved entirely right
const int      RMT_AXIS_BV_MIN          = 1230;              //Value of ctrl when moved entirely down
const int      RMT_AXIS_BV_MAX          = 1830;              //Value of ctrl when moved entirely up
//-------------|------------------------|--------------------|-----------------------------------------
float          RMT_AXIS_AH_PCT          = NONE;              //Current value of that control (percents)
float          RMT_AXIS_AV_PCT          = NONE;              //Current value of that control (percents)
float          RMT_AXIS_BH_PCT          = NONE;              //Current value of that control (percents)
float          RMT_AXIS_BV_PCT          = NONE;              //Current value of that control (percents)
//-------------|------------------------|--------------------|-----------------------------------------
byte           MOTOR_L_SPEED            = NONE;              //MOTOR L SPEED (00..FF)
byte           MOTOR_L_STATE            = FWD;               //MOTOR L STATE (NONE,FWD,BRAKE,REVERSE)
byte           MOTOR_R_SPEED            = NONE;              //MOTOR R SPEED (00..FF)
byte           MOTOR_R_STATE            = FWD;               //MOTOR R STATE (NONE,FWD,BRAKE,REVERSE)
//-------------|------------------------|--------------------|-----------------------------------------
byte           FLASHER                  = FLASHER_NONE;      //Flash light state
boolean        HEADLIGHTS               = false;             //Headlights state
boolean        HIGH_BEAM_LIGHTS         = false;             //High beam lights state
boolean        PARKING_LIGHTS           = false;             //Parking lights state
boolean        BRAKE_LIGHTS             = false;             //Brake lights state
boolean        BUZZER                   = false;             //Buzzer state
boolean        FLASH_L                  = false;             //Flash light L state (managed internally)
boolean        FLASH_R                  = false;             //Flash light R state (managed internally)
boolean        REMOTE_IS_CONNECTED      = false;             //Is remote connected (managed internally)
//-------------|------------------------|--------------------|-----------------------------------------

//COMMON ROUTINES:
int readPwmPin(byte aPin){return pulseIn(aPin,HIGH,100000);}
float calcByPct(float aTotal,float aPct){if((aTotal!=NONE)&&(aPct>NONE)){return(aTotal/100)*aPct;}else{return NONE;}}
float calcPct(float aTotal,float aAmount){if((aTotal!=NONE)&&(aAmount!=NONE)){return(100/aTotal)*aAmount;}else{return NONE;}}
//-------------|------------------------|--------------------|-----------------------------------------

void setup(){                
 pinMode(PIN_MOTOR_L_SPEED        ,OUTPUT);
 pinMode(PIN_MOTOR_L_BRAKE        ,OUTPUT);
 pinMode(PIN_MOTOR_L_FULL_SPEED   ,OUTPUT);
 pinMode(PIN_MOTOR_L_REVERSE      ,OUTPUT);
 pinMode(PIN_MOTOR_R_SPEED        ,OUTPUT);
 pinMode(PIN_MOTOR_R_BRAKE        ,OUTPUT);
 pinMode(PIN_MOTOR_R_FULL_SPEED   ,OUTPUT);
 pinMode(PIN_MOTOR_R_REVERSE      ,OUTPUT);
 pinMode(PIN_REMOTE_CH1           ,INPUT);
 pinMode(PIN_REMOTE_CH2           ,INPUT);
 pinMode(PIN_REMOTE_CH3           ,INPUT);
 pinMode(PIN_REMOTE_CH4           ,INPUT);
 if(USE_LIGHTS==true){
  pinMode(PIN_BUZZER              ,OUTPUT);
  pinMode(PIN_HEADLIGHTS          ,OUTPUT);
  pinMode(PIN_PARKING_LIGHTS      ,OUTPUT);
  pinMode(PIN_FLASH_LIGHT_L       ,OUTPUT);
  pinMode(PIN_FLASH_LIGHT_R       ,OUTPUT);
  pinMode(PIN_BRAKE_LIGHTS        ,OUTPUT);
  pinMode(PIN_HIGH_BEAM_LIGHTS    ,OUTPUT); 
 }
 if(USE_SERIAL_DATA==true){Serial.begin(SERIAL_DATA_RATE);}
}

void wrtStateName(byte aState){
 if(USE_SERIAL_DATA==true){
   if(aState==FWD){Serial.print("fwd_");}else
   if(aState==REVERSE){Serial.print("reverse_");}else
   if(aState==BRAKE){Serial.print("brake_");}else
 {Serial.print("none_");}}
}

float calcRmtPct(int aValue,int aMin,int aMax){
 float v;
 if(aMax>aMin){v=calcPct(aMax-aMin,aValue-aMin);}else{v=calcPct(aMin-aMax,aValue-aMax);}
 if(v<=NONE+RMT_SNAPPING_PCT){v=NONE;}else if(v>=100-RMT_SNAPPING_PCT){v=100;}
 if((v>=50-RMT_SNAPPING_PCT)&&(v<=50+RMT_SNAPPING_PCT)){v=50;}
 return v;
}

boolean blAH=false;
boolean blBH=false;
boolean hadWelcome=false;

void welcome(){
 const byte WELCOME_PAUSE = 250;
 MOTOR_L_SPEED=NONE;MOTOR_R_SPEED=NONE;MOTOR_L_STATE=BRAKE;MOTOR_R_STATE=BRAKE;
 //..
 if(USE_LIGHTS==true){
 FLASH_L=true;          transferStates();delay(WELCOME_PAUSE);  FLASH_L=false;
 FLASH_R=true;          transferStates();delay(WELCOME_PAUSE);  FLASH_R=false;
 PARKING_LIGHTS=true;   transferStates();delay(WELCOME_PAUSE);  PARKING_LIGHTS=false;
 HEADLIGHTS=true;       transferStates();delay(WELCOME_PAUSE);  HEADLIGHTS=false;
 HIGH_BEAM_LIGHTS=true; transferStates();delay(WELCOME_PAUSE);  HIGH_BEAM_LIGHTS=false;
 BRAKE_LIGHTS=true;     transferStates();delay(WELCOME_PAUSE);  BRAKE_LIGHTS=false;
 //..
 FLASH_L=true;          transferStates();delay(WELCOME_PAUSE);  
 FLASH_R=true;          transferStates();delay(WELCOME_PAUSE);  
 PARKING_LIGHTS=true;   transferStates();delay(WELCOME_PAUSE);  
 HEADLIGHTS=true;       transferStates();delay(WELCOME_PAUSE);  
 HIGH_BEAM_LIGHTS=true; transferStates();delay(WELCOME_PAUSE);  
 BRAKE_LIGHTS=true;     transferStates();delay(WELCOME_PAUSE);  
 }
 //..
 BUZZER=true;           transferStates();delay(150);BUZZER=false;  
 //..
 FLASH_L=false;FLASH_R=false;PARKING_LIGHTS=false;HEADLIGHTS=false;
 HIGH_BEAM_LIGHTS=false;BRAKE_LIGHTS=false;hadWelcome=true;transferStates();
}

float floatAbs(float f){if(f<0){f=-f;}return f;}

float hAmt;//amount AH
float vAmt;//amount AV
float lAmt=NONE;//amount L [-100..100]
float rAmt=NONE;//amount R [-100..100]
int ah=NONE;
int av=NONE;
int bh=NONE;
int bv=NONE;
 
void readRemoteControl(){
 ah=readPwmPin(RMT_AXIS_A_HORI);RMT_AXIS_AH_PCT=calcRmtPct(ah,RMT_AXIS_AH_MIN,RMT_AXIS_AH_MAX);
 av=readPwmPin(RMT_AXIS_A_VERT);RMT_AXIS_AV_PCT=calcRmtPct(av,RMT_AXIS_AV_MIN,RMT_AXIS_AV_MAX);
 bh=readPwmPin(RMT_AXIS_B_HORI);RMT_AXIS_BH_PCT=calcRmtPct(bh,RMT_AXIS_BH_MIN,RMT_AXIS_BH_MAX);
 bv=readPwmPin(RMT_AXIS_B_VERT);RMT_AXIS_BV_PCT=calcRmtPct(bv,RMT_AXIS_BV_MIN,RMT_AXIS_BV_MAX);
 REMOTE_IS_CONNECTED=((ah!=NONE)&&(av!=NONE)&&(bh!=NONE)&&(bv!=NONE));//if any is zero, the signal is not right, it must be off.
 if(REMOTE_IS_CONNECTED==true){
  if(RMT_AXIS_AV_PCT==50){vAmt=0;}else if(RMT_AXIS_AV_PCT<50){vAmt=map(RMT_AXIS_AV_PCT,0,50,-100,0);}else{vAmt=map(RMT_AXIS_AV_PCT,50,100,0,100);}
  if(RMT_AXIS_AH_PCT==50){hAmt=0;}else if(RMT_AXIS_AH_PCT<50){hAmt=-map(RMT_AXIS_AH_PCT,0,50,-100,0);}else{hAmt=-map(RMT_AXIS_AH_PCT,50,100,0,100);}
 }else{hAmt=NONE;vAmt=NONE;}
}
 
void whenRemoteIsOff(){
 MOTOR_L_SPEED=NONE;MOTOR_L_STATE=BRAKE;
 MOTOR_R_SPEED=NONE;MOTOR_R_STATE=BRAKE;
 transferStates();hadWelcome=false;

 if(USE_SERIAL_DATA==true){Serial.print("Remote control is not connected");Serial.println(".");}
}

void mainProgram(){//ONLY RUNNING WHEN REMOTE CONTROL IS CONNECTED
 if(!hadWelcome){welcome();}//WELCOME ON STATUP AND WHEN REMOTE IS RECONNECTED...
 
 if(vAmt==NONE){//"V" IN MIDDLE
   if(hAmt==NONE){lAmt=vAmt;rAmt=vAmt;}else//"V+H" BOTH IN MIDDLE = free/brk   //ok
                 {lAmt=hAmt;rAmt=-hAmt;}//ROTATE LEFT OR RIGHT                 //ok
 }else
 if(vAmt<NONE){//"V" BELOW MIDDLE
   if(hAmt==NONE){lAmt=vAmt;rAmt=vAmt;}else//"H" IN MIDDLE = same REVERSE speed
   if(hAmt<NONE) {lAmt=(-hAmt)/2;rAmt=vAmt;}else//REVERSE and TURN LEFT
                 {lAmt=vAmt;rAmt=(hAmt)/2;}//REVERSE and TURN RIGHT
 }else{//"V" ABOVE MIDDLE
   if(hAmt==NONE){lAmt=vAmt;rAmt=vAmt;}else//"H" IN MIDDLE = same FWD speed
   if(hAmt<NONE) {lAmt=(hAmt)/2;rAmt=vAmt;}else//FWD and TURN LEFT
                 {lAmt=vAmt;rAmt=(-hAmt)/2;}//FWD and TURN RIGHT
 }
 
 //convert "amount" to "speed" and "state":
 if(lAmt==NONE){MOTOR_L_STATE=NONE;}else
 if(lAmt<NONE){MOTOR_L_STATE=REVERSE;}else{MOTOR_L_STATE=FWD;}
 MOTOR_L_SPEED=floatAbs(lAmt);
 
 if(rAmt==NONE){MOTOR_R_STATE=NONE;}else
 if(rAmt<NONE){MOTOR_R_STATE=REVERSE;}else{MOTOR_R_STATE=FWD;}
 MOTOR_R_SPEED=floatAbs(rAmt);
 
 if(MOTOR_L_STATE==BRAKE){MOTOR_L_SPEED=NONE;}//Turn off power if braking
 if(MOTOR_R_STATE==BRAKE){MOTOR_R_SPEED=NONE;}//Turn off power if braking
 
 //LIGHTS AND BUZZER
  if(USE_LIGHTS==true){

   if(MOTOR_L_STATE==BRAKE){BRAKE_LIGHTS=true;}else
   if(MOTOR_R_STATE==BRAKE){BRAKE_LIGHTS=true;}else
   BRAKE_LIGHTS=false;

   PARKING_LIGHTS=(MOTOR_L_SPEED==NONE)&&(MOTOR_R_SPEED==NONE);
   HEADLIGHTS=!PARKING_LIGHTS;

   if(MOTOR_L_SPEED>=127){HIGH_BEAM_LIGHTS=true;}else
   if(MOTOR_R_SPEED>=127){HIGH_BEAM_LIGHTS=true;}else
   HIGH_BEAM_LIGHTS=false;
 
   if((MOTOR_L_SPEED==NONE)&&(MOTOR_R_SPEED!=NONE)){FLASHER=FLASHER_LEFT;}else
   if((MOTOR_R_SPEED==NONE)&&(MOTOR_L_SPEED!=NONE)){FLASHER=FLASHER_RIGHT;}else
   FLASHER=FLASHER_NONE;

   FLASH_L=(FLASHER==FLASHER_LEFT)||(FLASHER==FLASHER_CATASTROPHE);
   FLASH_R=(FLASHER==FLASHER_RIGHT)||(FLASHER==FLASHER_CATASTROPHE);
  }
 
 transferStates();

 if(USE_SERIAL_DATA==true){
  //Serial.print("AH:");if(RMT_ALIGNMENT_MODE==true){Serial.print(ah);Serial.print(" ");}else{Serial.print(int(RMT_AXIS_AH_PCT));Serial.print("% ");}
  //Serial.print("AV:");if(RMT_ALIGNMENT_MODE==true){Serial.print(av);Serial.print(" ");}else{Serial.print(int(RMT_AXIS_AV_PCT));Serial.print("% ");}
  if(RMT_ALIGNMENT_MODE==true){
   Serial.print("AH:");Serial.print(ah);Serial.print(" ");
   Serial.print("AV:");Serial.print(av);Serial.print(" ");
   Serial.print("BH:");Serial.print(bh);Serial.print(" ");
   Serial.print("BV:");Serial.print(bv);Serial.print(" ");
  }else{
   Serial.print("BH:");Serial.print(int(RMT_AXIS_BH_PCT));Serial.print("% ");
   Serial.print("BV:");Serial.print(int(RMT_AXIS_BV_PCT));Serial.print("%. ");
  }
  Serial.print("L:");wrtStateName(MOTOR_L_STATE);Serial.print(round(lAmt));Serial.print(" ");
  Serial.print("R:");wrtStateName(MOTOR_R_STATE);Serial.print(round(rAmt));Serial.println(".");  
 }
 
}

void loop(){
 readRemoteControl();
 if(REMOTE_IS_CONNECTED==true){mainProgram();}else{whenRemoteIsOff();}
 delay(LOOP_DELAY_TIME_MS);
}

const byte FLASH_LEN=4;
byte FLASH_POS=NONE;
boolean FLASH_STATE=false;

void transferStates(){
 if(FULL_SPEED_RELAY_ONLY==true){
  if(MOTOR_L_SPEED>250){analogWrite(PIN_MOTOR_L_SPEED,NONE);}else{analogWrite(PIN_MOTOR_L_SPEED,MOTOR_L_SPEED);}
  if(MOTOR_R_SPEED>250){analogWrite(PIN_MOTOR_R_SPEED,NONE);}else{analogWrite(PIN_MOTOR_R_SPEED,MOTOR_R_SPEED);}
 }else{
  analogWrite(PIN_MOTOR_L_SPEED,MOTOR_L_SPEED);
  analogWrite(PIN_MOTOR_R_SPEED,MOTOR_R_SPEED);
 }
 
 digitalWrite(PIN_MOTOR_L_FULL_SPEED,MOTOR_L_SPEED==0xFF);
 digitalWrite(PIN_MOTOR_R_FULL_SPEED,MOTOR_R_SPEED==0xFF);
 digitalWrite(PIN_MOTOR_L_BRAKE,    MOTOR_L_STATE==BRAKE);
 digitalWrite(PIN_MOTOR_L_REVERSE,  MOTOR_L_STATE==REVERSE);
 digitalWrite(PIN_MOTOR_R_BRAKE,    MOTOR_R_STATE==BRAKE);
 digitalWrite(PIN_MOTOR_R_REVERSE,  MOTOR_R_STATE==REVERSE);
 digitalWrite(PIN_BUZZER,           BUZZER);
 if(USE_LIGHTS==true){
  FLASH_POS+=1;if(FLASH_POS>=FLASH_LEN){FLASH_STATE=!FLASH_STATE;FLASH_POS=NONE;}
  digitalWrite(PIN_HEADLIGHTS,       HEADLIGHTS);
  digitalWrite(PIN_PARKING_LIGHTS,   PARKING_LIGHTS);
  digitalWrite(PIN_FLASH_LIGHT_L,    FLASH_L&&FLASH_STATE);
  digitalWrite(PIN_FLASH_LIGHT_R,    FLASH_R&&FLASH_STATE);
  digitalWrite(PIN_BRAKE_LIGHTS,     BRAKE_LIGHTS);
  digitalWrite(PIN_HIGH_BEAM_LIGHTS, HIGH_BEAM_LIGHTS);
 }
}
Arduino source HTML generated by Arduino PDE to HTM | Mini converter, mortenbs.com




Old: Robo v1.0, my first small robotic vehicle
This was the first small robotic vehicle I made from my brothers old toy.
A new board was made to control the main- and the turning motor (in this case a small DC motor with a clutch.)
[Robo1 Image] [Skeleton Image] 

Main board and parts
[pil] A relay based H-Bridge to control the main motor.
[pil] A transistor based H-Bridge to control the turning motor.
[pil] An Arduino Duemilanove board.
[pil] A battery-pack for the Arduino.
[pil] A battery-pack for the motors.
[pil] A buzzer (for small horn).
[pil] 1 x Sharp GP2Y0A02YK0F, Infrared Proximity Sensor Long Range (front).
[pil] 2 x Sharp GP2Y0A21YK, IR distance sensor (short range) (left+right).

Also small front+rear modules was made for lights etc...
[Robo1 Front Module Image] 

Robo v1.0, first test
First test of my Arduino controlled robotic vehicle (v1.0)

[Play]  [Download video]  

Robo v1.0, Arduino source code
//-----------------------------------------------------------
//RoboOne_Ctrl v1.2.00150, mortenbs.com, updated: 2010 Jun 17
//-----------------------------------------------------------

//Control a robotic vehicle, with passive turning motor (not servo), 
//and passive driving motor. (Passive/ PLUS=fwd, MINUS=bwd)

//todo:
//BUTTON: toggle behaviour
//BUTTON: desired direction (left, right)

//CONSTANTS
//-------------|------------------------|--------------------|-----------------------------------------
const boolean  ENABLE_SERIAL_DATA       = false;             //Enable serial data
const int      SERIAL_BAUD_RATE         = 9600;              //Serial data rate (if enabled)
const byte     MAIN_ROUTINE_DELAY       = 10;                //Overall program speed
const boolean  USE_HORN                 = true;              //Enable if horn is attached
const boolean  USE_HEADLIGHTS           = true;              //Enable if headlights is attached
const boolean  USE_FLASHLIGHTS          = true;              //Enable if flashlights is attached
const int      FLASHER_LENGTH           = 40;                //Lights flasher rate
const byte     EXTRA_BWD_TIME           = 10;                //U-turning extra reversing time
const int      DISTANCE_TOLERANCE_FRONT = 220;               //Sensor tolerance value (front)
const int      DISTANCE_TOLERANCE_SIDE  = 180;               //Sensors tolerance value (side)
//-------------|------------------------|--------------------|-----------------------------------------
const byte     FWD                      = 5;                 //Main motor, move fwd (pin id)
const byte     BWD                      = 6;                 //Main motor, move bwd (pin id)
const byte     LEFT                     = 3;                 //Turning motor, turn left (pin id)
const byte     RIGHT                    = 4;                 //Turning motor, turn right (pin id)
const byte     HORN                     = 7;                 //Horn (pin id)
const byte     HEADLIGHTS               = 8;                 //Headlights (pin id)
const byte     FLASHLIGHT_LEFT          = 9;                 //Flashlight left (pin id)
const byte     FLASHLIGHT_RIGHT         = 10;                //Flashlight right (pin id)
//-------------|------------------------|--------------------|-----------------------------------------
const byte     ANLG_PIN_DISTANCE_FRONT  = 5;                 //Sharp GP2Y0A02YK0F, IR sensor
const byte     ANLG_PIN_DISTANCE_LEFT   = 0;                 //Sharp GP2Y0A21YK, IR sensor
const byte     ANLG_PIN_DISTANCE_RIGHT  = 1;                 //Sharp GP2Y0A21YK, IR sensor
//-------------|------------------------|--------------------|-----------------------------------------
const byte     DESIRED_DIRECTION        = LEFT;              //Desired turning direction

//INTERNAL CONSTS
const byte     NONE                     = 0;                 //Common NONE id
//-------------|------------------------|--------------------|-----------------------------------------
const byte     MODE_AUTONAV             = NONE;              //Auto navigation (from sensors and cfg)
const byte     MODE_ROTATION_LEFT       = 1;                 //U-turning mode, towards left
const byte     MODE_ROTATION_RIGHT      = 2;                 //U-turning mode, towards right
//-------------|------------------------|--------------------|-----------------------------------------
const byte     FLASHER_LEFT             = 1;                 //Left (turning signal)
const byte     FLASHER_RIGHT            = 2;                 //Right (turning signal)
const byte     FLASHER_BOTH             = 3;                 //Both (catastrophe)
const byte     FLASHER_SHIFT            = 4;                 //Shift (resuming program)
//-------------|------------------------|--------------------|-----------------------------------------
const byte     BEHAVIOUR_SILENT         = 1;                 //Behave as silent as possible
const byte     BEHAVIOUR_RELAXED        = 2;                 //Behave normally (relaxed)
const byte     BEHAVIOUR_ACTIVE         = 3;                 //Behave faster (active)
const byte     BEHAVIOUR_ANGRY          = 4;                 //Behave as fast as possible etc
//-------------|------------------------|--------------------|-----------------------------------------
const byte     TEMPO_SLOW               = 1;                 //Slow tempo
const byte     TEMPO_MEDIUM             = 2;                 //Medium tempo
const byte     TEMPO_FAST               = 3;                 //Fast tempo
//-------------|------------------------|--------------------|-----------------------------------------

//INTERNAL VARS
byte BEHAVIOUR=BEHAVIOUR_ACTIVE;int aMoveLen=20;int aMoveSplit=3;int aMovePos=0;boolean started=false;//speed etc
byte MODE=MODE_AUTONAV;boolean HEADLIGHTS_ON;byte DIRECTION_MOVE=NONE;byte DIRECTION_TURN=NONE;//navigation
int aFront;boolean irFront;int aLeft;boolean irLeft;int aRight;boolean irRight;//sensors
int nFlash=0;boolean blFlash=true;int nFlasher;byte nHorn=0;//flasher and horn
int n=0;int v=0;int aSensTime=0;//counters

//-----------------------------------------------------------------------------------------------------
void stopMove(){if(DIRECTION_MOVE!=NONE){DIRECTION_MOVE=NONE;}}
void stopTurn(){if(DIRECTION_TURN!=NONE){DIRECTION_TURN=NONE;}}
void turnLeft(){if(DIRECTION_TURN!=LEFT){DIRECTION_TURN=LEFT;hornBehaviour();}}
void turnRight(){if(DIRECTION_TURN!=RIGHT){DIRECTION_TURN=RIGHT;hornBehaviour();}}
void moveFwd(){if(DIRECTION_MOVE!=FWD){DIRECTION_MOVE=FWD;hornBehaviour();}}
void moveBwd(){if(DIRECTION_MOVE!=BWD){DIRECTION_MOVE=BWD;hornBehaviour();}}
void flasher(byte aFlasher){if(nFlasher!=aFlasher){nFlasher=aFlasher;nFlash=0;blFlash=true;}}
void buzzer(byte aLen){nHorn=nHorn+aLen;}
//-----------------------------------------------------------------------------------------------------

//INITIAL ROUTINE
void setup(){
 pinMode(FWD,OUTPUT);pinMode(BWD,OUTPUT);
 pinMode(LEFT,OUTPUT);pinMode(RIGHT,OUTPUT);
 pinMode(HORN,OUTPUT);pinMode(HEADLIGHTS,OUTPUT);
 pinMode(FLASHLIGHT_LEFT,OUTPUT);pinMode(FLASHLIGHT_RIGHT,OUTPUT);
 if(ENABLE_SERIAL_DATA){Serial.begin(SERIAL_BAUD_RATE);}
}

//MAIN ROUTINE
void loop(){
 if(started==false){startUp();started=true;}//start routine
 aFront=analogRead(ANLG_PIN_DISTANCE_FRONT);irFront=(aFront>=DISTANCE_TOLERANCE_FRONT);
 aLeft=analogRead(ANLG_PIN_DISTANCE_LEFT);irLeft=(aLeft>=DISTANCE_TOLERANCE_SIDE);
 aRight=analogRead(ANLG_PIN_DISTANCE_RIGHT);irRight=(aRight>=DISTANCE_TOLERANCE_SIDE);
 
 HEADLIGHTS_ON=true
 if(MODE==MODE_AUTONAV){autoNav();}else
 if(MODE==MODE_ROTATION_LEFT){rotation(false);}else
 if(MODE==MODE_ROTATION_RIGHT){rotation(true);}

 update();
}

void resumeTaskMode(byte aDestMode){
 MODE=0;DIRECTION_MOVE=NONE;DIRECTION_TURN=NONE;HEADLIGHTS_ON=false;
 flasher(FLASHER_SHIFT);n=0;while(n<500){n=n+1;update();}//flasher shifting... (resuming)
 flasher(NONE);n=0;while(n<100){n=n+1;update();}//flasher none...
 MODE=aDestMode;aSensTime=0;n=0;v=0;
}

void abortAutoNav(byte aDestMode){//is used if sensor in very long time, it tries something else (aDestMode)
 DIRECTION_MOVE=NONE;DIRECTION_TURN=NONE;
 buzzer(50);HEADLIGHTS_ON=false;//lights off
 flasher(FLASHER_BOTH);n=0;while(n<500){n=n+1;update();}//flasher catastrophe... (problem)
 resumeTaskMode(aDestMode);buzzer(30);
}

void pullInReverse(byte aDestMode){//is used if sensor and high speed FWD, it will pull in reverse for some time.
 digitalWrite(FWD,false);digitalWrite(BWD,true);//IMMEDIATELY PULL IN REVERSE
 digitalWrite(LEFT,true);digitalWrite(RIGHT,true);
 digitalWrite(HEADLIGHTS,false);digitalWrite(HORN,true);
 delay(200);
 MODE=aDestMode;DIRECTION_MOVE=NONE;DIRECTION_TURN=NONE;aSensTime=0;n=0;v=0;//THEN RESUME
}

void autoNav(){n=0;v=0;nFlasher=NONE;
 if(irLeft||irRight){aSensTime=aSensTime+1;}else{aSensTime=0;}//Serial.println(aSensTime);
 if(aSensTime>=500){if(DESIRED_DIRECTION==RIGHT){abortAutoNav(MODE_ROTATION_RIGHT);}else{abortAutoNav(MODE_ROTATION_LEFT);}}else
 if(irFront&&irLeft&&irRight){tempo(TEMPO_SLOW);moveBwd();stopTurn();}else//MOVE BWD (slow speed)
 //if(irFront&&irLeft){tempo(TEMPO_MEDIUM);MODE=MODE_ROTATION_RIGHT;}else//ROTATE RIGHT
 //if(irFront&&irRight){tempo(TEMPO_MEDIUM);MODE=MODE_ROTATION_LEFT;}else//ROTATE LEFT
 if(irFront&&irLeft){if(DESIRED_DIRECTION==RIGHT){MODE=MODE_ROTATION_RIGHT;}else{MODE=MODE_ROTATION_LEFT;}}else//ROTATE TOWARDS DESIRED DIRECTION
 if(irFront&&irRight){if(DESIRED_DIRECTION==RIGHT){MODE=MODE_ROTATION_RIGHT;}else{MODE=MODE_ROTATION_LEFT;}}else//ROTATE TOWARDS DESIRED DIRECTION
 if(irLeft&irRight){tempo(TEMPO_MEDIUM);moveBwd();stopTurn();}else//MOVE BWD (turn smallest navigation) (medium speed)
 if(irLeft){tempo(TEMPO_MEDIUM);moveFwd();turnRight();}else//MOVE FWD, and TURN RIGHT (medium speed)
 if(irRight){tempo(TEMPO_MEDIUM);moveFwd();turnLeft();}else{//MOVE FWD, and TURN LEFT (medium speed)
 if(irFront){pullInReverse(MODE_ROTATION_LEFT);}else//ROTATE TO SMALLEST
  tempo(TEMPO_FAST);moveFwd();stopTurn();//MOVE FWD (fast speed)
 }  
}

void rotation(boolean aToRight){n=n+1;
 byte aLen;byte aPause;byte aPauseTurn;

 switch(BEHAVIOUR){
  case BEHAVIOUR_SILENT:aLen=10;aPause=100;aPauseTurn=35;break;
  case BEHAVIOUR_RELAXED:aLen=10;aPause=15;aPauseTurn=25;break;
  case BEHAVIOUR_ACTIVE:aLen=10;aPause=12;aPauseTurn=20;break;
  case BEHAVIOUR_ANGRY:aLen=8;aPause=10;aPauseTurn=15;break;
 }

 if(aToRight){flasher(FLASHER_RIGHT);}else{flasher(FLASHER_LEFT);}
 if(n>aPause+aPauseTurn+aLen+EXTRA_BWD_TIME+aPause+aPauseTurn+aLen){v=v+1;if(v<3){n=0;}else{MODE=MODE_AUTONAV;}}else
 if(n>aPause+aPauseTurn+aLen+EXTRA_BWD_TIME+aPause+aPauseTurn){moveFwd();}else
 if(n>aPause+aPauseTurn+aLen+EXTRA_BWD_TIME+aPause){if(aToRight){turnRight();}else{turnLeft();}}else
 if(n>aPause+aPauseTurn+aLen+EXTRA_BWD_TIME){stopMove();stopTurn();}else
 if(n>aPause+aPauseTurn){moveBwd();}else
 if(n>aPause){if(aToRight){turnLeft();}else{turnRight();}}else
 if(n>=0){stopMove();stopTurn();}
}

void tempo(byte aTempo){
 switch(BEHAVIOUR){
  case BEHAVIOUR_SILENT:switch(aTempo){
   case TEMPO_SLOW:aMoveLen=60;aMoveSplit=2;break;    //SILENT SLOW
   case TEMPO_FAST:aMoveLen=60;aMoveSplit=4;break;    //SILENT FAST
  default:aMoveLen=60;aMoveSplit=3;break;}break;      //SILENT MEDIUM
  case BEHAVIOUR_RELAXED:switch(aTempo){
   case TEMPO_SLOW:aMoveLen=30;aMoveSplit=2;break;    //RELAXED SLOW
   case TEMPO_FAST:aMoveLen=30;aMoveSplit=4;break;    //RELAXED FAST
  default:aMoveLen=30;aMoveSplit=3;break;}break;      //RELAXED MEDIUM
  case BEHAVIOUR_ACTIVE:switch(aTempo){
   case TEMPO_SLOW:aMoveLen=20;aMoveSplit=3;break;    //ACTIVE SLOW
   case TEMPO_FAST:aMoveLen=20;aMoveSplit=6;break;    //ACTIVE FAST
  default:aMoveLen=25;aMoveSplit=5;break;}break;      //ACTIVE MEDIUM
  case BEHAVIOUR_ANGRY:switch(aTempo){
   case TEMPO_SLOW:aMoveLen=15;aMoveSplit=3;break;    //ANGRY SLOW
   case TEMPO_FAST:aMoveLen=15;aMoveSplit=5;break;    //ANGRY FAST
  default:aMoveLen=15;aMoveSplit=4;break;}break;      //ANGRY MEDIUM
 }
}

void hornBehaviour(){
 switch(BEHAVIOUR){
  //case BEHAVIOUR_SILENT:break;
  //case BEHAVIOUR_RELAXED:break;
  case BEHAVIOUR_ACTIVE:buzzer(1);break;
  case BEHAVIOUR_ANGRY:buzzer(2);break;
 }
}

void startUp(){//startup routine (welcome)
 DIRECTION_MOVE=NONE;DIRECTION_TURN=NONE;
 HEADLIGHTS_ON=false;//lights off
 flasher(FLASHER_BOTH);n=0;while(n<250){n=n+1;update();}//flasher catastrophe... (problem)
 resumeTaskMode(MODE_AUTONAV);buzzer(30);
}

//-----------------------------------------------------------------------------------------------------
void update(){
 aMovePos=aMovePos+1;if(aMovePos>aMoveLen){aMovePos=0;}//MOVING SPEED BALANCE
 digitalWrite(FWD,(DIRECTION_MOVE==FWD)&&((MODE!=MODE_AUTONAV)||(aMovePos<=aMoveSplit)));//MOVE FWD
 digitalWrite(BWD,(DIRECTION_MOVE==BWD)&&((MODE!=MODE_AUTONAV)||(aMovePos<=aMoveSplit)));//MOVE BWD
 digitalWrite(LEFT,DIRECTION_TURN==LEFT);//TURN LEFT
 digitalWrite(RIGHT,DIRECTION_TURN==RIGHT);//TURN RIGHT
 digitalWrite(HEADLIGHTS,HEADLIGHTS_ON&&USE_HEADLIGHTS);digitalWrite(HORN,USE_HORN&&(nHorn>0));if(nHorn>0){nHorn=nHorn-1;}//HEADLIGHTS AND HORN
 if(USE_FLASHLIGHTS){nFlash=nFlash+1;if(nFlash>=FLASHER_LENGTH){nFlash=0;blFlash=blFlash==false;}//MANAGE FLASHER
  digitalWrite(FLASHLIGHT_LEFT,blFlash&&((nFlasher==FLASHER_LEFT)||(nFlasher==FLASHER_BOTH)||(nFlasher==FLASHER_SHIFT)));//FLASH LEFT
  digitalWrite(FLASHLIGHT_RIGHT,(blFlash&&((nFlasher==FLASHER_RIGHT)||(nFlasher==FLASHER_BOTH)))||((nFlasher==FLASHER_SHIFT)&&(blFlash==false)));//FLASH RIGHT
 }delay(MAIN_ROUTINE_DELAY); 
}
Arduino source HTML generated by Arduino PDE to HTM | Mini converter, mortenbs.com

Robo v1.0, Arduino real time control [720p]
Real time controlling an Arduino-board using a PC-program

[Play]  [Download video]  



WiFi realtime controlling small robot vehicle
Small vehicle overloaded with BIG computer, testing the real-time controller over a WiFi connection.

[Play]  [Download video]  








Small robotics from B. Laursen

Second Arduino Robot of B. Laursen (Jun 2010)
Small 4WD robotic vehicle made by B. Laursen. It uses an ultrasonic distance sensor.

[Play]  [Download video]  

First Arduino Robot of B. Laursen (May 2009)
Small robotic vehicle made by B. Laursen. It had a Sharp IR Sensor attached to it.

[Play]  [Download video]  




[pil] Your comment or message

See also
[icon] Arduino - Arduino source code examples, Arduino projects and circuits, robotic projects and more....
[icon] DC motor control and H-Bridge - A digital motor control is able to turn the motor on/off, and maybe even reverse the...
[icon] Small circuits - Small electronic circuits. Delayed power on circuit, Delayed power off circuit, A simple...
[icon] Resistor - A resistor is used to lower the voltage in an electronic circuit. Resistor color values...
[icon] Transistor - A transistor is by it self a small power inverter. NPN-transistors reacts to positive and...
[icon] Videos - List of videos that are available on the mortenbs.com website.
[icon] IT - IT/Technology. Various projects and information about computer technology and electronic...


[icon] mortenbs.com