Skip to content

Commit

Permalink
Python linting
Browse files Browse the repository at this point in the history
  • Loading branch information
hello-amal committed May 21, 2024
1 parent 7dbc951 commit 2402ff5
Show file tree
Hide file tree
Showing 11 changed files with 130 additions and 117 deletions.
2 changes: 2 additions & 0 deletions .flake8
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
[flake8]
max-line-length = 120
22 changes: 22 additions & 0 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,20 @@ repos:
hooks:
- id: black

# Flake8 lints Python code
- repo: https://github.com/pycqa/flake8
rev: 5.0.4
hooks:
- id: flake8

# MyPy does static type-checking in Python
# Note: In practice this doesn't currently do much, since we don't have type hints in our Python scripts.
- repo: https://github.com/pre-commit/mirrors-mypy
rev: v0.981
hooks:
- id: mypy
args: [--install-types, --non-interactive, --no-strict-optional, --ignore-missing-imports]

# Beautysh formats Bash scripts
- repo: https://github.com/lovesegfault/beautysh
rev: v6.2.1
Expand Down Expand Up @@ -62,3 +76,11 @@ repos:
hooks:
- id: prettier
types_or: [css, html, javascript, json, jsx, ts, tsx]

# # ESLint lints Javascript/Typescript files
# - repo: https://github.com/pre-commit/mirrors-eslint
# rev: 'v8.56.0' # Use the sha / tag you want to point at
# hooks:
# - id: eslint
# files: \.[jt]sx?$ # *.js, *.jsx, *.ts and *.tsx
# types: [file]
3 changes: 0 additions & 3 deletions launch/gripper_camera.launch.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
from launch_ros.actions import Node

import launch
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration


def generate_launch_description():
Expand Down
1 change: 1 addition & 0 deletions launch/multi_camera.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration

json_path = os.path.join(
get_package_share_directory("stretch_core"), "config", "HighAccuracyPreset.json"
Expand Down
3 changes: 0 additions & 3 deletions launch/navigation_camera.launch.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
from launch_ros.actions import Node

import launch
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration


def generate_launch_description():
Expand Down
72 changes: 32 additions & 40 deletions launch/web_interface.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,19 +13,15 @@
GroupAction,
IncludeLaunchDescription,
)
from launch.conditions import IfCondition, LaunchConfigurationNotEquals, UnlessCondition
from launch.conditions import LaunchConfigurationNotEquals
from launch.launch_description_sources import (
FrontendLaunchDescriptionSource,
PythonLaunchDescriptionSource,
)
from launch.substitutions import (
AndSubstitution,
FindExecutable,
LaunchConfiguration,
NotSubstitution,
OrSubstitution,
PathJoinSubstitution,
ThisLaunchFileDir,
)


