James Martel
Published © GPL3+

What Do I Build Next? RC Tank with 4DOF Arm

What Do I Build Next? This time a RC Tank with a 4DOF arm controlled with a PS2 controller. Sounds easy... Not

BeginnerFull instructions provided2 hours1,099
What Do I Build Next? RC Tank with 4DOF Arm

Things used in this project

Hardware components

Amazon Web Services RC Tank kit with 4DOF ARM
×1
Amazon Web Services 18650 batteries
×4
Amazon Web Services AAA battery
×2

Software apps and online services

Arduino IDE
Arduino IDE
Amazon Web Services Makerbuying-Small Hammer Website

Hand tools and fabrication machines

Phillips screwdriver
Plier, Long Nose
Plier, Long Nose
Plier, Cutting
Plier, Cutting

Story

Read more

Schematics

interconnect

interconnect two

Code

PS2X_ArmCar_Shield

Arduino
#include "PS2X_lib.h"  //for v1.6
#include <Wire.h>
#include "Adafruit_MotorShield.h"
#include "Adafruit_MS_PWMServoDriver.h"

/******************************************************************
 * set pins connected to PS2 controller:
 *   - 1e column: original 
 *   - 2e colmun: Stef?
 * replace pin numbers by the ones you use
 ******************************************************************/
#define PS2_DAT        12  
#define PS2_CMD        11  
#define PS2_SEL        10 
#define PS2_CLK        13 

/******************************************************************
 * select modes of PS2 controller:
 *   - pressures = analog reading of push-butttons 
 *   - rumble    = motor rumbling
 * uncomment 1 of the lines for each mode selection
 ******************************************************************/
//#define pressures   true
#define pressures   true 
//#define rumble      true
#define rumble      true

PS2X ps2x; // create PS2 Controller Class

//right now, the library does NOT support hot pluggable controllers, meaning 
//you must always either restart your Arduino after you connect the controller, 
//or call config_gamepad(pins) again after connecting the controller.

int error = 0;
byte type = 0;
byte vibrate = 0;

int lx = 0;
int ly=  0;
int L_Speed = 0;
int R_Speed = 0;
// Create the motor shield object with the default I2C address
Adafruit_MotorShield AFMS = Adafruit_MotorShield(); 
// Or, create it with a different I2C address (say for stacking)
// Adafruit_MotorShield AFMS = Adafruit_MotorShield(0x61); 

// Select which 'port' M1, M2, M3 or M4. In this case, M1
Adafruit_DCMotor *L_M3 = AFMS.getMotor(3);
Adafruit_DCMotor *R_M4 = AFMS.getMotor(4);
// You can also make another motor on port M2
//Adafruit_DCMotor *myOtherMotor = AFMS.getMotor(2);


const int SERVOS = 4;
const int ACC = 10; // the accurancy of the potentiometer value before idle starts counting
int PIN[SERVOS], value[SERVOS], idle[SERVOS], currentAngle[SERVOS], MIN[SERVOS], MAX[SERVOS], INITANGLE[SERVOS], previousAngle[SERVOS],ANA[SERVOS];

void setServoPulse(uint8_t n, double pulse) {
  double pulselength;
  pulselength = 1000000;   // 1,000,000 us per second
  pulselength /= 50;   // 50 Hz
  Serial.print(pulselength); Serial.println(" us per period"); 
  pulselength /= 4096;  // 12 bits of resolution
  Serial.print(pulselength); Serial.println(" us per bit"); 
  pulse *= 1000;
  pulse /= pulselength;
  Serial.println(pulse);
  AFMS.setPWM(n, pulse);
}

// Angle to PWM
void writeServo(uint8_t n,uint8_t angle){
  double pulse;
  pulse=0.5+angle/90.0;
  setServoPulse(n,pulse);
}

