控制原理
1.按下键盘时,teleop_twist_keyboard Package发布名为 /cmd_vel 的Topic
2.创建一个Package,创建 base_controller 节点订阅这个话题,接收速度数据,在转换成与底盘通信的格式,然后写入串口
3.当小车底盘接收到串口发来的速度后,就控制电机运转,从而实现键盘控制小车的移动
测试:
1、打开键盘
# rosrun teleop_twist_keyboard teleop_twist_keyboard.py
2、运行功能包
#rosrun base_controller base_controller
ps: 查看Twist发布的cmd_vel话题
# rostopic list
# rostopic echo /cmd_vel
必须保证USB转串口线连接在树莓派ttyUSB1上
ls -l /dev |grep ttyUSB #查看USB口
3、在teleop_twist_keyboard上按键进行控制
teleop_twist_keyboard有两种控制方式:1.普通模式 2.全向模式
本项目采用四全向轮故使用模式2(大写锁定可启动)。
步骤:
0、准备工作:
cd ~/catkin_ws/src
git clone https://github.com/Forrest-Z/teleop_twist_keyboard.git
git clone https://github.com/Forrest-Z/serial.git
1、创建创建一个Package #一定要到catkin_ws/src 文件夹下进行创建!
# catkin_create_pkg base_controller std_msgs rospy roscpp
创建时需要添加依赖,ROS会自动在package.xml 文件里添加这些依赖。
2、写一个小Node(cpp)
在base_controller/src 目录下创建base_controller.cpp
# roscd base_controller
# touch base_controller.cpp
# gedit base_controller.cpp
代码:
/****************************************************
ROS Robot control base on serial
Making sure ttyUSB1 !!!
function :
1.transmit control conmmand to control robot moving
2.Subscribe /cmd_vel(keyboard transmit)
Twist msgs
serial commend:
14 Byte:[linear_speed_X 4 Byte][linear_speed_Y 4 Byte][angular_speed_Z 4 4Byte][end "\r\n" 2 Byte]
****************************************************/
#include "ros/ros.h"
#include <geometry_msgs/Twist.h>
#include <string>
#include <iostream>
#include <cstdio>
#include <unistd.h>
#include <math.h>
#include "serial/serial.h"
using std::string;
using std::exception;
using std::cout;
using std::cerr;
using std::endl;
using std::vector;
float linear_temp_x=0,linear_temp_y=0,angular_temp_z=0;
unsigned char data_terminal0=0x0d; // "/r"
unsigned char data_terminal1=0x0a; // "/n"
unsigned char speed_data[14]={0} ; //serial data
union floatData
{
float d;
unsigned char data[4];
}linear_speed_x,linear_speed_y,angular_speed_z;
void callback(const geometry_msgs::Twist & cmd_input) //Subscribe Twist
{
string port("/dev/ttyUSB0");
unsigned long baud = 115200;
serial::Serial my_serial(port, baud, serial::Timeout::simpleTimeout(1000));
linear_temp_x = cmd_input.linear.x;
linear_temp_y = cmd_input.linear.y;
angular_temp_z = cmd_input.angular.z;
linear_speed_x.d = linear_temp_x ;
linear_speed_y.d = linear_temp_y ;
angular_speed_z.d= angular_temp_z;
for(int i=0;i<4;i++)
{
speed_data[i] = linear_speed_x.data[i] ;
speed_data[i+4] = linear_speed_y.data[i] ;
speed_data[i+8] = angular_speed_z.data[i];
}
speed_data[12]=data_terminal0;
speed_data[13]=data_terminal1;
//write to serial
my_serial.write(speed_data,14);
}
int main(int argc, char **argv)
{
string port("/dev/ttyUSB0");
unsigned long baud = 115200;
serial::Serial my_serial(port,baud,serial::Timeout::simpleTimeout(1000));
ros::init(argc, argv, "base_controller"); //init Node
ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("cmd_vel", 20, callback);
ros::spin();
return 0;
}
修改 CMakeLists:
cmake_minimum_required(VERSION 2.8.3)
project(base_controller)
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
serial
)
catkin_package(
CATKIN_DEPENDS roscpp rospy std_msgs
)
include_directories(
${catkin_INCLUDE_DIRS}
${serial_INCLUDE_DIRS}
)
add_executable(base_controller src/base_controller.cpp)
## Specify libraries to link a library or executable target against
target_link_libraries(base_controller ${catkin_LIBRARIES})
编译(catkin_ws 目录下)
# catkin_make
节点创建结束
到此,已经可以使用文首测试模块进行测试。
新:添加launch文件
功能
使 Node:teleop_twist_keyboard 和 base_controller 同时启动
步骤
1、创建launch
# roscd base_controller
# mkdir launch
# cd launch
# gedit keycontrol.launch
2、编辑如下