前言
Jetson为ubantu操作系统,Arduino拥有一套烧录系统,只要在任意操作系统中编译完成,然后烧录进Arduino便可执行命令。本文重点是帮助初学者找齐完成整套流程的各类原件,然后可以按照本文进行操作复刻。
Jetson需要做好的准备
- 烧 录 操 作 系 统
- 在 Jetson 上 安 装 VNCviewer 此时有两种方法可以连接电脑和Jetson,
A . 用路由器连接两者,这种情况Jetson的IP非常好找,使用 IPscanner可以很快找到,并且jetson可以上网(推荐)
B . 用网线连接两者,这种情况Jetson默认是动态IP,使用IPscanner也要找好久(一般是好几个小时),所以建议锁定IP,操作如下(不推荐,但有时外出操作只能这样):
a.首先找到 Edit Connections选项 - b.进入网线连接的那个选项,按下图配置
进入控制台输入
ifconfig
得到下面的结果
然后电脑端便可以使用固定的IP进行有线连接了
3.安装各种软件
例如spyder,arduino IDE等
代码讲解
本次实验的目的是控制一个打在深度学习平台的小车,所以小车的控制功能必不可少,这类简单的功能完全可以通过Arduino来实现,代码如下。
#include <string.h>
#include <SparkFun_TB6612.h>
#include <Wire.h>
#include <Servo.h>
//引入必备的库函数
int car_control[3]={
10,10,90};
//初始化小车的动力参数,分别是左后轮速度,右后轮速度,转弯角度,速度的变化区间为[-255,255],速度的变化区间为[45,135]
Servo myservo;
//servo类用于控制舵机
#define SERVOMIN 150
#define SERVOMAX 600
#define AIN1 2
#define BIN1 7
#define AIN2 4
#define BIN2 8
#define PWMA 5
#define PWMB 6
#define STBY 9
const int offsetA = 1;
const int offsetB = -1;
Motor motor1 = Motor(AIN1, AIN2, PWMA, offsetA, STBY);
Motor motor2 = Motor(BIN1, BIN2, PWMB, offsetB, STBY);
//定义小车马达参数,到此为止调用motor就可直接控制小车马达
//***car_control函数为Arduino接收指令的函数原型,核心是利用Serial.readString()读取发送来的字符串,如果本次接收的字符串str与上一次接受的指令pre_str不同,则按照字符串的内容调节小车参数,字符串需要包含两个后轮速度和转弯角度,分别用空格隔开例如 "100 100 135",但是函数有重大技术问题,因为Serial.readString()刷新速度太慢,导致小车控制有延迟,并且通信轨道中并不只有我发出的信号,还有一些杂乱的字符串,导致发出信号的头部受到污染,car_control[0]的第一位经常会变成字符格式,导致函数失效,并且极其容易报错****//
char pre_str_char=' ';
char str_char=' ';
char str_char_read=' ';
void Car_control(int* car_control)
{
pre_str=str;
char str_char[12];
char *p;
str=Serial.readString();
if (pre_str!=str ) {
int i=0;
strcpy(str_char,str.c_str());
p=strtok(str_char," ");
car_control[0]=atoi(p);
for(i=0;i<2;++i)
{
i++;
p=strtok(NULL," ");
car_control[i]=atoi(p);
}
str=pre_str;
}
}
//****此程序为修改后的控制函数,大体思想是利用Serial.available()检测是否有字符串正在传输,Serial.read()按字符读取输入来的字符串并压入定义好的字符串数组内,从而重构原信号,并且为了避免发出的数据受到污染,所以定义了部头,发送的信号格式如下 "ss100 100 50e"以s开头,几个s都可以,为了鲁棒性和速度兼顾,本程序使用了两个ss,如果第一个s受到污染,依然可以用第二个s进行判断,并且收到e后会重置函数,,继续等待下一个s而不是继续读取。***//
void Car_control_re(int* car_control)
{
char str_char_store[30];
//读取字符后存入str_char_store,方便一会使用字符串处理函数
char *p;
//临时变量
int able=0;
//able为1可以读取,able为0禁止读取
int i=0;
//写入位数变量
if (Serial.available() && Serial.read()=='s'){
//首先判断是否有内容要读取,并且判断是不是s,如果不是s就会被舍弃并进入下一次读取
able=1;
//如果读取到s成功进入循环,那么设置写入判断为1
delay(2);
while(Serial.available()){
str_char_read=Serial.read();
//读取下一位
if (str_char_read=='s') { delay(1);str_char_read=Serial.read();delay(1); }
//这里会吸收所有多余的s
else if (str_char_read=='e' ) {str_char_store[i]='\0';i=0; able=0;}
//如果不是s检查是否是e,防止误读取,检测到e就关闭写入通道
if (able==1 && i<30 ){str_char_store[i]=str_char_read; i++; }
//如果是s后的正常数字,那么写入str_char_store
delay(2);
}
p=strtok(str_char_store," ");
//p用于分割正常数字和空格
car_control[0]=atoi(p);
//将读取到的数字字符串转为实际的数字,写入car_control用于改变小车速度
for(i=1;i<=2;++i)
{
p=strtok(NULL," ");
car_control[i]=atoi(p);
}
}
}
void setup(){
Serial.begin(9600);
//开始监听9600波段
myservo.attach(10);
//舵机控制初始化
}
void loop(){
Car_control_re( car_control);
//读取输入
if (car_control[2]>135){car_control[2]=90;}
else if (car_control[2]<45){car_control[2]=90;}
//如果舵机参数超出可运动的范围就会损害舵机,所以做一个判断,如果输入有误在这里进行调整
motor1.drive(car_control[0],1);
motor2.drive(car_control[1],1);
myservo.write(car_control[2]);
//执行指令
}
上面是控制小车运动的底层程序,下面是jetson与arduino通信的程序
# -*- coding: utf-8 -*-
"""
Created on Mon Apr 20 10:34:33 2020
整个程序没有循环,但是pynput会自动进行循环,每一次按键都会新开一条线程运行 on_press 方法
所以如何防止不同线程同时刻与Arduino才是关键,首先
1.如果速度超过最大速度,并且持续加速,本条指令失效
2.在真正加速之前已经把能加到的最高速度记录下来,防止加速过程中积压过多加速指令等待发送
3.如果积压的指令超过了0.5秒,则删除新发送的指令
4.当前指令的预期结束时间记录下来,发送给其他正在等待的进程,然后按照时间顺序依次更新完成时间,每次增加0.15秒,如果进程指令发现当前时间小于其他进程完成的时间,那么就休眠直到轮到此进程执行命令,如果其他进程早已完成指令,那么本条指令立即发送
@author: 86198
"""
import serial
import sys
from pynput import keyboard
from pynput.keyboard import Key, Listener
import time
def connect():
port="/dev/ttyACM0"
rates=9600
ser=serial.Serial(port,rates)
# ser.flushOutput()
turn = 90
speed=0
t=0.15
timer_write=time.time()
return timer_write,speed,turn,ser,t
timer_write,speed,turn,ser,t=connect()
def on_press(key):
global timer_write
global speed
global turn
global t
# ser.flushInput()
# print(dir(key))
if (len(format(key))==3) :
if (speed==250 and (format(key)[1] == "w")):
return
if (speed==-250 and (format(key)[1] == "s")):
return
if (turn==45 and (format(key)[1] == "a")):
return
if (turn==135 and (format(key)[1] == "d")):
return
time_diff=timer_write-time.time()
timer_write=time.time()+t
if time_diff > 0.5:
return
print('-------------start----------------------')
if ((format(key)[1] == "w") ):
''' '''
if speed<0:
speed=0
elif speed<250:
speed+=50
turn=90
print('w pressed')
elif ((format(key)[1] == "s") ):
''' '''
if speed>0:
speed=0
elif speed>-250:
speed-=50
turn=90
print('s pressed')
elif ((format(key)[1] == "a") ):
''' '''
turn=45
print('a pressed')
elif ((format(key)[1] == "d") ):
''' '''
turn=135
print('d pressed')
elif ((format(key)[1] == "q") ):
turn=90
speed=0
print('stopped')
ser.flushOutput()
msg="ss"+str(speed)+" "+str(speed)+" "+str(turn)+"e"
ser.write(bytes(msg,encoding='utf8') )
ser.close()
sys.exit(1)
if time_diff>0 :
timer_write+=time_diff
print("waiting")
time.sleep(time_diff)
ser.flushOutput()
msg="ss"+str(speed)+" "+str(speed)+" "+str(turn)+"e"
# print(msg)
ser.write(bytes(msg,encoding='utf8') )
print(speed)
print('-------------close----------------------')
#while True:
with keyboard.Listener(on_press = on_press) as listener:
listener.join()
以上就是全部内容了,有问题可以留言,都会回复的。