void setup(){
  Serial.begin(57600);
  delay(2000);  //added delay to give wireless ps2 module some time to startup, before configuring it
  Serial.print("Search Controller..");
  //CHANGES for v1.6 HERE!!! **************PAY ATTENTION*************
  do{
  //setup pins and settings: GamePad(clock, command, attention, data, Pressures?, Rumble?) check for error
    error = ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT, pressures, rumble);
    if(error == 0){
      Serial.println("\nConfigured successful ");
      break;
    }else{
      Serial.print(".");
      delay(100);
    }
  }while(1);  
  type = ps2x.readType(); 
  switch(type) {
    case 0:
      Serial.println("Unknown Controller type found ");
      break;
    case 1:
      Serial.println("DualShock Controller found ");
      break;
    case 2:
      Serial.println("GuitarHero Controller found ");
      break;
    case 3:
      Serial.println("Wireless Sony DualShock Controller found ");
      break;
   }
   ps2x.read_gamepad(true, 200);
   delay(500);
   ps2x.read_gamepad(false, 200);
   delay(300);
   ps2x.read_gamepad(true, 200);
   delay(500);
   
    //Middle Servo
  PIN[0] = 0;
  MIN[0] = 10;
  MAX[0] = 170;
  INITANGLE[0] = 90;
  ANA[0] = 3;
  //Left Side
  PIN[1] = 1;
  MIN[1] = 10; // This should bring the lever to just below 90deg to ground
  MAX[1] = 140;
  INITANGLE[1] = 90; // This should bring the lever parallel with the ground
  ANA[1] = 2;
  //Right Side
  PIN[2] = 14;
  MIN[2] = 40;
  MAX[2] = 170;
  INITANGLE[2] = 90;
  ANA[2] = 0;
  //Claw Servo
  PIN[3] = 15;
  MIN[3] = 0;
  MAX[3] = 120;
  INITANGLE[3] = 60;
  ANA[3] = 1;
  
  AFMS.begin(50);  // create with the default frequency 1.6KHz
  for (int i = 0; i < SERVOS; i++){
    value[i] = 0;
    idle[i] = 0;
    previousAngle[i]=INITANGLE[i];
    currentAngle[i]=INITANGLE[i];
    writeServo(PIN[i],INITANGLE[i]);
  }
  

   
}

