大事なことを最初に言うと、Windows10、WSL2、ROS 2の組み合わせは時間の無駄だからやめとけ。 素直にUbuntu PC用意するかWindows11のPro用意しよう。
GWを2日使って、DOFBOTのラズパイに入れたROS 2と別のUbuntu PCに入れたROS 2で通信させました。 これでUbuntu側からDOFBOTのLEDが制御できるようになりました。 うまくやればDOFBOT側は最低限のAPI呼び出しをするだけで、Ubuntu側でロボ制御の開発ができそうです。
Windowsさえ使わなければ、特に問題なく動きました。
DOFBOT側の設定
~/.bashrcに設定を書く。 ROS_DOMAIN_IDは設定しなくても大丈夫。 Ubuntu側のIPアドレスをROS_MASTER_URIとして環境変数に登録する。 自分のIPアドレスをROS_IPとして、環境変数に登録する。
# export ROS_DOMAIN_ID=1 export ROS_MASTER_URI=http://192.168.1.20:11311 export ROS_IP=192.168.1.18 source /home/dofbot/mashiro_ws/install/setup.bash
LEDを点灯させるソースコード
import rclpy from rclpy.node import Node from std_msgs.msg import Int8 import time from Arm_Lib import Arm_Device class LedSub(Node): def __init__(self): super().__init__("ledsub") self.sub = self.create_subscription(Int8, 't_led', self.callback, 10) self.arm = Arm_Device() time.sleep(0.1) def callback(self, msg): self.get_logger().info(f'sub {msg.data}') if msg.data == 0: self.arm.Arm_RGB_set(50, 0, 0) #RGB Red light on elif msg.data == 1: self.arm.Arm_RGB_set(0, 50, 0) #RGB Green light on elif msg.data == 2: self.arm.Arm_RGB_set(0, 0, 50) #RGB Blue light on else: self.arm.Arm_RGB_set(0, 0, 0) #RGB Red light on # time.sleep(1) def main(): rclpy.init() node = LedSub() try: rclpy.spin(node) except KeyboardInterrupt: print("stop") del node.arm rclpy.shutdown() print("end of main") if __name__ == '__main__': main()
Ubuntu側の設定
こっちは自分自身のIPアドレスを環境変数に入れるだけ。
export ROS_IP=192.168.1.20
Pythonのソースはこう
import rclpy from rclpy.node import Node from std_msgs.msg import Int8 class LedPub(Node): def __init__(self): super().__init__("ledpub") self.pub = self.create_publisher(Int8, 't_led', 10) self.timer = self.create_timer(1, self.timer_callback) self.i = 0 def timer_callback(self): msg = Int8() if self.i < 3: msg.data = self.i self.i += 1 else: msg.data = 0 self.i = 0 # self.destroy_timer(self.timer) self.pub.publish(msg) self.get_logger().info(f'Pub LED {msg.data}') def main(): rclpy.init() node = LedPub() try: rclpy.spin(node) except KeyboardInterrupt: print("stop") rclpy.shutdown() print("end of main") if __name__ == '__main__': main()