Skip to content

Commit

Permalink
Merge pull request #8 from rogy-AquaLab/fix
Browse files Browse the repository at this point in the history
Fix
  • Loading branch information
H1rono committed Jun 3, 2024
2 parents 088f8c2 + 04964de commit 2b2f315
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 10 deletions.
2 changes: 1 addition & 1 deletion device/joystick/joystick/joystick.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ def __init__(self):
self.get_logger().info(f"Using controller: {name}")

def _timer_callback(self):
self.get_logger().info("tick")
self.get_logger().debug("tick")
pygame.event.pump()

numaxes = self._joystick.get_numaxes()
Expand Down
11 changes: 5 additions & 6 deletions device/nucleo_communicate_py/nucleo_communicate_py/receiver.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
import sys

import rclpy
from rclpy.node import Node
from packet_interfaces.msg import Current, Flex, Voltage
from rclpy.node import Node
from serial import Serial
from std_msgs.msg import Header

from .mutex_serial import MutexSerial

Expand All @@ -30,7 +29,7 @@ def receive_raw(self) -> tuple[int, int, int, int]:
return (flex1, flex2, current, voltage)

def map_values(
flex1: int, flex2: int, current: int, voltage: int
self, flex1: int, flex2: int, current: int, voltage: int
) -> tuple[int, int, float, float]:
# TODO: current, voltageの計算はnucleo側と要相談
return (flex1, flex2, current / 0xFFFF, voltage / 0xFFFF)
Expand All @@ -52,15 +51,15 @@ def __init__(self, mutex_serial: MutexSerial) -> None:
self._recv = Recv(mutex_serial)

def _timer_callback(self) -> None:
self.get_logger().trace("tick")
self.get_logger().debug("tick")
flex1, flex2, current, voltage = self._recv.receive_raw()
self.get_logger().info(f"received from nucleo: {flex1=}, {flex2=}, {current=}, {voltage=}")
flex1, flex2, current, voltage = self._recv.map_values(flex1, flex2, current, voltage)
self._flex1_publisher.publish(Flex(value=flex1))
self._flex2_publisher.publish(Flex(value=flex2))
# TODO: データのマッピングはnucleo側と相談
self._current_publisher.publish(Flex(value=current))
self._voltage_publisher.publish(Flex(value=voltage))
self._current_publisher.publish(Current(value=current))
self._voltage_publisher.publish(Voltage(value=voltage))


def main(args=sys.argv):
Expand Down
4 changes: 2 additions & 2 deletions device/pi_i2c/pi_i2c/depth.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
import sys

import rclpy
from rclpy.node import Node
from packet_interfaces.msg import Depth as DepthMsg
from rclpy.node import Node


class Depth(Node):
Expand All @@ -14,7 +14,7 @@ def __init__(self) -> None:
def _timer_callback(self) -> None:
# TODO
# 深さセンサーからデータを取得してpublish
self.get_logger().info("tick")
self.get_logger().debug("tick")


def main(args=sys.argv):
Expand Down
2 changes: 1 addition & 1 deletion device/pi_i2c/pi_i2c/imu.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ def __init__(self) -> None:
def _timer_callback(self) -> None:
# TODO
# IMUからデータを取得してpublish
self.get_logger().info("tick")
self.get_logger().debug("tick")


def main(args=sys.argv):
Expand Down

0 comments on commit 2b2f315

Please sign in to comment.