void loop() {
  /* You must Read Gamepad to get new values and set vibration values
     ps2x.read_gamepad(small motor on/off, larger motor strenght from 0-255)
     if you don't enable the rumble, use ps2x.read_gamepad(); with no values
     You should call this at least once a second
   */  
    ps2x.read_gamepad(false, vibrate); //read controller and set large motor to spin at 'vibrate' speed
    
    if(ps2x.Button(PSB_START)){         //will be TRUE as long as button is pressed
      Serial.println("Start is being held");
      ps2x.read_gamepad(true, 200);
    }
    if(ps2x.Button(PSB_SELECT))
      Serial.println("Select is being held");      

  
    if(ps2x.Button(PSB_PAD_UP)) {      //will be TRUE as long as button is pressed
      Serial.print("Up held this hard: ");
      Serial.println(ps2x.Analog(PSAB_PAD_UP), DEC);
      L_M3->run(FORWARD);
      R_M4->run(FORWARD);
      L_Speed = ps2x.Analog(PSAB_PAD_UP);
      R_Speed = ps2x.Analog(PSAB_PAD_UP);  
    }else if(ps2x.ButtonReleased(PSB_PAD_UP))  {
      L_M3->run(RELEASE);
      R_M4->run(RELEASE);      
    }
    if(ps2x.Button(PSB_PAD_DOWN)){
      Serial.print("DOWN held this hard: ");
      Serial.println(ps2x.Analog(PSAB_PAD_DOWN), DEC);
      L_Speed = ps2x.Analog(PSAB_PAD_DOWN);
      R_Speed = ps2x.Analog(PSAB_PAD_DOWN);       
      L_M3->run(BACKWARD);
      R_M4->run(BACKWARD);
    }else if(ps2x.ButtonReleased(PSB_PAD_DOWN))  {
      L_M3->run(RELEASE);
      R_M4->run(RELEASE);      
    }
    if(ps2x.Button(PSB_R1)){
      R_Speed = 0;
    }
    if(ps2x.Button(PSB_L1)){
      L_Speed = 0;
    }
    L_M3->setSpeed(L_Speed);
    R_M4->setSpeed(R_Speed);
    
    if(ps2x.Button(PSB_PAD_LEFT)){
      L_M3->run(BACKWARD);
      R_M4->run(FORWARD);
      L_M3->setSpeed(250);
      R_M4->setSpeed(250);
    }else if(ps2x.ButtonReleased(PSB_PAD_LEFT))  {
      L_M3->run(RELEASE);
      R_M4->run(RELEASE);      
    }
    if(ps2x.Button(PSB_PAD_RIGHT)){
      Serial.println(ps2x.Analog(PSB_PAD_RIGHT));
      L_M3->run(FORWARD);
      R_M4->run(BACKWARD);
      L_M3->setSpeed(250);
      R_M4->setSpeed(250);
    }else if(ps2x.ButtonReleased(PSB_PAD_RIGHT))  {
      Serial.println("*****PSB_PAD_RIGHT***** ");
      L_M3->run(RELEASE);
      R_M4->run(RELEASE);      
    }

    
    vibrate = ps2x.Analog(PSAB_CROSS);  //this will set the large motor vibrate speed based on how hard you press the blue (X) button
    if (ps2x.NewButtonState()) {        //will be TRUE if any button changes state (on to off, or off to on)
      if(ps2x.Button(PSB_L3))
        Serial.println("L3 pressed");
      if(ps2x.Button(PSB_R3))
        Serial.println("R3 pressed");
      if(ps2x.Button(PSB_L2))
        Serial.println("L2 pressed");
      if(ps2x.Button(PSB_R2))
        Serial.println("R2 pressed");
      if(ps2x.Button(PSB_TRIANGLE))
        Serial.println("Triangle pressed");        
    }

    if(ps2x.ButtonPressed(PSB_CIRCLE)){               //will be TRUE if button was JUST pressed
      Serial.println("Circle just pressed");
      openGripper(); 
    }
    if(ps2x.NewButtonState(PSB_CROSS)) {              //will be TRUE if button was JUST pressed OR released
      Serial.println("X just changed");
      ps2x.read_gamepad(true, vibrate);   
  }
    if(ps2x.ButtonPressed(PSB_SQUARE)) {             //will be TRUE if button was JUST released
      Serial.println("Square just released");
      closeGripper() ;
    }
    if(ps2x.Button(PSB_L1) || ps2x.Button(PSB_R1)) { //print stick values if either is TRUE
      Serial.print("Stick Values:");
      Serial.print(ps2x.Analog(PSS_LY), DEC); //Left stick, Y axis. Other options: LX, RY, RX  
      Serial.print(",");
      Serial.print(ps2x.Analog(PSS_LX), DEC); 
      Serial.print(",");
      Serial.print(ps2x.Analog(PSS_RY), DEC); 
      Serial.print(",");
      Serial.println(ps2x.Analog(PSS_RX), DEC); 
      
    }     
  
  
  value[0] = ps2x.Analog(PSS_LX);
  value[1] = ps2x.Analog(PSS_RY);
  value[2] = ps2x.Analog(PSS_LY);
  value[3] = ps2x.Analog(PSS_RX);
  
   for (int i = 0; i < SERVOS; i++){
    if (value[i] > 130) {
      if (currentAngle[i] < MAX[i]) currentAngle[i]+=1;
      writeServo(PIN[i],currentAngle[i]);     
    } else if (value[i] < 120) {
      if (currentAngle[i] > MIN[i]) currentAngle[i]-=1;
      writeServo(PIN[i],currentAngle[i]);    
    }  
  }  
  
  delay(10);
}


//Grab something
void openGripper() {
  writeServo(PIN[3],MIN[3]);
  delay(300);
}

//Let go of something
void closeGripper() {
  writeServo(PIN[3],MAX[3]);
  delay(300);
}

PS2X_lib.h

