通信topicの名前を’oculus_topic’に変更している。
bytesを使用するときは1バイトに収まる値にしないとエラーになる。
機材固有の計算以降は機材固有の計算式なので単純な流用はできない。
__GetEulerOffsetは将来、正面をリセットするのに必要。
ログは、毎回送られてきたデータ表示しているが、これは数回に一回表示に変えるなどして、表示負荷を減らしたほうが良い。
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# Copyright 2022 robot-creation-diary.com
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# チュートリアルの内容から、HMDのオイラー角を受け取りそれに合わせて
# サーボモータを制御するように変更してある
# 使用機材:サーボモータ:Miuzei MS18、サーボモータコントローラ:20軸サーボモータコントローラ WR-MSXX
import rclpy
from rclpy.node import Node
from cpp_pubsub.msg import OculusMsg
import serial
class MinimalSubscriber(Node):
def __init__(self):
super().__init__('minimal_subscriber')
self.subscription = self.create_subscription(
OculusMsg,
'oculus_topic',
self.listener_callback,
10)
self.subscription # prevent unused variable warning
# Comportを開く
self.comport = serial.Serial("COM3", 38400)
def __del__(self):
# comportを閉じる
self.comport.close()
def listener_callback(self, msg):
# 送られてきた値を表示
self.get_logger().info('I heard x: "%f" ' % msg.head_euler[0])
self.get_logger().info('I heard y: "%f" ' % msg.head_euler[1])
self.get_logger().info('I heard z: "%f" ' % msg.head_euler[2])
self.move_servo(
self.euler_to_servo(msg.head_euler[0], 0, False),
self.euler_to_servo(msg.head_euler[1], 90, False)
)
# 機材固有の計算-----------------------------------------
# サーボにデータ送信
def move_servo(self, servo1, servo2):
test = []
test.append(0xFD)
test.append(0x09)
test.append(0x06)
test.append(0x00)
test.append(0x0F)
# 1byteに収まらない数値の場合"bytes"でエラーになる
test.append(int(servo1))
test.append(0x0)
# 1byteに収まらない数値の場合"bytes"でエラーになる
test.append(int(servo2))
test.append(0xFE)
bs = bytes(test)
self.comport.write(bs)
# 機材固有の計算Eulerからサーボの角度に変更
def euler_to_servo(self, euler, ezero, pm):
if pm: # 向きの指定
return self.__euler_to_servo_main(euler, ezero)
else:
return 221 - self.__euler_to_servo_main(euler, ezero)
# 主要確度計算110が中心なのでそれを中心になるように取得
def __euler_to_servo_main(self, euler, ezero):
# 110を正面0とする。1-220になるように設定
ebuf = self.__get_euler_offset(euler, ezero)
if 0 <= ebuf:
if 110 < ebuf:
return 220
else:
return ebuf + 110
else:
if ebuf <= -110:
return 1
else:
return ebuf + 110
# オフセット設定。(ゼロ点設定)
def __get_euler_offset(self, euler, ezero):
# ezeroの位置を正面0とする。
if (euler < ezero - 180):
euler += 360
return euler-ezero
if (ezero + 180 < euler):
euler -= 360
return euler - ezero
return euler - ezero
def main(args=None):
rclpy.init(args=args)
minimal_subscriber = MinimalSubscriber()
rclpy.spin(minimal_subscriber)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()