古人智慧

Just Do it!
上士聞道,勤而行之;中士聞道,若存若亡;下士聞道,大笑之。不笑,不足以爲道。
~ 道德經 41

「實現夢想不是追逐成功,而是在於賦予生命意義,人生中的每個決定與聲音都有其重要含義。」"The key to realizing a dream is to focus not on success but on significance — and then even the small steps and little victories along your path will take on greater meaning."
電視名人-歐普拉·溫芙蕾(OPRAH WINFREY)

搜尋此網誌

Translation

2018年4月29日 星期日

[Robot] 全3D打印 履帶機器人DIY

坦克車履帶傳動系統是個很棒的設計,可以在複雜與惡劣的地形上快速行進,用在robot上應該是適用的。
最近在Thingiverse看到一個神人作品SMARS作品是可以全3D打印的履帶與機身, 而且使用的小型馬達N20剛好手上有,真是太棒了,可以解解這種傳動系統的渴。。。

作品背景說明

要啟動一個項目,電控板是核心,有幾點必須考慮:
1.PCB尺寸
2.有多少GPIO可以控制外接模塊或馬達
3.operation電壓
再來就是周邊模塊的選擇,例如直流DC馬達要搭配馬達驅動板。
遙控器是相當麻煩的部分,我是選擇用jjRobots公司搭配OSC協議透過Wifi UDP傳送,OSC主要訴求是即時傳送與接收,這對遙控車是非常必要的選擇。
之前做4足Spider用HTML來控制,就非常不順暢卡卡的,甚至會突然HTML package會漏掉。
最後,電源系統設計,從電池電壓、尺寸與重量,DC-DC降壓板的電流輸出,這些都足以讓項目卡關,難以持續。
從上述的分析,很容易瞭解這次為何選擇TinyPlan。這片TinyPlan是以ESP8266為核心,並搭載兩顆2.4v 750F電容式快充鋰電池,串聯起來可以提供4.8v,1C放電。並提供8個GPIO,4根pin接馬達驅動板,2根接UltraSonic sensor綽綽有餘,是個非常好的選擇。

作品展示

零件表與設備工具

BOM list:

設備:

3D 打印機
3D 結構

設計階段

3D 結構列印與組裝


《用2mm鑽頭通一下比較好安裝》

《TinyPlan+L9113S》

Arduino軟件設計