Arduino
/******************************************************************
*  Super amazing PS2 controller Arduino Library v1.8
*		details and example sketch: 
*			http://www.billporter.info/?p=240
*
*    Original code by Shutter on Arduino Forums
*
*    Revamped, made into lib by and supporting continued development:
*              Bill Porter
*              www.billporter.info
*
*	 Contributers:
*		Eric Wetzel (thewetzel@gmail.com)
*		Kurt Eckhardt
*
*  Lib version history
*    0.1 made into library, added analog stick support. 
*    0.2 fixed config_gamepad miss-spelling
*        added new functions:
*          NewButtonState();
*          NewButtonState(unsigned int);
*          ButtonPressed(unsigned int);
*          ButtonReleased(unsigned int);
*        removed 'PS' from begining of ever function
*    1.0 found and fixed bug that wasn't configuring controller
*        added ability to define pins
*        added time checking to reconfigure controller if not polled enough
*        Analog sticks and pressures all through 'ps2x.Analog()' function
*        added:
*          enableRumble();
*          enablePressures();
*    1.1  
*        added some debug stuff for end user. Reports if no controller found
*        added auto-increasing sentence delay to see if it helps compatibility.
*    1.2
*        found bad math by Shutter for original clock. Was running at 50kHz, not the required 500kHz. 
*        fixed some of the debug reporting. 
*	1.3 
*	    Changed clock back to 50kHz. CuriousInventor says it's suppose to be 500kHz, but doesn't seem to work for everybody. 
*	1.4
*		Removed redundant functions.
*		Fixed mode check to include two other possible modes the controller could be in.
*       Added debug code enabled by compiler directives. See below to enable debug mode.
*		Added button definitions for shapes as well as colors.
*	1.41
*		Some simple bug fixes
*		Added Keywords.txt file
*	1.5
*		Added proper Guitar Hero compatibility
*		Fixed issue with DEBUG mode, had to send serial at once instead of in bits
*	1.6
*		Changed config_gamepad() call to include rumble and pressures options
*			This was to fix controllers that will only go into config mode once
*			Old methods should still work for backwards compatibility 
*    1.7
*		Integrated Kurt's fixes for the interrupts messing with servo signals
*		Reorganized directory so examples show up in Arduino IDE menu
*    1.8
*		Added Arduino 1.0 compatibility. 
*    1.9
*       Kurt - Added detection and recovery from dropping from analog mode, plus
*       integreated Chipkit (pic32mx...) support
*
*
*
*This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
GNU General Public License for more details.
<http://www.gnu.org/licenses/>
*  
******************************************************************/

// $$$$$$$$$$$$ DEBUG ENABLE SECTION $$$$$$$$$$$$$$$$
// to debug ps2 controller, uncomment these two lines to print out debug to uart
//#define PS2X_DEBUG
//#define PS2X_COM_DEBUG

#ifndef PS2X_lib_h
  #define PS2X_lib_h

#if ARDUINO > 22
  #include "Arduino.h"
#else
  #include "WProgram.h"
#endif

#include <math.h>
#include <stdio.h>
#include <stdint.h>
#ifdef __AVR__
  // AVR
  #include <avr/io.h>
  #define CTRL_CLK        4
  #define CTRL_BYTE_DELAY 3
#else
  // Pic32...
  #include <pins_arduino.h>
  #define CTRL_CLK        5
  #define CTRL_CLK_HIGH   5
  #define CTRL_BYTE_DELAY 4
#endif 

//These are our button constants
#define PSB_SELECT      0x0001
#define PSB_L3          0x0002
#define PSB_R3          0x0004
#define PSB_START       0x0008
#define PSB_PAD_UP      0x0010
#define PSB_PAD_RIGHT   0x0020
#define PSB_PAD_DOWN    0x0040
#define PSB_PAD_LEFT    0x0080
#define PSB_L2          0x0100
#define PSB_R2          0x0200
#define PSB_L1          0x0400
#define PSB_R1          0x0800
#define PSB_GREEN       0x1000
#define PSB_RED         0x2000
#define PSB_BLUE        0x4000
#define PSB_PINK        0x8000
#define PSB_TRIANGLE    0x1000
#define PSB_CIRCLE      0x2000
#define PSB_CROSS       0x4000
#define PSB_SQUARE      0x8000

//Guitar  button constants
#define UP_STRUM		0x0010
#define DOWN_STRUM		0x0040
#define STAR_POWER		0x0100
#define GREEN_FRET		0x0200
#define YELLOW_FRET		0x1000
#define RED_FRET		0x2000
#define BLUE_FRET		0x4000
#define ORANGE_FRET		0x8000
#define WHAMMY_BAR		8

//These are stick values
#define PSS_RX 5
#define PSS_RY 6
#define PSS_LX 7
#define PSS_LY 8

