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