微软Xbox One无线手柄控制机器人
Posted
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了微软Xbox One无线手柄控制机器人相关的知识,希望对你有一定的参考价值。
ROS中的joy包提供了游戏手柄的驱动,并且包含joy_node节点,这一节点可以发布包含手柄按钮和轴信息的Joy消息。在终端中输入下面命令,安装joy包:
$ sudo apt-get install ros-kinetic-joy
Configuring the Joystick
安装好之后,将用USB线将手柄连上电脑,然后输入下面指令看看Linux能否找到设备:
$ ls /dev/input/
通常会输出下面类似的信息:
by-id event0 event2 event4 event6 event8 mouse0 mouse2 uinput by-path event1 event3 event5 event7 js0 mice mouse1
游戏手柄的名字一般为jsX,这里我们的手柄为js0,可以使用jstest命令来测试手柄:
$ sudo jstest /dev/input/js0
按下手柄上不同的按钮或者移动摇杆,可以看到相应数据发生变化:
接下来要让ROS节点joy_node能获取手柄信息,先列出手柄的权限( ls -l: 以长格式的形式查看当前目录下所有可见文件的详细属性):
$ ls -l /dev/input/js0
将会看到下面类似的输出:
crw-rw-XX- 1 root dialout 188, 0 2009-08-14 12:04 /dev/input/jsX
如果XX为rw,表示js设备配置正确;如果XX为--表示设备没有配置正确,需要添加权限:
$ sudo chmod a+rw /dev/input/js0
Starting the Joy Node
为了能发布joy消息我们需要运行joy_node节点,并且指定设备名,默认为js0(tell the joy node which joystick device to use the default is js0):
$ roscore $ rosparam set joy_node/dev "/dev/input/js0"
然后就可以运行joy_node节点:
$ rosrun joy joy_node
如果运行成功,端中会显示下面的信息:
[ INFO] [1513180661.775001483]: Opened joystick: /dev/input/js0. deadzone_: 0.050000.
打开一个新终端,输入下面命令查看具体的joy消息:
$ rostopic echo joy
sensor_msgs/Joy消息格式如下:
# Reports the state of a joysticks axes and buttons. Header header # timestamp in the header is the time the data is received from the joystick float32[] axes # the axes measurements from a joystick int32[] buttons # the buttons measurements from a joystick
蓝牙无线连接
打开Ubuntu16.04的蓝牙,查找到Xbox Wireless Controller后进行连接:
不过在连接过程中遇到了一些问题,蓝牙一连上就掉了。下面这个方法可以解决这一问题:
1. install
sudo apt install sysfsutils
2. 以管理员权限用gedit打开sysfs.conf文件
sudo gedit /etc/sysfs.conf
3. 在文件中加入下面一行:
module/bluetooth/parameters/disable_ertm = 1
4. 保存文件然后重启电脑。开机后再次连接:
待手柄上的指示灯常亮,用ls命令查看设备,可以看出js0已经安装好:
测试与校准
JStest is a simple and useful tool that you can use to calibrate your controllers’ axis.
sudo apt-get install jstest-gtk
输入下面命令打开jstest的GUI界面,选择已经连接上的Xbox One手柄
$ jstest-gtk
点击Properties属性按钮,可以进行手柄测试:
Writing a Teleoperation Node for a Linux-Supported Joystick
在工作空间中创建一个测试package:
$ cd ~/catkin_ws/src $ catkin_create_pkg learning_joy roscpp turtlesim joy $ cd ~/catkin_ws/ $ catkin_make
然后在package的src文件夹中创建turtle_teleop_joy.cpp源文件
#include <ros/ros.h> #include <geometry_msgs/Twist.h> #include <sensor_msgs/Joy.h> // create the TeleopTurtle class and define the joyCallback function that will take a joy msg class TeleopTurtle { public: TeleopTurtle(); private: void joyCallback(const sensor_msgs::Joy::ConstPtr& joy); ros::NodeHandle nh_; int linear_, angular_; // used to define which axes of the joystick will control our turtle double l_scale_, a_scale_; ros::Publisher vel_pub_; ros::Subscriber joy_sub_; }; TeleopTurtle::TeleopTurtle(): linear_(1), angular_(2) { // initialize some parameters nh_.param("axis_linear", linear_, linear_); nh_.param("axis_angular", angular_, angular_); nh_.param("scale_angular", a_scale_, a_scale_); nh_.param("scale_linear", l_scale_, l_scale_); // create a publisher that will advertise on the command_velocity topic of the turtle vel_pub_ = nh_.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 1); // subscribe to the joystick topic for the input to drive the turtle joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &TeleopTurtle::joyCallback, this); }
void TeleopTurtle::joyCallback(const sensor_msgs::Joy::ConstPtr& joy) { geometry_msgs::Twist twist;
// take the data from the joystick and manipulate it by scaling it and using independent axes to control the linear and angular velocities of the turtle twist.angular.z = a_scale_*joy->axes[angular_]; twist.linear.x = l_scale_*joy->axes[linear_];
vel_pub_.publish(twist); } int main(int argc, char** argv) {
// initialize our ROS node, create a teleop_turtle, and spin our node until Ctrl-C is pressed ros::init(argc, argv, "teleop_turtle"); TeleopTurtle teleop_turtle; ros::spin(); }
在CMakeLists中加入下面这两行:
add_executable(turtle_teleop_joy src/turtle_teleop_joy.cpp) target_link_libraries(turtle_teleop_joy ${catkin_LIBRARIES})
按照前面的操作连接并配置好手柄以后,在learning_joy目录下新建一个launch文件夹并在其中创建turtle_joy.launch文件(注意joystick设备名称要写对):
<launch> <!-- Turtlesim Node--> <node pkg="turtlesim" type="turtlesim_node" name="sim"/> <!-- joy node --> <node pkg="joy" type="joy_node" name="turtle_joy" respawn="true"> <param name="dev" type="string" value="/dev/input/js0" /> <param name="deadzone" value="0.12" /> </node> <!-- Axes --> <param name="axis_linear" value="1" type="int"/> <param name="axis_angular" value="0" type="int"/> <param name="scale_linear" value="2" type="double"/> <param name="scale_angular" value="2" type="double"/> <node pkg="learning_joy" type="turtle_teleop_joy" name="teleop"/> </launch>
编译好之后执行下面的命令,可以开启3个节点(turtlesim_node海龟仿真节点、joy_node发布手柄消息节点、turtle_teleop_joy订阅手柄消息并发布turtle1/cmd_vel消息节点),实现用手柄控制海龟运动:
roslaunch learning_joy turtle_joy.launch
用手柄上的左摇杆(下图中的1)来控制海龟:Up/Down Axis控制前进和后退;Left/Right Axis控制左转和右转
参考:
如何将 Xbox One 无线控制器连接到 Windows PC
Get to know your Xbox One Wireless Controller
How to Set Up an Xbox One Controller in Ubuntu
How do I get an Xbox One controller to work with 16.04
以上是关于微软Xbox One无线手柄控制机器人的主要内容,如果未能解决你的问题,请参考以下文章