//These are analog buttons
#define PSAB_PAD_RIGHT    9
#define PSAB_PAD_UP      11
#define PSAB_PAD_DOWN    12
#define PSAB_PAD_LEFT    10
#define PSAB_L2          19
#define PSAB_R2          20
#define PSAB_L1          17
#define PSAB_R1          18
#define PSAB_GREEN       13
#define PSAB_RED         14
#define PSAB_BLUE        15
#define PSAB_PINK        16
#define PSAB_TRIANGLE    13
#define PSAB_CIRCLE      14
#define PSAB_CROSS       15
#define PSAB_SQUARE      16

#define SET(x,y) (x|=(1<<y))
#define CLR(x,y) (x&=(~(1<<y)))
#define CHK(x,y) (x & (1<<y))
#define TOG(x,y) (x^=(1<<y))

class PS2X {
  public:
    boolean Button(uint16_t);                //will be TRUE if button is being pressed
    unsigned int ButtonDataByte();
    boolean NewButtonState();
    boolean NewButtonState(unsigned int);    //will be TRUE if button was JUST pressed OR released
    boolean ButtonPressed(unsigned int);     //will be TRUE if button was JUST pressed
    boolean ButtonReleased(unsigned int);    //will be TRUE if button was JUST released
    void read_gamepad();
    boolean  read_gamepad(boolean, byte);
    byte readType();
    byte config_gamepad(uint8_t, uint8_t, uint8_t, uint8_t);
    byte config_gamepad(uint8_t, uint8_t, uint8_t, uint8_t, bool, bool);
    void enableRumble();
    bool enablePressures();
    byte Analog(byte);
    void reconfig_gamepad();

  private:
    inline void CLK_SET(void);
    inline void CLK_CLR(void);
    inline void CMD_SET(void);
    inline void CMD_CLR(void);
    inline void ATT_SET(void);
    inline void ATT_CLR(void);
    inline bool DAT_CHK(void);
    
    unsigned char _gamepad_shiftinout (char);
    unsigned char PS2data[21];
    void sendCommandString(byte*, byte);
    unsigned char i;
    unsigned int last_buttons;
    unsigned int buttons;
	
    #ifdef __AVR__
      uint8_t maskToBitNum(uint8_t);
      uint8_t _clk_mask; 
      volatile uint8_t *_clk_oreg;
      uint8_t _cmd_mask; 
      volatile uint8_t *_cmd_oreg;
      uint8_t _att_mask; 
      volatile uint8_t *_att_oreg;
      uint8_t _dat_mask; 
      volatile uint8_t *_dat_ireg;
    #else
      uint8_t maskToBitNum(uint8_t);
      uint16_t _clk_mask; 
      volatile uint32_t *_clk_lport_set;
      volatile uint32_t *_clk_lport_clr;
      uint16_t _cmd_mask; 
      volatile uint32_t *_cmd_lport_set;
      volatile uint32_t *_cmd_lport_clr;
      uint16_t _att_mask; 
      volatile uint32_t *_att_lport_set;
      volatile uint32_t *_att_lport_clr;
      uint16_t _dat_mask; 
      volatile uint32_t *_dat_lport;
    #endif
	
    unsigned long last_read;
    byte read_delay;
    byte controller_type;
    boolean en_Rumble;
    boolean en_Pressures;
};

#endif

Adafruit_MS_PWMServoDriver.h

Arduino
/*************************************************** 
  This is a library for our Adafruit 16-channel PWM & Servo driver

  Pick one up today in the adafruit shop!
  ------> http://www.adafruit.com/products/815

  These displays use I2C to communicate, 2 pins are required to  
  interface. For Arduino UNOs, thats SCL -> Analog 5, SDA -> Analog 4

  Adafruit invests time and resources providing this open source code, 
  please support Adafruit and open-source hardware by purchasing 
  products from Adafruit!

  Written by Limor Fried/Ladyada for Adafruit Industries.  
  BSD license, all text above must be included in any redistribution
 ****************************************************/

#ifndef _Adafruit_MS_PWMServoDriver_H
#define _Adafruit_MS_PWMServoDriver_H

#if ARDUINO >= 100
 #include "Arduino.h"
#else
 #include "WProgram.h"
#endif


#define PCA9685_SUBADR1 0x2
#define PCA9685_SUBADR2 0x3
#define PCA9685_SUBADR3 0x4

