Contents
何を学習するのか?
PS4 / Xbox One / G29 コントローラを ROS から利用する
複数のコントローラを同時に利用する

PS4 コントローラを接続
$ ls /dev/input
by-id event0 event10 event12 event14 event16 event18 event2 event21 event4 event6 event8 js0 mouse0 mouse2
by-path event1 event11 event13 event15 event17 event19 event20 event3 event5 event7 event9 mice mouse1
$ rostopic list
/diagnostics
/joy
/joy/set_feedback
/rosout
/rosout_agg
# terminal 1
$ roscore
# terminal 2
$ rosrun joy joy_node
# rosrun joy joy_node _dev:=/dev/input/js0
# terminal 3
$ rostopic echo /joy
header:
seq: 1
stamp:
secs: 1597731861
nsecs: 505892714
frame_id: ''
axes: [0.0, 0.08846031129360199, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
launch ファイルで起動 remap編
<launch>
<node respawn="true" pkg="joy" type="joy_node" name="joy_ps4" >
<param name="dev" type="string" value="/dev/input/js0" />
<remap from="joy" to="joy_ps4"/>
</node>
</launch>
$ rostopic list
/diagnostics
/joy/set_feedback
/joy_ps4
/rosout
/rosout_agg
launch ファイルで起動 GROUP編
<launch>
<group ns="joy_ps4">
<node respawn="true" pkg="joy" type="joy_node" name="joy_ps4" >
<param name="dev" type="string" value="/dev/input/js0" />
</node>
</group>
</launch>
$ rostopic list
/diagnostics
/joy_ps4/joy
/joy_ps4/joy/set_feedback
/rosout
/rosout_agg
PS4コントローラと更にXBox Oneコントローラを追加
$ ls /dev/input
by-id event0 event10 event12 event14 event16 event18 event2 event21 event3 event5 event7 event9 js1 mouse0 mouse2
by-path event1 event11 event13 event15 event17 event19 event20 event22 event4 event6 event8 js0 mice mouse1
# PS4
/dev/input/js0
# XBox One
/dev/input/js1
<launch>
<group ns="joy_ps4">
<node respawn="true" pkg="joy" type="joy_node" name="joy_ps4" >
<param name="dev" type="string" value="/dev/input/js0" />
</node>
</group>
<group ns="joy_xbox">
<node respawn="true" pkg="joy" type="joy_node" name="joy_xbox" >
<param name="dev" type="string" value="/dev/input/js1" />
</node>
</group>
</launch>
$ roslaunch ps4_xbox_joy.launch
... logging to /home/max/.ros/log/361ad208-e11b-11ea-b29c-144f8a3bd049/roslaunch-max-desktop-20779.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://max-desktop:44419/
SUMMARY
========
PARAMETERS
* /joy_ps4/joy_ps4/dev: /dev/input/js0
* /joy_xbox/joy_xbox/dev: /dev/input/js1
* /rosdistro: melodic
* /rosversion: 1.14.6
NODES
/joy_ps4/
joy_ps4 (joy/joy_node)
/joy_xbox/
joy_xbox (joy/joy_node)
ROS_MASTER_URI=http://localhost:11311
process[joy_ps4/joy_ps4-1]: started with pid [20794]
process[joy_xbox/joy_xbox-2]: started with pid [20795]
[ERROR] [1597733256.956718298]: Couldn't open joystick force feedback!
[ERROR] [1597733256.956744275]: Couldn't open joystick force feedback!
$ rostopic list
/diagnostics
/joy_ps4/joy
/joy_ps4/joy/set_feedback
/joy_xbox/joy
/joy_xbox/joy/set_feedback
/rosout
/rosout_agg
$ rostopic echo -c /joy_ps4/joy
$ rostopic echo -c /joy_xbox/joy
GROUP, nodeのnameを分ける事によって同時に
違うトピックで取得出来る
ROS Pythonで値の取得
#! /usr/bin/env python
import rospy
from sensor_msgs.msg import Joy
def joy_callback(joy_msg):
# ------------- AXES ---------------
rospy.loginfo("------------------")
# XboxOne Analog:left left -1.0 right: 1.0
rospy.loginfo("axes0 AN-L LR %s", joy_msg.axes[0])
# XboxOne Analog:left up 1.0 down: -1.0
rospy.loginfo("axes1 AN-L UD: %s", joy_msg.axes[1])
# XboxOne BackButton L
rospy.loginfo("axes2 BB-L : %s", joy_msg.axes[2])
# XboxOne Analog:right left -1.0 right: 1.0
rospy.loginfo("axes3 AN-R LR: %s", joy_msg.axes[3])
# XboxOne Analog:right up 1.0 down: -1.0
rospy.loginfo("axes4 Anl-R UD : %s", joy_msg.axes[4])
# XboxOne BackButton L
rospy.loginfo("axes5 BB-R UD : %s", joy_msg.axes[5])
# XboxOne Cross Left:1.0 Right:-1.0
rospy.loginfo("axes6 cross LR: %s", joy_msg.axes[6])
# XboxOne Cross Up:1.0 Down:-1.0
rospy.loginfo("axes7 cross UD: %s", joy_msg.axes[7])
# ------------- Buttons ---------------
rospy.loginfo("buttons0 A %s", joy_msg.buttons[0])
rospy.loginfo("buttons1 B %s", joy_msg.buttons[1])
rospy.loginfo("buttons2 X %s", joy_msg.buttons[2])
rospy.loginfo("buttons3 Y %s", joy_msg.buttons[3])
rospy.loginfo("buttons4 L %s", joy_msg.buttons[4])
rospy.loginfo("buttons5 R %s", joy_msg.buttons[5])
rospy.loginfo("buttons6 CL %s", joy_msg.buttons[6])
rospy.loginfo("buttons7 CR %s", joy_msg.buttons[7])
rospy.loginfo("buttons8 X %s", joy_msg.buttons[8])
def start():
global pub
rospy.init_node('xbox')
rospy.Subscriber("joy", Joy, joy_callback, queue_size=1)
rospy.spin()
if __name__ == '__main__':
start()
#! /usr/bin/env python
import rospy
from sensor_msgs.msg import Joy
def joy_callback(joy_msg):
rospy.loginfo("----------------")
# ------------- AXES ---------------
# PS4 Analog:left left 1.0 right: -1.0
rospy.loginfo("axes0 AN-L LR %s", joy_msg.axes[0])
# PS4 Analog:left up 1.0 down: -1.0
rospy.loginfo("axes1 AN-L UD: %s", joy_msg.axes[1])
# PS4 BackButton L
rospy.loginfo("axes2 BB-L : %s", joy_msg.axes[2])
# PS4 Analog:right left 1.0 right: 1.0
rospy.loginfo("axes3 AN-R LR: %s", joy_msg.axes[3])
# PS4 Analog:right up 1.0 down: -1.0
rospy.loginfo("axes4 Anl-R UD : %s", joy_msg.axes[4])
# PS4 BackButton L
rospy.loginfo("axes5 BB-R UD : %s", joy_msg.axes[5])
# PS4 Cross Left:1.0 Right:-1.0
rospy.loginfo("axes6 cross LR: %s", joy_msg.axes[6])
# PS4 Cross Up:1.0 Down:-1.0
rospy.loginfo("axes7 cross UD: %s", joy_msg.axes[7])
# ------------- Buttons ---------------
rospy.loginfo("buttons0 X %s", joy_msg.buttons[0])
rospy.loginfo("buttons1 O %s", joy_msg.buttons[1])
rospy.loginfo("buttons2 A %s", joy_msg.buttons[2])
rospy.loginfo("buttons3 [] %s", joy_msg.buttons[3])
rospy.loginfo("buttons4 L %s", joy_msg.buttons[4])
rospy.loginfo("buttons5 R %s", joy_msg.buttons[5])
rospy.loginfo("buttons6 CL %s", joy_msg.buttons[8])
rospy.loginfo("buttons7 CR %s", joy_msg.buttons[9])
rospy.loginfo("buttons8 P %s", joy_msg.buttons[10])
def start():
global pub
rospy.init_node('ps4')
rospy.Subscriber("joy", Joy, joy_callback, queue_size=1)
rospy.spin()
if __name__ == '__main__':
start()
#! /usr/bin/env python
import rospy
from sensor_msgs.msg import Joy
def joy_callback(joy_msg):
# ------------- AXES ---------------
rospy.loginfo("---------G29--------")
# Steer / left 1.0 right: -1.0
rospy.loginfo("axes0 AN-L LR %s", joy_msg.axes[0])
# Left Pedal / up -1.0 down: 1.0
rospy.loginfo("axes1 L : %s", joy_msg.axes[1])
# Right Pedal / up -1.0 down: 1.0
rospy.loginfo("axes2 R : %s", joy_msg.axes[2])
# Center Pedal / up -1.0 down: 1.0
rospy.loginfo("axes3 C : %s", joy_msg.axes[3])
# LR / L -1.0 R: 1.0
rospy.loginfo("axes4 LR : %s", joy_msg.axes[4])
# UD / U 1.0 D: -1.0
rospy.loginfo("axes5 UD : %s", joy_msg.axes[5])
# ------------- Buttons ---------------
rospy.loginfo("buttons0 X %s", joy_msg.buttons[0])
rospy.loginfo("buttons1 [] %s", joy_msg.buttons[1])
rospy.loginfo("buttons2 O %s", joy_msg.buttons[2])
rospy.loginfo("buttons3 ^ %s", joy_msg.buttons[3])
rospy.loginfo("buttons4 R %s", joy_msg.buttons[4])
rospy.loginfo("buttons5 L %s", joy_msg.buttons[5])
rospy.loginfo("buttons6 R2 %s", joy_msg.buttons[6])
rospy.loginfo("buttons7 L2 %s", joy_msg.buttons[7])
rospy.loginfo("buttons8 SHARE %s", joy_msg.buttons[8])
rospy.loginfo("buttons8 OPTION %s", joy_msg.buttons[9])
rospy.loginfo("buttons8 R3 %s", joy_msg.buttons[10])
rospy.loginfo("buttons8 L3 %s", joy_msg.buttons[11])
rospy.loginfo("buttons8 + %s", joy_msg.buttons[19])
rospy.loginfo("buttons8 - %s", joy_msg.buttons[20])
rospy.loginfo("buttons8 Enter %s", joy_msg.buttons[23])
rospy.loginfo("buttons8 PS %s", joy_msg.buttons[24])
def start():
global pub
rospy.init_node('xbox')
rospy.Subscriber("joy", Joy, joy_callback, queue_size=1)
rospy.spin()
if __name__ == '__main__':
start()
Software Engineer #Unity #iOS