參考jjRobots的OSC來開發(https://github.com/jjrobots/B-ROBOT_EVO2/tree/master/Arduino)
主程式如下:
/*
   RegisHsu 2018-04-28
   TinyPlan ESP8266 module + L9110S + UltraSound
   Controller jjrobots - www.jjrobots.com

   v01:
      initial version
   v02:
      add UltraDonic sensor
*/

#include <ESP8266WiFi.h>
#include "RHROBOTS_OSC.h"
#include "RHROBOTS_BROBOT.h"

#define BAUDRATE 250000

// TinyPlan Port define
#define PIN_D1 14
#define PIN_D2 12
#define PIN_D3 13
#define PIN_D4 15
#define PIN_D5 16
#define PIN_D6 5
#define PIN_D7 4
#define PIN_D8 2

//N20 Motor pin define
#define MOTOR_M1_S1 PIN_D1
#define MOTOR_M1_S2 PIN_D2
#define MOTOR_M2_S1 PIN_D5
#define MOTOR_M2_S2 PIN_D6

//Ultrasonic sensor pin define
#define ULTRA_TRIG PIN_D3
#define ULTRA_ECHO PIN_D7

// NORMAL MODE PARAMETERS (MAXIMUN SETTINGS)
#define MAX_THROTTLE 2400
#define MAX_STEERING 2400
#define MAX_CONTROL_OUTPUT 1024

uint8_t loop_counter;       // To generate a medium loop 40Hz
uint8_t slow_loop_counter;  // slow loop 2Hz
uint8_t sendBattery_counter; // To send battery status

long timer_old;
long timer_value;
int debug_counter;
float debugVariable;
float dt;

int16_t motor1;
int16_t motor2;

bool newControlParameters = false;
bool modifing_control_parameters = false;

uint8_t mode;  // mode = 0 Normal mode, mode = 1 Pro mode (More agressive)

float throttle;
float steering;
float max_throttle = MAX_THROTTLE;
float max_steering = MAX_STEERING;
float control_output;

// Ultrasonic
volatile long duration;
volatile int distance;
volatile int echo_interr_flag, echo_obstacle;
volatile long t_echo_s, t_echo_e;
long t_auto_last, t_auto_curr;
int echo_trig_sw;

void echo_interr(void)
{
  echo_interr_flag = 1 - echo_interr_flag;
  if (echo_interr_flag)
    t_echo_s = micros();
  else
  {
    t_echo_e = micros();
    duration = t_echo_e - t_echo_s;
    distance = duration * 0.034 / 2;
    if (distance < 12) //12cm
      echo_obstacle = 1;
    else
      echo_obstacle = 0;
  }
}

void echo_trigger(void)
{
  echo_trig_sw = 1;
  // Clears the trigPin
  digitalWrite(ULTRA_TRIG, LOW);
  delayMicroseconds(2);

  // Sets the trigPin on HIGH state for 10 micro seconds
  digitalWrite(ULTRA_TRIG, HIGH);
  delayMicroseconds(10);
  digitalWrite(ULTRA_TRIG, LOW);
  echo_interr_flag = 0;
  echo_obstacle = 0;
}

void auto_pilot(void)
{
  t_auto_curr = millis();
  if ((t_auto_curr - t_auto_last) > 80)
  {
    t_auto_last = t_auto_curr;
    //Serial.println("Trig");
    echo_trigger();
  }

  if (echo_obstacle)
  {
    echo_obstacle = 0;
    //Serial.println("obstacle");
    //stop
    setMotorSpeedM1(0);
    setMotorSpeedM2(0);
    delay(800);
    //back
    setMotorSpeedM1(-motor1);
    setMotorSpeedM2(-motor2);
    delay(600);
    //turn left
    setMotorSpeedM1(motor1);
    setMotorSpeedM2(-motor2);
    delay(600);
    //stop
    setMotorSpeedM1(0);
    setMotorSpeedM2(0);
    delay(500);
  }
  setMotorSpeedM1(motor1);
  setMotorSpeedM2(motor2);
}

// Set speed of Stepper Motor1
// tspeed could be positive or negative (reverse)
void setMotorSpeedM1(int16_t tspeed)
{
  if (tspeed >= 0)
  {
    analogWrite(MOTOR_M1_S1, 0);
    analogWrite(MOTOR_M1_S2, tspeed);
  }
  else
  {
    analogWrite(MOTOR_M1_S1, -tspeed);
    analogWrite(MOTOR_M1_S2, 0);
  }
}

// Set speed of Stepper Motor2
// tspeed could be positive or negative (reverse)
void setMotorSpeedM2(int16_t tspeed)
{
  if (tspeed >= 0)
  {
    analogWrite(MOTOR_M2_S1, 0);
    analogWrite(MOTOR_M2_S2, tspeed);
  }
  else
  {
    analogWrite(MOTOR_M2_S1, -tspeed);
    analogWrite(MOTOR_M2_S2, 0);
  }
}

void setup() {
  // put your setup code here, to run once:
  // init motors
  pinMode(MOTOR_M1_S1, OUTPUT);
  pinMode(MOTOR_M1_S2, OUTPUT);
  pinMode(MOTOR_M2_S1, OUTPUT);
  pinMode(MOTOR_M2_S2, OUTPUT);

  //init Ultrasonic sensor
  echo_interr_flag = 0;
  t_auto_last = 0;
  echo_obstacle = 0;
  pinMode(ULTRA_TRIG, OUTPUT); // Sets the trigPin as an Output
  pinMode(ULTRA_ECHO, INPUT_PULLUP); // Sets the echoPin as an Input
  attachInterrupt(digitalPinToInterrupt(ULTRA_ECHO), echo_interr, CHANGE);
  Serial.begin(BAUDRATE); // Serial output to console
  //Regis
  OSC.UDP_Init();

  Serial.println("BROBOT by JJROBOTS v2.2");

  // STEPPER MOTORS INITIALIZATION
  Serial.println("DC motors initialization...");
  // pre-action
  echo_trigger();
  // Little motor vibration to indicate that robot is ready
  setMotorSpeedM1(0);
  setMotorSpeedM2(0);
  for (uint8_t k = 0; k < 3; k++)
  {
    setMotorSpeedM1(1000);
    setMotorSpeedM2(1000);
    //BROBOT.moveServo1(SERVO_AUX_NEUTRO + 5);
    delay(100);
    setMotorSpeedM1(-1000);
    setMotorSpeedM2(-1000);
    //BROBOT.moveServo1(SERVO_AUX_NEUTRO - 5);
    delay(100);
  }
  setMotorSpeedM1(0);
  setMotorSpeedM2(0);

  for (int i = 0; i < 3; i++)
  {
    // pre-action
    echo_trigger();
    delay(200);
  }
  // OSC initialization
  OSC.fadder1 = 0.5;
  OSC.fadder2 = 0.5;

  Serial.println("Let's start...");
  mode = 0;
}

void loop() {

  //Regis
  OSC.MsgRead();  // Read UDP OSC messages
  if (OSC.toggle1 == 1)
  {
    motor1 = -780;
    motor2 = -780;
    auto_pilot();
  }

  if (OSC.newMessage)
  {
    OSC.newMessage = 0;
    //Regis
    if (OSC.page == 1) // Get commands from user (PAGE1 are user commands: throttle, steering...)
    {
      //OSC.newMessage = 0;
      throttle = (OSC.fadder1 - 0.5) * max_throttle;
      // We add some exponential on steering to smooth the center band
      steering = OSC.fadder2 - 0.5;
      if (steering > 0)
        steering = (steering * steering + 0.5 * steering) * max_steering;
      else
        steering = (-steering * steering + 0.5 * steering) * max_steering;

      motor1 = throttle - steering;
      motor2 = throttle + steering;
      motor1 = constrain(motor1, -MAX_CONTROL_OUTPUT, MAX_CONTROL_OUTPUT);
      motor2 = constrain(motor2, -MAX_CONTROL_OUTPUT, MAX_CONTROL_OUTPUT);
      setMotorSpeedM1(motor1);
      setMotorSpeedM2(motor2);
    }
  } // End new OSC message
}

測試


《使用jjRobots的遙控App》

《加上UltraSonic sensor》

沒有留言:

張貼留言