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)