Expand Down Expand Up @@ -77,93 +73,94 @@ def map_configuration_to_drivers(model, tool, has_beta_teleop_kit, has_nav_head_
if (
model == "RE1V0"
and tool == "tool_stretch_gripper"
and has_beta_teleop_kit == False
and has_nav_head_cam == False
and has_beta_teleop_kit is False
and has_nav_head_cam is False
):
return "d435-only", False, False, False
elif (
model == "RE1V0"
and tool == "tool_stretch_gripper"
and has_beta_teleop_kit == True
and has_nav_head_cam == False
and has_beta_teleop_kit is True
and has_nav_head_cam is False
):
return "d435-only", True, True, False
elif (
model == "RE1V0"
and tool == "tool_stretch_dex_wrist"
and has_beta_teleop_kit == False
and has_nav_head_cam == False
and has_beta_teleop_kit is False
and has_nav_head_cam is False
):
return "d435-only", False, False, False
elif (
model == "RE1V0"
and tool == "tool_stretch_dex_wrist"
and has_beta_teleop_kit == True
and has_nav_head_cam == False
and has_beta_teleop_kit is True
and has_nav_head_cam is False
):
return "d435-only", True, True, False
# Stretch 2
elif (
model == "RE2V0"
and tool == "tool_stretch_gripper"
and has_beta_teleop_kit == False
and has_nav_head_cam == False
and has_beta_teleop_kit is False
and has_nav_head_cam is False
):
return "d435-only", False, False, False
elif (
model == "RE2V0"
and tool == "tool_stretch_gripper"
and has_beta_teleop_kit == True
and has_nav_head_cam == False
and has_beta_teleop_kit is True
and has_nav_head_cam is False
):
return "d435-only", True, True, False
elif (
model == "RE2V0"
and tool == "tool_stretch_dex_wrist"
and has_beta_teleop_kit == False
and has_nav_head_cam == False
and has_beta_teleop_kit is False
and has_nav_head_cam is False
):
return "d435-only", False, False, False
elif (
model == "RE2V0"
and tool == "tool_stretch_dex_wrist"
and has_beta_teleop_kit == True
and has_nav_head_cam == False
and has_beta_teleop_kit is True
and has_nav_head_cam is False
):
return "d435-only", True, True, False
# Stretch 2+ (upgraded Stretch 2)
elif (
model == "RE2V0"
and tool == "eoa_wrist_dw3_tool_sg3"
and has_beta_teleop_kit == False
and has_nav_head_cam == True
and has_beta_teleop_kit is False
and has_nav_head_cam is True
):
return "both", False, False, True
elif (
model == "RE2V0"
and tool == "eoa_wrist_dw3_tool_nil"
and has_beta_teleop_kit == False
and has_nav_head_cam == True
and has_beta_teleop_kit is False
and has_nav_head_cam is True
):
return "both", False, False, True
# Stretch 3
elif (
model == "SE3"
and tool == "eoa_wrist_dw3_tool_sg3"
and has_beta_teleop_kit == False
and has_nav_head_cam == True
and has_beta_teleop_kit is False
and has_nav_head_cam is True
):
return "both", False, False, True
elif (
model == "SE3"
and tool == "eoa_wrist_dw3_tool_nil"
and has_beta_teleop_kit == False
and has_nav_head_cam == True
and has_beta_teleop_kit is False
and has_nav_head_cam is True
):
return "both", False, False, True

raise ValueError(
f"cannot find valid configuration for model={model}, tool={tool}, has_beta_teleop_kit={has_beta_teleop_kit}, has_nav_head_cam={has_nav_head_cam}"
f"cannot find valid configuration for model={model}, tool={tool}, "
f"has_beta_teleop_kit={has_beta_teleop_kit}, has_nav_head_cam={has_nav_head_cam}"
)


Expand All @@ -173,7 +170,6 @@ def generate_launch_description():
rosbridge_package = str(get_package_share_path("rosbridge_server"))
stretch_core_path = str(get_package_share_directory("stretch_core"))
stretch_navigation_path = str(get_package_share_directory("stretch_nav2"))
navigation_bringup_path = str(get_package_share_directory("nav2_bringup"))

_, robot_params = stretch_body.robot_params.RobotParams().get_params()
stretch_serial_no = robot_params["robot"]["serial_no"]
Expand Down Expand Up @@ -222,10 +218,6 @@ def generate_launch_description():
),
description="Full path to the ROS2 parameters file to use for all launched nodes",
)
dict_file_path = os.path.join(core_package, "config", "stretch_marker_dict.yaml")
depthimage_to_laserscan_config = os.path.join(
core_package, "config", "depthimage_to_laser_scan_params.yaml"
)

# Start collecting nodes to launch
ld = LaunchDescription(
Expand Down Expand Up @@ -277,7 +269,7 @@ def generate_launch_description():
)
)

if driver_navigation_cam == True:
if driver_navigation_cam is True:
# Beta Teleop Kit Navigation Camera
ld.add_action(
GroupAction(
Expand All @@ -297,7 +289,7 @@ def generate_launch_description():
)
)

if driver_nav_head_cam == True:
if driver_nav_head_cam is True:
# Nav Head Wide Angle Camera
ld.add_action(
GroupAction(
Expand All @@ -313,7 +305,7 @@ def generate_launch_description():
)
)

if driver_gripper_cam == True:
if driver_gripper_cam is True:
# Beta Teleop Kit Gripper Camera
ld.add_action(
GroupAction(
Expand All @@ -333,7 +325,7 @@ def generate_launch_description():
)
)

if driver_navigation_cam == False and driver_nav_head_cam == False:
if driver_navigation_cam is False and driver_nav_head_cam is False:
# Blank Navigation Camera Node
# Publish blank image if no navigation camera exists
ld.add_action(
Expand All @@ -352,7 +344,7 @@ def generate_launch_description():
)
)

