引言
想做一个自动驾驶的demo,用于算法的验证和展示。目前完成了车辆平台的搭建和电机控制,后续会陆续更新其他部分:路径规划、激光slam建图与定位,语义地图的构建,控制算法等等。
硬件平台:
计算平台
- Jetson TX2
- arduino-uno
车载平台
- RC-car
传感器
- velodyne-16
- Razor-9dof-imu
整个基本框架是Jetson TX2做上层感知,定位,路径规划的处理,arduino负责底层的电机控制。目标总体框架如下所示:
arduino电机控制
电机控制代码如下所示:
#include <Servo.h>
#include <ros.h>
#include <geometry_msgs/Twist.h>
class Car {
public:
void initControler();
void armControler();
void writeToControler(int, int);
float limitMotor(int);
float limitServo(int);
private:
const int MOTOR_PIN = 10;
const int SERVO_PIN = 9;
const int MOTOR_MAX = 2000;
const int MOTOR_MIN = 1600;
const int MOTOR_STOP = 1300;
const int STEER_MIN = 1100;
const int STEER_MAX = 1900;
const int STEER_CENTER = 1500;
const int noAction = 0;
Servo motor;
Servo steering;
};
Car car;
int motor_speed;
int steer;
volatile unsigned long dt;
volatile unsigned long t0;
ros::NodeHandle nh;
geometry_msgs::Twist vel_angular_back;
void controlCallback(const geometry_msgs::Twist& ecu) {
car.writeToControler(ecu.linear.x, ecu.angular.z);
vel_angular_back.linear.x = ecu.linear.x;
vel_angular_back.angular.z = ecu.angular.z;
}
ros::Publisher ecu_back("ecu_back", &vel_angular_back);
ros::Subscriber<geometry_msgs::Twist> sub_control("control", controlCallback);
/**
* ARDUINO INITIALIZATION
*/
void setup() {
car.initControler();
car.armControler();
t0 = millis();
nh.getHardware()->setBaud(57600);
nh.initNode();
nh.advertise(ecu_back);
nh.subscribe(sub_control);
}
/**
* ARDUINO MAIN lOOP
*/
void loop() {
dt = millis() - t0;
ecu_back.publish(&vel_angular_back);
if (dt > 50) {
t0 = millis();
// to do
}
nh.spinOnce();
}
/**
* CAR CLASS IMPLEMENTATION
*/
void Car::initControler() {
motor.attach(MOTOR_PIN);
steering.attach(SERVO_PIN);
}
void Car::armControler() {
motor.writeMicroseconds(1500);
steering.writeMicroseconds(STEER_CENTER);
delay(3000);
}
float Car::limitMotor(int x) {
if (x == noAction) {
return MOTOR_STOP;
}
if (x > MOTOR_MAX) {
x = MOTOR_MAX;
} else if (x < MOTOR_MIN) {
x = MOTOR_MIN;
}
return x;
}
float Car::limitServo(int x) {
if (x == noAction) {
return STEER_CENTER;
}
if (x > STEER_MAX) {
x = STEER_MAX;
} else if (x < STEER_MIN) {
x = STEER_MIN;
}
return x;
}
void Car::writeToControler(int motor_speed, int steer) {
int motorCMD, servoCMD;
motorCMD = car.limitMotor(motor_speed);
servoCMD = car.limitServo(steer);
//motorCMD = motor_speed;
//servoCMD = steer;
motor.writeMicroseconds(motorCMD);
steering.writeMicroseconds(servoCMD);
}
为了完成arduino电机控制与TX2的通讯,需要在TX2上面搭建一些环境:
安装arduino
sudo apt-get install arduino
安装rosserial-arduino
用途:用于arduino的ROS通讯桥接
二进制方式安装在ROS工作站(推荐)
sudo apt-get install ros-indigo-rosserial-arduino
sudo apt-get install ros-indigo-rosserial
rospack profile
源码方式安装在ROS工作站
cd <ws>/src
git clone https://github.com/ros-drivers/rosserial.git
cd <ws>
catkin_make
安装ros_lib到Arduino IDE开发环境
上面的安装会得到ros_lib,它需要复制到Arduino的开发环境,以启用Arduino与ROS通讯。
linux系统下,生成ros_lib到Linux下的Arduino库目录sketchbook/libraries(一般在用户的home目录下)
cd <sketchbook>/libraries
rm -rf ros_lib #如之前有,可以先删除
rosrun rosserial_arduino make_libraries.py .
然后,可以打开arduino IDE,找到file-examples-ros_lib是否存在,如果这一不没安装好的话,会找不到ros.h的头文件
运行ROS-arduino
写好arduino的代码之后,就可以试着运行看看
运行roscore
roscore
新终端运行,/dev/ttyUSB0为Arduino设备,设备可能是/dev/ttyUSB0,也可能是/dev/ttyACM0,需要自己确认
rosrun rosserial_python serial_node.py /dev/ttyUSB0
或
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
然后就可以在ROS中发布转向速度的话题消息,arduino节点接收消息后,完成电机控制。