Skip to content

Commit

Permalink
ruff check --fix
Browse files Browse the repository at this point in the history
  • Loading branch information
H1rono committed Jun 29, 2024
1 parent 442cce1 commit 8bd697d
Show file tree
Hide file tree
Showing 23 changed files with 43 additions and 44 deletions.
8 changes: 4 additions & 4 deletions app/imshow/imshow/imshow.py
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
import cv2
import rclpy
from cv_bridge import CvBridge
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2


class Imshow(Node):
def __init__(self):
super().__init__('imshow')
self.subscription=self.create_subscription(Image, 'camera_image', self.listener_callback, 10)
self.bridge=CvBridge()

def listener_callback(self, msg):
frame=self.bridge.imgmsg_to_cv2(msg, "bgr8")
cv2.imshow('Camera', frame)
Expand All @@ -24,4 +24,4 @@ def main(args=None):
rclpy.shutdown()

if __name__=='__main__':
main()
main()
4 changes: 2 additions & 2 deletions app/imshow/launch/imshow_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,6 @@ def generate_launch_description():
package="imshow",
executable="imshow",
namespace="app",
remappings=[("/app/camera/image", "/packet/camera/image")]
)
remappings=[("/app/camera/image", "/packet/camera/image")],
),
])
4 changes: 2 additions & 2 deletions app/imshow/setup.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
import os
from glob import glob

from setuptools import find_packages, setup
from setuptools import setup

package_name = 'imshow'

Expand All @@ -12,7 +12,7 @@
data_files=[
('share/ament_index/resource_index/packages',['resource/' + package_name]),
('share/' + package_name,['package.xml']),
(os.path.join('share',package_name,'launch'),glob(os.path.join('launch','*')))
(os.path.join('share',package_name,'launch'),glob(os.path.join('launch','*'))),
],
install_requires=['setuptools'],
zip_safe=True,
Expand Down
6 changes: 3 additions & 3 deletions app/power_map/launch/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,14 @@ def generate_launch_description():
config = os.path.join(
get_package_share_directory("power_map"),
"config",
"default_param.yml"
"default_param.yml",
)
return LaunchDescription([
Node(
package="power_map",
executable="power-map",
namespace="app",
parameters=[config],
remappings=[("/app/power", "/device/order/power")]
)
remappings=[("/app/power", "/device/order/power")],
),
])
4 changes: 2 additions & 2 deletions app/simple_joy_app/launch/app_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,6 @@ def generate_launch_description():
package="simple_joy_app",
executable="app",
namespace="app",
remappings=[("/app/joystick", "/device/joystick")]
)
remappings=[("/app/joystick", "/device/joystick")],
),
])
4 changes: 2 additions & 2 deletions device/camera_reader/camera_reader/camera.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
import cv2
import rclpy
from cv_bridge import CvBridge
from rclpy.node import Node
from sensor_msgs.msg import Image
import cv2
from cv_bridge import CvBridge


class Camera(Node):
Expand Down
6 changes: 3 additions & 3 deletions device/camera_reader/launch/camera_reader_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
def generate_launch_description():
return LaunchDescription([
Node(
package="camera_reader",
executable="camera_reader",
package="camera_reader",
executable="camera_reader",
namespace="device",
remappings=[("/device/camera/image", "/packet/camera/image")])
remappings=[("/device/camera/image", "/packet/camera/image")]),
])
6 changes: 3 additions & 3 deletions device/camera_reader/setup.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
import os
from glob import glob

from setuptools import find_packages, setup
from setuptools import setup

package_name = 'camera_reader'

Expand All @@ -12,7 +12,7 @@
data_files=[
('share/ament_index/resource_index/packages',['resource/' + package_name]),
('share/' + package_name,['package.xml']),
(os.path.join('share','package_name','launch'),glob(os.path.join('launch','*')))
(os.path.join('share','package_name','launch'),glob(os.path.join('launch','*'))),
],
install_requires=['setuptools'],
zip_safe=True,
Expand All @@ -26,4 +26,4 @@
'camera=camera_reader.camera:main',
],
},
)
)
2 changes: 1 addition & 1 deletion device/joystick/launch/joystick_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,5 @@

