2020年に製作したDonkey Car スマートカー について記事にしました。
Donkey CarはRaspberry Pi のカメラからコースをディープラーニングさせ自動走行を行います。(動画は白線上を自動走行)
動画
■Raspberry Pi3 B+ (技適製品)
電源供給:モバイル電池
■Arduino Nano
■カメラモジュール
■PCA9685 PWM Servo ドライバ
■ギアモータ
■モータードライバDRV8833
■HC-SR04超音波センサー
回路図
SSH接続
①Secure Shell(通常使用)
chrome ウェブストア
②TeraTerm(他SSH接続)
パスフレーズ:raspberry
Joystick接続
●USBドングルをRaspberry Pi
USBに差込
●D ⇔ X (X側にする)
操作
エラーが発生した場合
ポート【】または【22】する
パスワード:raspberry
cd ~/mycar
rm data.zip(過去のdata.zip削除)
ls -l
cd ~/mycar/data
rm -r tub......(過去の学習データ削除)
ls -l
学習走行(自動保存)→JoystickでCar操作
cd ~/mycar
python manage.py drive --js
[Ctrl]+[C]学習終了
保存データ確認
cd ~/mycar/data
ls -l
圧縮
cd ~/mycar
zip -r data.zip data/(~/mycar/data/ 以下フォルダ全圧縮)
ls -l
データの転送
cd ~/mycar/
get data.zip
『パソコンにdata.zipを任意ファイルに転送』
Google Colaboratory学習
【Colaboratory(DonkeyCar 3.1.5, TenforFlow 1.13.1対応版】クリック
学習済みデータをDonwload
『ダウンロードフォルダに[mypilot.h5]をダウンロード』
自動走行
cd ~/mycar/models
put mypilot.h5
ls -l
『ダウンロードフォルダのmypilot.h5をDonkey Carに転送』
DonkeyCarを動かす
cd ~/mycar
python manage.py drive --model ./models/mypilot.h5
プログラム(Arduino Nano)
int L_trig = 2;
int L_echo = 4;
int R_trig = 7;
int R_echo = 8;
/* PIN settings */
#define M1_IN1 6
#define M1_IN2 9
#define M2_IN1 10
#define M2_IN2 11
#define CH1_PWM 3
#define CH2_PWM 5
#define sw 12
/* PWM settings */
/* CH1 is forward-backward PWM channel.
* CH2 is left-right PWM channel.
*/
#define CH1_PWM_N 1520
#define CH1_PWM_RANGE 400
#define CH2_PWM_N 1520
#define CH2_PWM_RANGE 400
int ch1_val = CH1_PWM_N;
int ch2_val = CH2_PWM_N;
float ch1_norm_val = 0;
float ch2_norm_val = 0;
float ZERO_THRESHOULD = 0.03;
float mapfloat(long x, long in_min, long in_max, long out_min, long out_max){
return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
}
/* Check if num is under threshold */
bool checkZero(float num){
if(num == 0.0){
return true;
}else if(num > 0.0){
if(num < ZERO_THRESHOULD){
return true;
}else{
return false;
}
}else{
if(num > -ZERO_THRESHOULD){
return true;
}else{
return false;
}
}
}
/*Control motors*/
void runMotors(float in_ch1, float in_ch2){
if(!checkZero(in_ch1) || !checkZero(in_ch2)){
if (in_ch1 > 0 && checkZero(in_ch2)) {
analogWrite(M1_IN1, LOW);
analogWrite(M2_IN1, LOW);
int velocity = in_ch1*255;
if(velocity > 255){
velocity = 255;
}
//Serial.print(velocity);
analogWrite(M1_IN2, velocity);
analogWrite(M2_IN2, velocity*0.8);
//Serial.println(":-----Forward-----");
}
else if (in_ch1 < 0 && checkZero(in_ch2)) {
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN2, LOW);
int velocity = in_ch1*(-255);
if(velocity > 255){
velocity = 255;
}
//Serial.print(velocity);
analogWrite(M1_IN1, velocity);
analogWrite(M2_IN1, velocity);
//Serial.println(":-----Back-----");
}
if (in_ch2 > 0 && checkZero(in_ch1)) {
analogWrite(M1_IN1, LOW);
analogWrite(M2_IN2, LOW);
int velocity = in_ch2*255;
if(velocity > 255){
velocity = 255;
}
//Serial.print(velocity);
analogWrite(M1_IN2, velocity);
analogWrite(M2_IN1, velocity);
// Serial.println(":-----Left turn-----");
}
else if (in_ch2 < 0 && checkZero(in_ch1)) {
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN1, LOW);
int velocity = in_ch2*(-255);
if(velocity > 255){
velocity = 255;
}
//Serial.print(velocity);
analogWrite(M1_IN1, velocity);
analogWrite(M2_IN2, velocity);
//Serial.println(":-----Right turn-----");
}
if (in_ch1 > 0 && !checkZero(in_ch2)) {
analogWrite(M1_IN1, LOW);
analogWrite(M2_IN1, LOW);
int velocity = in_ch1*255;
int velocity_z = in_ch2*255;
int right_velocity = velocity - velocity_z;
int left_velocity = velocity + velocity_z;
if(right_velocity > 255){
right_velocity = 255;
}else if(right_velocity < 0){
right_velocity = 0;
}
if(left_velocity > 255){
left_velocity = 255;
}else if(left_velocity < 0){
left_velocity = 0;
}
analogWrite(M1_IN2, left_velocity);
analogWrite(M2_IN2, right_velocity);
}
else if (in_ch1 < 0 && !checkZero(in_ch2)) {
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN2, LOW);
int velocity = in_ch1*(-255);
int velocity_z = in_ch2*255;
int right_velocity = velocity + velocity_z;
int left_velocity = velocity - velocity_z;
if(right_velocity > 255){
right_velocity = 255;
}else if(right_velocity < 0){
right_velocity = 0;
}
if(left_velocity > 255){
left_velocity = 255;
}else if(left_velocity < 0){
left_velocity = 0;
}
analogWrite(M1_IN1, left_velocity);
analogWrite(M2_IN1, right_velocity);
}
}
else {
analogWrite(M1_IN1, LOW);
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN1, LOW);
analogWrite(M2_IN2, LOW);
}
if(checkZero(in_ch1) && checkZero(in_ch2)){
analogWrite(M1_IN1, LOW);
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN1, LOW);
analogWrite(M2_IN2, LOW);
}
}
/*Normalize PWM input between -1.0 and 1.0*/
float normPWM(float in_val, float in_c, float in_range){
if(in_val > in_c+in_range){
return 1.0;
}else if(in_val < in_c-in_range){
return -1.0;
}
return mapfloat(in_val, in_c-in_range, in_c+in_range, -1.0, 1.0);
}
void SR04_senser(){
int status ;
status = digitalRead(sw) ;
if(status == HIGH){
digitalWrite(L_trig,LOW);
delayMicroseconds(1);
digitalWrite(L_trig,HIGH);
delayMicroseconds(11);
digitalWrite(L_trig,LOW);
int L_t = pulseIn(L_echo,HIGH);
int L_dist = L_t*0.017;
//Serial.print("L ");
//Serial.println(L_dist);
digitalWrite(R_trig,LOW);
delayMicroseconds(1);
digitalWrite(R_trig,HIGH);
delayMicroseconds(11);
digitalWrite(R_trig,LOW);
int R_t = pulseIn(R_echo,HIGH);
int R_dist = R_t*0.017;
//Serial.print("R ");
//Serial.println(R_dist);
if(L_dist < 15){
analogWrite(M1_IN1, 150); //back
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN1, 150);
analogWrite(M2_IN2, LOW);
delay(500);
analogWrite(M1_IN1, 150); //right
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN1, LOW);
analogWrite(M2_IN2, 150);
delay(500);
}
if(R_dist < 15){
analogWrite(M1_IN1, 150); //back
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN1, 150);
analogWrite(M2_IN2, LOW);
delay(500);
analogWrite(M1_IN1, LOW); //left
analogWrite(M1_IN2, 150);
analogWrite(M2_IN1, 150);
analogWrite(M2_IN2, LOW);
delay(500);
}
}
}
void setup()
{
pinMode(M1_IN1, OUTPUT);
pinMode(M1_IN2, OUTPUT);
pinMode(M2_IN1, OUTPUT);
pinMode(M2_IN2, OUTPUT);
pinMode(CH1_PWM, INPUT);
pinMode(CH2_PWM, INPUT);
pinMode(L_trig,OUTPUT);
pinMode(L_echo,INPUT);
pinMode(R_trig,OUTPUT);
pinMode(R_echo,INPUT);
pinMode(sw,INPUT) ;
analogWrite(M1_IN1, LOW);
analogWrite(M1_IN2, LOW);
analogWrite(M2_IN1, LOW);
analogWrite(M2_IN2, LOW);
Serial.begin(9600);
//Serial.println("Start!!!");
}
void loop()
{
SR04_senser();
ch1_val = pulseIn(CH1_PWM, HIGH);
ch2_val = pulseIn(CH2_PWM, HIGH);
ch1_norm_val = normPWM((float)ch1_val, CH1_PWM_N, CH1_PWM_RANGE);
ch2_norm_val = normPWM((float)ch2_val, CH2_PWM_N, CH2_PWM_RANGE);
//Serial.print(ch1_val);
//Serial.print(":");
//Serial.print(ch1_norm_val,4);
//Serial.print(" ");
//Serial.print(ch2_val);
//Serial.print(":");
//Serial.println(ch2_norm_val,4);
runMotors(ch1_norm_val, ch2_norm_val);
}
0 件のコメント:
コメントを投稿