#define PCA9685_MODE1 0x0
#define PCA9685_PRESCALE 0xFE

#define LED0_ON_L 0x6
#define LED0_ON_H 0x7
#define LED0_OFF_L 0x8
#define LED0_OFF_H 0x9

#define ALLLED_ON_L 0xFA
#define ALLLED_ON_H 0xFB
#define ALLLED_OFF_L 0xFC
#define ALLLED_OFF_H 0xFD


class Adafruit_MS_PWMServoDriver {
 public:
  Adafruit_MS_PWMServoDriver(uint8_t addr = 0x40);
  void begin(void);
  void reset(void);
  void setPWMFreq(float freq);
  void setPWM(uint8_t num, uint16_t on, uint16_t off);

 private:
  uint8_t _i2caddr;

  uint8_t read8(uint8_t addr);
  void write8(uint8_t addr, uint8_t d);
};

#endif

Adafruit_MotorShield.h

Arduino
/******************************************************************
 This is the library for the Adafruit Motor Shield V2 for Arduino. 
 It supports DC motors & Stepper motors with microstepping as well
 as stacking-support. It is *not* compatible with the V1 library!

 It will only work with https://www.adafruit.com/products/1483
 
 Adafruit invests time and resources providing this open
 source code, please support Adafruit and open-source hardware
 by purchasing products from Adafruit!
 
 Written by Limor Fried/Ladyada for Adafruit Industries.
 BSD license, check license.txt for more information.
 All text above must be included in any redistribution.
 ******************************************************************/

#ifndef _Adafruit_MotorShield_h_
#define _Adafruit_MotorShield_h_

#include <inttypes.h>
#include <Wire.h>
#include "Adafruit_MS_PWMServoDriver.h"

//#define MOTORDEBUG

#define MICROSTEPS 16         // 8 or 16

#define MOTOR1_A 2
#define MOTOR1_B 3
#define MOTOR2_A 1
#define MOTOR2_B 4
#define MOTOR4_A 0
#define MOTOR4_B 6
#define MOTOR3_A 5
#define MOTOR3_B 7

#define FORWARD 1
#define BACKWARD 2
#define BRAKE 3
#define RELEASE 4

#define SINGLE 1
#define DOUBLE 2
#define INTERLEAVE 3
#define MICROSTEP 4

class Adafruit_MotorShield;

class Adafruit_DCMotor
{
 public:
  Adafruit_DCMotor(void);
  friend class Adafruit_MotorShield;
  void run(uint8_t);
  void setSpeed(uint8_t);
  
 private:
  uint8_t PWMpin, IN1pin, IN2pin;
  Adafruit_MotorShield *MC;
  uint8_t motornum;
};

class Adafruit_StepperMotor {
 public:
  Adafruit_StepperMotor(void);
  friend class Adafruit_MotorShield;

  void step(uint16_t steps, uint8_t dir,  uint8_t style = SINGLE);
  void setSpeed(uint16_t);
  uint8_t onestep(uint8_t dir, uint8_t style);
  void release(void);
  uint32_t usperstep;

 private:
  uint8_t PWMApin, AIN1pin, AIN2pin;
  uint8_t PWMBpin, BIN1pin, BIN2pin;
  uint16_t revsteps; // # steps per revolution
  uint8_t currentstep;
  Adafruit_MotorShield *MC;
  uint8_t steppernum;
};

class Adafruit_MotorShield
{
  public:
    Adafruit_MotorShield(uint8_t addr = 0x60);
    friend class Adafruit_DCMotor;
    void begin(uint16_t freq = 1600);

    void setPWM(uint8_t pin, uint16_t val);
    void setPin(uint8_t pin, boolean val);
    Adafruit_DCMotor *getMotor(uint8_t n);
    Adafruit_StepperMotor *getStepper(uint16_t steps, uint8_t n);
 private:
    uint8_t _addr;
    uint16_t _freq;
    Adafruit_DCMotor dcmotors[4];
    Adafruit_StepperMotor steppers[2];
    Adafruit_MS_PWMServoDriver _pwm;
};

#endif

Motor_Shield.zip

Arduino
No preview (download only).

Credits

James Martel

James Martel

48 projects • 62 followers
Self taught Robotics platform developer with electronics background

Comments