if drivers_realsense == "d435-only" and driver_gripper_cam == False:
if drivers_realsense == "d435-only" and driver_gripper_cam is False:
# Blank Gripper Camera Node
# Publish blank image if there is no gripper camera exists
ld.add_action(
Expand Down
18 changes: 11 additions & 7 deletions nodes/configure_video_streams.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,20 +10,18 @@
import PyKDL
import rclpy
import ros2_numpy
import tf2_py as tf2
import tf2_ros
import yaml
from cv_bridge import CvBridge
from rclpy.duration import Duration
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node
from rclpy.qos import QoSProfile, ReliabilityPolicy
from rclpy.time import Time

# from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud
from sensor_msgs.msg import CameraInfo, CompressedImage, Image, JointState, PointCloud2
from sensor_msgs_py.point_cloud2 import create_cloud, read_points
from std_srvs.srv import SetBool
from visualization_msgs.msg import MarkerArray


class ConfigureVideoStreams(Node):
Expand Down Expand Up @@ -170,11 +168,17 @@ def pc_callback(self, msg, img):
Time(),
timeout=Duration(seconds=0.1),
)
except:
except (
tf2.ConnectivityException,
tf2.ExtrapolationException,
tf2.InvalidArgumentException,
tf2.LookupException,
tf2.TimeoutException,
tf2.TransformException,
) as error:
self.get_logger().warn(
"Could not find the transform between frames {} and {}".format(
"base_link", "camera_color_optical_frame"
)
"Could not find the transform between frames base_link and "
f"camera_color_optical_frame. Error: {error}"
)
return img

Expand Down
41 changes: 20 additions & 21 deletions nodes/gripper_camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
# my_image_publisher/my_image_publisher/publisher_node.py

import os
import threading

import cv2
import rclpy
Expand All @@ -22,26 +21,26 @@
UVC_VIDEO_INDEX = "/dev/hello-gripper-camera"
UVC_VIDEO_FORMAT = "MJPG" # MJPG YUYV

UVC_BRIGHTNESS = (
-40
) # brightness 0x00980900 (int) : min=-64 max=64 step=1 default=0 value=0
UVC_CONTRAST = (
40 # contrast 0x00980901 (int) : min=0 max=64 step=1 default=32 value=32
)
UVC_SATURATION = (
60 # saturation 0x00980902 (int) : min=0 max=128 step=1 default=90 value=90
)
UVC_HUE = 0 # hue 0x00980903 (int) : min=-40 max=40 step=1 default=0 value=0
UVC_GAMMA = (
80 # gamma 0x00980910 (int) : min=72 max=500 step=1 default=100 value=100
)
UVC_GAIN = 80 # gain 0x00980913 (int) : min=0 max=100 step=1 default=0 value=0
UVC_WB_TEMP = 4250 # white_balance_temperature 0x0098091a (int) : min=2800 max=6500 step=1 default=4600 value=4600 flags=inactive
UVC_SHARPNESS = (
100 # sharpness 0x0098091b (int) : min=0 max=6 step=1 default=3 value=3
)
UVC_BACKLIT_COMP = 1 # backlight_compensation 0x0098091c (int) : min=0 max=2 step=1 default=1 value=1
UVC_EXPOSURE_TIME = 157 # exposure_time_absolute 0x009a0902 (int) : min=1 max=5000 step=1 default=157 value=157 flags=inactive
# brightness 0x00980900 (int) : min=-64 max=64 step=1 default=0 value=0
UVC_BRIGHTNESS = -40
# contrast 0x00980901 (int) : min=0 max=64 step=1 default=32 value=32
UVC_CONTRAST = 40
# saturation 0x00980902 (int) : min=0 max=128 step=1 default=90 value=90
UVC_SATURATION = 60
# hue 0x00980903 (int) : min=-40 max=40 step=1 default=0 value=0
UVC_HUE = 0
# gamma 0x00980910 (int) : min=72 max=500 step=1 default=100 value=100
UVC_GAMMA = 80
# gain 0x00980913 (int) : min=0 max=100 step=1 default=0 value=0
UVC_GAIN = 80
# white_balance_temperature 0x0098091a (int) : min=2800 max=6500 step=1 default=4600 value=4600 flags=inactive
UVC_WB_TEMP = 4250
# sharpness 0x0098091b (int) : min=0 max=6 step=1 default=3 value=3
UVC_SHARPNESS = 100
# backlight_compensation 0x0098091c (int) : min=0 max=2 step=1 default=1 value=1
UVC_BACKLIT_COMP = 1
# exposure_time_absolute 0x009a0902 (int) : min=1 max=5000 step=1 default=157 value=157 flags=inactive
UVC_EXPOSURE_TIME = 157

# More UVC Video capture properties here:
# https://docs.opencv.org/3.4/d4/d15/group__videoio__flags__base.html
Expand Down
Loading

0 comments on commit 2402ff5

Please sign in to comment.