def generate_launch_description():
return LaunchDescription([
Node(package="joystick", executable="joystick", namespace="device")
Node(package="joystick", executable="joystick", namespace="device"),
])
4 changes: 2 additions & 2 deletions device/joystick/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*')))
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*'))),
],
install_requires=['setuptools'],
zip_safe=True,
Expand All @@ -24,7 +24,7 @@
tests_require=[],
entry_points={
'console_scripts': [
"joystick = joystick.joystick:main"
"joystick = joystick.joystick:main",
],
},
)
2 changes: 1 addition & 1 deletion device/nucleo_communicate_py/launch/channel_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,6 @@ def generate_launch_description() -> LaunchDescription:
main = Node(
package="nucleo_communicate_py",
executable="channel",
namespace="device"
namespace="device",
)
return LaunchDescription([main])
2 changes: 1 addition & 1 deletion device/nucleo_communicate_py/launch/receiver_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,6 @@ def generate_launch_description() -> LaunchDescription:
receiver = Node(
package="nucleo_communicate_py",
executable="receiver",
namespace="device"
namespace="device",
)
return LaunchDescription([receiver])
2 changes: 1 addition & 1 deletion device/nucleo_communicate_py/launch/sender_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,6 @@ def generate_launch_description() -> LaunchDescription:
sender = Node(
package="nucleo_communicate_py",
executable="sender",
namespace="device"
namespace="device",
)
return LaunchDescription([sender])
6 changes: 3 additions & 3 deletions device/nucleo_communicate_py/nucleo_communicate_py/channel.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import sys

import rclpy
from packet_interfaces.msg import Current, Flex, Voltage, Power
from packet_interfaces.msg import Current, Flex, Power, Voltage
from rclpy.node import Node
from std_msgs.msg import Empty

Expand All @@ -21,13 +21,13 @@ def __init__(self, mutex_serial: MutexSerial):
Empty,
"quit",
self._quit_callback,
10
10,
)
self._order_subscription = self.create_subscription(
Power,
"order/power",
self._order_callback,
10
10,
)
self._sender = Sndr(mutex_serial)
# Receiver.__init__
Expand Down
2 changes: 1 addition & 1 deletion device/nucleo_communicate_py/nucleo_communicate_py/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import sys

import rclpy
from rclpy.executors import MultiThreadedExecutor, ExternalShutdownException
from rclpy.executors import ExternalShutdownException, MultiThreadedExecutor

from .mutex_serial import MutexSerial
from .receiver import Receiver
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ def receive_raw(self) -> tuple[int, int, int, int]:
return (flex1, flex2, current, voltage)

def map_values(
self, 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 Down
6 changes: 3 additions & 3 deletions device/nucleo_communicate_py/nucleo_communicate_py/sender.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
import sys

import rclpy
from packet_interfaces.msg import Power
from rclpy.node import Node
from serial import Serial
from std_msgs.msg import Empty
from packet_interfaces.msg import Power

from .mutex_serial import MutexSerial

Expand Down Expand Up @@ -60,13 +60,13 @@ def __init__(self, mutex_serial: MutexSerial) -> None:
Empty,
"quit",
self._quit_callback,
10
10,
)
self._order_subscription = self.create_subscription(
Power,
"order/power",
self._order_callback,
10
10,
)
self._sender = Sndr(mutex_serial)

Expand Down
4 changes: 2 additions & 2 deletions device/nucleo_communicate_py/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*')))
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*'))),
],
install_requires=['setuptools'],
zip_safe=True,
Expand All @@ -26,7 +26,7 @@
'console_scripts': [
"sender = nucleo_communicate_py.sender:main",
"receiver = nucleo_communicate_py.receiver:main",
"channel = nucleo_communicate_py.channel:main"
"channel = nucleo_communicate_py.channel:main",
],
},
)
2 changes: 1 addition & 1 deletion device/pi_i2c/launch/all_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,6 @@ def generate_launch_description() -> LaunchDescription:
all_exec = Node(
package="pi_i2c",
executable="all",
namespace="device"
namespace="device",
)
return LaunchDescription([all_exec])
2 changes: 1 addition & 1 deletion device/pi_i2c/launch/depth_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,6 @@ def generate_launch_description() -> LaunchDescription:
depth = Node(
package="pi_i2c",
executable="depth",
namespace="device"
namespace="device",
)
return LaunchDescription([depth])
2 changes: 1 addition & 1 deletion device/pi_i2c/launch/imu_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,6 @@ def generate_launch_description() -> LaunchDescription:
imu = Node(
package="pi_i2c",
executable="imu",
namespace="device"
namespace="device",
)
return LaunchDescription([imu])
2 changes: 1 addition & 1 deletion device/pi_i2c/pi_i2c/all.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
import sys

import rclpy
from rclpy.executors import MultiThreadedExecutor, ExternalShutdownException
from rclpy.executors import ExternalShutdownException, MultiThreadedExecutor

from .depth import Depth
from .imu import Imu
Expand Down
5 changes: 2 additions & 3 deletions device/pi_i2c/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@

from setuptools import find_packages, setup


package_name = 'pi_i2c'

setup(
Expand All @@ -14,7 +13,7 @@
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*')))
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*'))),
],
install_requires=['setuptools'],
zip_safe=True,
Expand All @@ -27,7 +26,7 @@
'console_scripts': [
"depth = pi_i2c.depth:main",
"imu = pi_i2c.imu:main",
"all = pi_i2c.all:main"
"all = pi_i2c.all:main",
],
},
)

0 comments on commit 8bd697d

Please sign in to comment.