ロボット・アプリケーション作成のための開発環境であるROSをプラットホームとして利用し、PCゲーム用のコントローラーでドローンを操縦するためのPythonプログラムを紹介いたします。
ROSを利用することで、実行に必要なPythonによるコーディング作業が大幅に省略できます。
はじめに
ここで紹介するサンプルプログラムを正常に動作させるためには、以下の条件が全て満たされている必要があります。
動作に必要な条件
- ROS Indigo 以降のバージョンが正しく動作していること
- ROSのワークスペース設定等の初期設定が完了していること
- 上記ワークスペースにBeBop2用ROSドライバーパッケージおよびジョイスティック用パッケージがセットアップされていること
- 使用するコントローラーがOSレベルで正しく認識されていること
サンプルコード
サンプルプログラムの動作確認環境
- OS: ubuntu16.04LTS(64bit)
- ROS: kinetic
- Python: 3.4.1
- Package: bebop_autonomy, ros-kinetic-joy, joystick
- Joypad: Microsoft Xbox One Wireless Controller (model 1537)
1)bebop_autonomyを使用する
最初に紹介するのは、Parrot Bebopや、Bebop2用のROSドライバーであるbebop_autonomyを活用する方法です。標準的なコントローラーであれば、設定の変更無しですぐに使用することができます。
bebop_autonomyが既にセットアップされており、コントローラーのキーマッピングがデフォルトのままで支障がなければ、次のコマンドを実行するだけですぐにコントローラーが使用できるようになります。
まず、ターミナルを開き
$ roslaunch bebop_driver bebop_node.launch
を実行します。一通りのコマンドが実行されたことを確認したら、もう一つ別のターミナルを開き
$ roslaunch bebop_tools joy_teleop.launch
を実行します。
デフォルの設定では上手くコントローラーが使用できない場合は、
bebop_autonomy/bebop_tools/launch/joy_teleop.launch
をご自分の環境に合わせて修正してください。
joy_teleop.launchの内容は以下のようになっています。
<launch>
<arg name="joy_dev" default="/dev/input/js0" />
<arg name="joy_config" default="log710" />
<arg name="teleop_config" default="$(find bebop_tools)/config/$(arg joy_config).yaml" />
<arg name="namespace" default="bebop" />
<group ns="$(arg namespace)">
<rosparam file="$(arg teleop_config)" command="load" />
<node pkg="joy" type="joy_node" name="joy_node">
<param name="dev" value="$(arg joy_dev)" />
<param name="deadzone" value="0.2" />
<param name="autorepeat_rate" value="20" />
</node>
<node pkg="joy_teleop" type="joy_teleop.py" name="joy_teleop">
</node>
</group>
</launch>
環境によって変更する必要がある箇所
2行目)"/dev/input/js0":使用するコントローラーのデバイス名に合わせてください。
3行目)"log710":デフォルトでは、キーマップが下記ファイルで設定されています。
bebop_autonomy/bebop_tools/config/log710.yaml
※Xbox 360用のxbox360.yamlも用意されていますので、"log710"の部分を"xbox360"に書き換えるだけで変更できます。もし自分が使い慣れたキーマップで使用したい場合は、yamlファイルの中を書き換えるか新しくyamlファイルを作成してください。
2)コントールプログラムを自作する
次に紹介するのは、プログラムを自作する方法です。今回は、ターミナルを2つ開かなくも使えるようにしたlaunchファイルと、BeBop2用ROSドライバーに依存しない、汎用的なコントローラー用のPythonプログラムを紹介いたします。
まず、先に紹介したbebop_node.launchと同じ場所に、好きなファイル名でlaunchファイルを作成します。新しいlaunchファイル(ここでは、bebop_controller.launchとしました)の内容は以下を参考にしてください。
<launch>
<arg name="namespace" default="bebop" />
<arg name="drone_type" default="bebop2" />
<arg name="config_file" default="$(find bebop_driver)/config/defaults.yaml" />
<arg name="joy_dev" default="/dev/input/js0" />
<group ns="$(arg namespace)">
<node pkg="bebop_driver" name="bebop_driver" type="bebop_driver_node" output="screen">
<rosparam command="load" file="$(arg config_file)" />
</node>
<include file="$(find bebop_description)/launch/description.launch" />
<node pkg="joy" type="joy_node" name="joy_node">
<param name="dev" value="$(arg joy_dev)" />
<param name="deadzone" value="0.2" />
<param name="autorepeat_rate" value="20" />
</node>
<node pkg="bebop_driver" type="drone_controller.py" name="drone_controller">
</node>
</group>
</launch>
次に、制御用のPythonプログラム(ここでは、drone_controller.pyとしました)について説明します。
drone_controller.pyは、bebop_autonomy/bebop_driver/script/に配置し、プログラムとして実行可能となるよう、アクセス権の設定変更を行ってください。
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
import time
from std_msgs.msg import Empty
from geometry_msgs.msg import Twist
from sensor_msgs.msg import Joy
COMMAND_PERIOD = 100 #ms
class DroneController(object):
def __init__(self):
self._twist = Twist()
self._pubTakeoff = rospy.Publisher('/bebop/takeoff',Empty, queue_size = 10)
self._pubLand = rospy.Publisher('/bebop/land', Empty, queue_size = 10)
self._pubReset = rospy.Publisher('/bebop/reset', Empty, queue_size = 10)
self._pubTwist = rospy.Publisher('/bebop/cmd_vel', Twist, queue_size = 10)
self._teleop_sub = rospy.Subscriber('joy', Joy, self.callback)
self._twist_Timer = rospy.Timer(rospy.Duration(COMMAND_PERIOD/1000.0), self.Send_twist)
rospy.on_shutdown(self.SendLand)
def callback(self, data):
if data.buttons[5] == 1: # RB
if data.buttons[1] == 1: # RB + B
self.SendEmergency()
elif data.buttons[0] == 1: # RB + A
self.SendLand()
elif data.buttons[3] == 1: # RB + Y
self.SendTakeoff()
else: # RB
value_xyza = [0, 0, 0, 0]
value_xyza[0] = float(data.axes[4]) # Right thumb stick (up/down) FRONT/BACK
value_xyza[1] = float(data.axes[3]) # Right thumb stick (left/right) LEFT/RIGHT
value_xyza[2] = float(data.axes[1]) # Left thumb stick (up/down) UP/DOWN
value_xyza[3] = float(data.axes[0]) # Left thumb stick (left/right) L-TURN/R-TURN
if value_xyza <> [0, 0, 0, 0]:
self._twist.linear.x = value_xyza[0]
self._twist.linear.y = value_xyza[1]
self._twist.linear.z = value_xyza[2]
self._twist.angular.z = value_xyza[3]
def SendEmergency(self):
self._pubReset.publish(Empty())
def SendLand(self):
self._pubLand.publish(Empty())
def SendTakeoff(self):
self._pubTakeoff.publish(Empty())
def Send_twist(self, event):
self._pubTwist.publish(self._twist)
if __name__ == '__main__':
rospy.init_node('drone_controller')
drone_controller = DroneController()
rospy.spin()
ファイルの作成が完了したら、ターミナルを開き
$ roslaunch bebop_driver bebop_controller.launch
を実行します。エラーが出る場合、ファイル名、ファイルの配置場所、アクセス権の設定に間違いがないかチェックしてみてください。
注)上記コマンドを実行しbebop2への接続が成功すると、ドローンのカメラ映像やナビゲーションデータ取得に伴う多くのエラーが返ってくることがありますが、コントローラーの使用に影響はありません。