From aec0a94b7425292fbd3ea5f347e5a3d7eb552fb1 Mon Sep 17 00:00:00 2001 From: 23-yoshikawa Date: Mon, 24 Jun 2024 17:51:27 +0900 Subject: [PATCH] =?UTF-8?q?topic=E5=90=8D=E3=82=92=E6=94=B9=E5=90=8D?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- device/nucleo_communicate_py/nucleo_communicate_py/channel.py | 4 ++-- .../nucleo_communicate_py/nucleo_communicate_py/receiver.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/device/nucleo_communicate_py/nucleo_communicate_py/channel.py b/device/nucleo_communicate_py/nucleo_communicate_py/channel.py index 6c3f422..7df5c52 100644 --- a/device/nucleo_communicate_py/nucleo_communicate_py/channel.py +++ b/device/nucleo_communicate_py/nucleo_communicate_py/channel.py @@ -33,8 +33,8 @@ def __init__(self, mutex_serial: MutexSerial): # Receiver.__init__ self._current_publisher = self.create_publisher(Current, "current", 10) # NOTE: packet_interfaces/Composed の命名と揃える - self._flex1_publisher = self.create_publisher(Flex, "flexsensor1", 10) - self._flex2_publisher = self.create_publisher(Flex, "flexsensor2", 10) + self._flex1_publisher = self.create_publisher(Flex, "flex/1", 10) + self._flex2_publisher = self.create_publisher(Flex, "flex/2", 10) self._voltage_publisher = self.create_publisher(Voltage, "voltage", 10) self._timer = self.create_timer(0.5, self._recv_callback) self._recv = Recv(mutex_serial) diff --git a/device/nucleo_communicate_py/nucleo_communicate_py/receiver.py b/device/nucleo_communicate_py/nucleo_communicate_py/receiver.py index 3739a13..7223e5a 100644 --- a/device/nucleo_communicate_py/nucleo_communicate_py/receiver.py +++ b/device/nucleo_communicate_py/nucleo_communicate_py/receiver.py @@ -44,8 +44,8 @@ def __init__(self, mutex_serial: MutexSerial) -> None: super().__init__("receiver") self._current_publisher = self.create_publisher(Current, "current", 10) # NOTE: packet_interfaces/Composed の命名と揃える - self._flex1_publisher = self.create_publisher(Flex, "flexsensor1", 10) - self._flex2_publisher = self.create_publisher(Flex, "flexsensor2", 10) + self._flex1_publisher = self.create_publisher(Flex, "flex/1", 10) + self._flex2_publisher = self.create_publisher(Flex, "flex/2", 10) self._voltage_publisher = self.create_publisher(Voltage, "voltage", 10) self._timer = self.create_timer(0.5, self._timer_callback) self._recv = Recv(mutex_serial)