0
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

More than 3 years have passed since last update.

プチロボMS3LをROSのジョイスティックで動かすシンプルなpythonコード

Posted at

はじめに

ROSのlistenerノードのサンプルコードを少し書き換えて、WR-XX制御基板とシリアル通信をする操作を加えた簡単なpythonコードを書いて、プチロボ入門用の3軸指型ロボットのMS3Lを操作してみた。

環境

  • Ubuntu18.04LTE
  • ROS Melodic
  • Wonderkit/MS3L
  • ポリパッド3ターボゲームパッド

やっていること

ジョイパッケージを利用して配布されたトピックを読み込んで、サブスクライブしたゲームコントローラのジョイスティックの値にサーボモータの位置を割り当てて動かすだけです。モータの回転速度は固定値を利用しますがpythonなのでソースコードは簡単に変更できます。

ソースコード

simple_joy_wrxx_node.py
# !/usr/bin/env python
import serial, struct, time
import rospy
from sensor_msgs.msg import Joy

_serial = serial.Serial('/dev/ttyUSB0')
_serial.baudrate = 38400
_serial.parity = serial.PARITY_NONE
_serial.bytesize = serial.EIGHTBITS
_serial.stopbits = serial.STOPBITS_ONE
_serial.timeout = 0.05

def callback(data):
    command = [0xFD,0x0B,0x06,0x01,0x0A,0x6E,0x0,0x6E,0x0,0x6E,0xFE]
    command[5] = int(data.axes[0] * 50 + 110)
    command[7] = int(data.axes[1] * 50 + 110)
    command[9] = int(data.axes[2] * 50 + 110)
    for cmd in command:
        data = struct.pack("B", cmd)
        _serial.write(data)
    print(command)
    _serial.flush()

if __name__ == '__main__':
    rospy.init_node('joy_wrxx_node')
    rospy.Subscriber("joy",Joy,callback)
    rospy.spin()

終わりに

ジョイスティックのボタンに動作を割り当てて動かすことも簡単にできそうです。ROSで「いつC++(や他の言語)を使うべきか、悩んでいたのですが、オライリーの「プログラミングROS」が一つの回答をしてくれていました。

C++のノードは同じようなPythonのノードよりも速い場合がありますが、その速度の向上が、C++ノードを書いたりデバッグしたりする時間に見合うものかどうかが重要です。

自分の場合、C++を使わないと決めてから、このコードを書くまでほんの数日でした。というか、このコードを書くのに使った時間はのべ1時間くらいです。C++で書いていたらもっとずっと時間がかかっていました(C++の学習中なので・・・)。やっぱり、ROSのようなプロトタイプづくりにはPythonを利用するのは合理的な選択と言えそうですね。

0
0
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
0
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?