实验室有这么酷的驾驶设备,来了一年还没有实际操作过,早就蠢蠢欲试了,哈哈哈不过之前负责的师兄还在就一直没敢用,现在他毕业了就可以为所欲为了
之前师兄好像都是在Windows下开发的,我觉得比较麻烦而且与现有的框架感觉兼容性不高,所以还是选择了在Linux下开发
首先要确定插入的设备哪一个是G29方向盘,下面两个命令都可以
ls /dev/input
或
dmesg
一般来说是event11
或js0
要查看方向盘信息,在终端输入
cat /dev/input/js0 | hexdump
输出信息如下
(base) redwall@redwall-desktop:~$ cat /dev/input/js0 | hexdump
0000000 d754 0053 0000 0081 d754 0053 0000 0181
0000010 d754 0053 0000 0281 d754 0053 0000 0381
0000020 d754 0053 0000 0481 d754 0053 0000 0581
0000030 d754 0053 0000 0681 d754 0053 0000 0781
0000040 d754 0053 0000 0881 d754 0053 0000 0981
显然没什么可读性
安装操纵杆的校准工具:jstest-gtk
sudo aptitude install jstest-gtk
建议大家熟悉使用aptitude而不是apt
安装完成后在终端运行
jstest-gtk /dev/input/js0
出现如下图形界面,方向盘信息均在图形界面中进行了显示
安装并编译相关包,在终端输入
sudo aptitude install ros-melodic-joy
sudo aptitude install ros-melodic-joystick
sudo aptitude install ros-melodic-joystick-drivers
rosdep install joy
rosmake joy
在两个终端中分别输入
roscore
rosrun joy joy_node
查看现有的话题
(base) redwall@redwall-desktop:~/catkin_ws$ rostopic list
/diagnostics
/joy
/joy/set_feedback
/rosout
/rosout_agg
其中/joy
话题包含了需要的方向盘信息,查看/joy
话题的内容
(base) redwall@redwall-desktop:~$ rostopic echo /joy
输出
---
header:
seq: 386
stamp:
secs: 1657894839
nsecs: 565566079
frame_id: "/dev/input/js0"
axes: [0.648137629032135, 0.0, 0.0, 0.0, 0.0, 0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
---
header:
seq: 387
stamp:
secs: 1657894839
nsecs: 567570108
frame_id: "/dev/input/js0"
axes: [0.6481055021286011, 0.0, 0.0, 0.0, 0.0, 0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
---
header:
seq: 388
stamp:
secs: 1657894839
nsecs: 573687380
frame_id: "/dev/input/js0"
axes: [0.6480733752250671, 0.0, 0.0, 0.0, 0.0, 0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
查看/joy
话题的信息
(base) redwall@redwall-desktop:~$ rostopic info /joy
Type: sensor_msgs/Joy
Publishers:
* /joy_node (http://redwall-desktop:41415/)
Subscribers: None
可以看到该话题是由/joy_node
节点发布的,信息的数据类型为sensor_msgs/Joy
查看sensor_msgs/Joy
的消息格式
(base) redwall@redwall-desktop:~$ rosmsg show sensor_msgs/Joy
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[] axes
int32[] buttons
所以在正常使用中只要订阅该话题,并对该话题发布的消息进行解析即可获取G29方向盘的信息
编写简单的测试程序
#include
#include
#include
using namespace std;
void steer_callback(const sensor_msgs::Joy::ConstPtr &msg)
{
cout << "Receive control message from:" << msg->header.frame_id << endl;
for (int i = 0; i < msg->axes.size(); ++i)
{
if (msg->axes[i] != 0.0)
{
cout << "Axis " << i << " is not zero!" << endl;
cout << "Axis " << i << " value:" << msg->axes[i] << endl;
}
}
for (int i = 0; i < msg->buttons.size(); ++i)
{
if (msg->buttons[i] != 0.0)
{
cout << "Button " << i << " is not zero!" << endl;
cout << "Button " << i << " value:" << msg->axes[i] << endl;
}
}
cout << endl;
}
int main(int argc, char *argv[])
{
ros::init(argc, argv, "logitech_steer");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("/joy", 1, steer_callback);
ros::spin();
return 0;
}
编写简单的launch文件
<?xml version="1.0"?>
<launch>
<node pkg="joy" type="joy_node" name="joy_node" output="screen" />
<node pkg="steer_test" type="steer_test" name="steer_test" output="screen" />
</launch>
运行输出
(base) redwall@redwall-desktop:~/catkin_ws$ roslaunch steer_test steer_test.launch
... logging to /home/redwall/.ros/log/dbe33e8e-043a-11ed-a8dc-000babe43e9a/roslaunch-redwall-desktop-20515.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://redwall-desktop:46371/
SUMMARY
========
PARAMETERS
* /rosdistro: melodic
* /rosversion: 1.14.13
NODES
/
joy_node (joy/joy_node)
steer_test (steer_test/steer_test)
ROS_MASTER_URI=http://localhost:11311
process[joy_node-1]: started with pid [20547]
process[steer_test-2]: started with pid [20548]
[ WARN] [1657895770.683714324]: Couldn't set gain on joystick force feedback: Bad file descriptor
[ INFO] [1657895770.685046029]: Opened joystick: /dev/input/js0. deadzone_: 0.050000.
Receive control message from:/dev/input/js0
Axis 0 is not zero!
Axis 0 value:0.648041
Receive control message from:/dev/input/js0
Axis 0 is not zero!
Axis 0 value:0.648009
Receive control message from:/dev/input/js0
Axis 0 is not zero!
Axis 0 value:0.647977
Receive control message from:/dev/input/js0
Axis 0 is not zero!
Axis 0 value:0.647945
方向盘 | axes[0] |
---|---|
离合 | axes[1] |
刹车 | axes[3] |
油门 | axes[2] |
左拨片 | buttons[5] |
右拨片 | buttons[4] |
红色圆环包围的回车键 | buttons[23] |
加号键 | buttons[19] |
减号键 | buttons[20] |
方向上下键 | axes[5] |
方向左右键 | axes[4] |
L2键 | buttons[7] |
L3键 | buttons[11] |
R2键 | buttons[6] |
R3键 | buttons[10] |
罗技G29方向盘linux下的开发