Address Jess comments

This commit is contained in:
Remi Cadene
2024-09-28 13:11:17 +02:00
parent 1de04e4756
commit 5c73bec913
7 changed files with 23 additions and 27 deletions

View File

@@ -33,7 +33,7 @@ def find_camera_indices(raise_when_empty=True, mock=False) -> list[int]:
connected to the computer.
"""
if mock:
from tests.mock_intelrealsense import (
from tests.mock_pyrealsense2 import (
RSCameraInfo,
RSContext,
)
@@ -82,7 +82,7 @@ def save_images_from_cameras(
camera_ids = find_camera_indices(mock=mock)
if mock:
from tests.mock_opencv import COLOR_RGB2BGR, cvtColor
from tests.mock_cv2 import COLOR_RGB2BGR, cvtColor
else:
from cv2 import COLOR_RGB2BGR, cvtColor
@@ -263,7 +263,7 @@ class IntelRealSenseCamera:
)
if self.mock:
from tests.mock_intelrealsense import (
from tests.mock_pyrealsense2 import (
RSConfig,
RSFormat,
RSPipeline,
@@ -373,7 +373,7 @@ class IntelRealSenseCamera:
# IntelRealSense uses RGB format as default (red, green, blue).
if requested_color_mode == "bgr":
if self.mock:
from tests.mock_opencv import COLOR_RGB2BGR, cvtColor
from tests.mock_cv2 import COLOR_RGB2BGR, cvtColor
else:
from cv2 import COLOR_RGB2BGR, cvtColor
@@ -430,6 +430,7 @@ class IntelRealSenseCamera:
num_tries = 0
while self.color_image is None:
# TODO(rcadene, aliberts): intelrealsense has diverged compared to opencv over here
num_tries += 1
time.sleep(1 / self.fps)
if num_tries > self.fps and (self.thread.ident is None or not self.thread.is_alive()):

View File

@@ -47,7 +47,7 @@ def find_camera_indices(raise_when_empty=False, max_index_search_range=MAX_OPENC
possible_camera_ids = range(max_index_search_range)
if mock:
from tests.mock_opencv import VideoCapture
from tests.mock_cv2 import VideoCapture
else:
from cv2 import VideoCapture
@@ -244,24 +244,24 @@ class OpenCVCamera:
raise RobotDeviceAlreadyConnectedError(f"OpenCVCamera({self.camera_index}) is already connected.")
if self.mock:
from tests.mock_opencv import (
from tests.mock_cv2 import (
CAP_PROP_FPS,
CAP_PROP_FRAME_HEIGHT,
CAP_PROP_FRAME_WIDTH,
VideoCapture,
)
else:
import cv2
from cv2 import (
CAP_PROP_FPS,
CAP_PROP_FRAME_HEIGHT,
CAP_PROP_FRAME_WIDTH,
VideoCapture,
setNumThreads,
)
# Use 1 thread to avoid blocking the main thread. Especially useful during data collection
# when other threads are used to save the images.
cv2.setNumThreads(1)
setNumThreads(1)
camera_idx = f"/dev/video{self.camera_index}" if platform.system() == "Linux" else self.camera_index
with self.lock:
@@ -356,7 +356,7 @@ class OpenCVCamera:
# so we convert the image color from BGR to RGB.
if requested_color_mode == "rgb":
if self.mock:
from tests.mock_opencv import COLOR_BGR2RGB, cvtColor
from tests.mock_cv2 import COLOR_BGR2RGB, cvtColor
else:
from cv2 import COLOR_BGR2RGB, cvtColor
@@ -409,10 +409,6 @@ class OpenCVCamera:
num_tries += 1
if num_tries > self.fps * 2:
raise TimeoutError("Timed out waiting for async_read() to start.")
# if num_tries > self.fps and (self.thread.ident is None or not self.thread.is_alive()):
# raise Exception(
# "The thread responsible for `self.async_read()` took too much time to start. There might be an issue. Verify that `self.thread.start()` has been called."
# )
def disconnect(self):
if not self.is_connected:

View File

@@ -143,8 +143,6 @@ MODEL_BAUDRATE_TABLE = {
NUM_READ_RETRY = 10
NUM_WRITE_RETRY = 10
COMM_SUCCESS = 0
def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str]) -> np.ndarray:
"""This function converts the degree range to the step range for indicating motors rotation.
@@ -363,7 +361,7 @@ class DynamixelMotorsBus:
)
if self.mock:
from tests.mock_dynamixel import PacketHandler, PortHandler
from tests.mock_dynamixel_sdk import PacketHandler, PortHandler
else:
from dynamixel_sdk import PacketHandler, PortHandler
@@ -401,7 +399,7 @@ class DynamixelMotorsBus:
def reconnect(self):
if self.mock:
from tests.mock_dynamixel import PacketHandler, PortHandler
from tests.mock_dynamixel_sdk import PacketHandler, PortHandler
else:
from dynamixel_sdk import PacketHandler, PortHandler
@@ -797,9 +795,9 @@ class DynamixelMotorsBus:
def _read_with_motor_ids(self, motor_models, motor_ids, data_name):
if self.mock:
from tests.mock_dynamixel import GroupSyncRead
from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncRead
else:
from dynamixel_sdk import GroupSyncRead
from dynamixel_sdk import COMM_SUCCESS, GroupSyncRead
return_list = True
if not isinstance(motor_ids, list):
@@ -838,9 +836,9 @@ class DynamixelMotorsBus:
start_time = time.perf_counter()
if self.mock:
from tests.mock_dynamixel import GroupSyncRead
from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncRead
else:
from dynamixel_sdk import GroupSyncRead
from dynamixel_sdk import COMM_SUCCESS, GroupSyncRead
if motor_names is None:
motor_names = self.motor_names
@@ -902,9 +900,9 @@ class DynamixelMotorsBus:
def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values):
if self.mock:
from tests.mock_dynamixel import GroupSyncWrite
from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite
else:
from dynamixel_sdk import GroupSyncWrite
from dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite
if not isinstance(motor_ids, list):
motor_ids = [motor_ids]
@@ -934,9 +932,9 @@ class DynamixelMotorsBus:
start_time = time.perf_counter()
if self.mock:
from tests.mock_dynamixel import GroupSyncWrite
from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite
else:
from dynamixel_sdk import GroupSyncWrite
from dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite
if motor_names is None:
motor_names = self.motor_names

View File

@@ -204,7 +204,7 @@ def require_robot(func):
@wraps(func)
def wrapper(*args, **kwargs):
# Access the pytest request context to get the mockeypatch fixture
# Access the pytest request context to get the is_robot_available fixture
request = kwargs.get("request")
robot_type = kwargs.get("robot_type")
mock = kwargs.get("mock")
@@ -228,6 +228,7 @@ def require_robot(func):
def require_camera(func):
@wraps(func)
def wrapper(*args, **kwargs):
# Access the pytest request context to get the is_camera_available fixture
request = kwargs.get("request")
camera_type = kwargs.get("camera_type")
mock = kwargs.get("mock")
@@ -250,7 +251,7 @@ def require_camera(func):
def require_motor(func):
@wraps(func)
def wrapper(*args, **kwargs):
# Access the pytest request context to get the mockeypatch fixture
# Access the pytest request context to get the is_motor_available fixture
request = kwargs.get("request")
motor_type = kwargs.get("motor_type")
mock = kwargs.get("mock")