From 4402b21a73ff33a137373117ef8a43aa1564554a Mon Sep 17 00:00:00 2001
From: Pim Hutting
Date: Sun, 9 Nov 2025 15:43:22 +0100
Subject: [PATCH 1/5] refactor: added config file and moved constants
- Moved hardcoded configuration constants to a dedicated config.py file.
- Created VideoConfig, AudioConfig, MainConfig, and Settings classes in config.py
ref: N25B-236
---
src/robot_interface/core/__init__.py | 0
src/robot_interface/core/config.py | 46 +++++++++++++++++++
.../endpoints/actuation_receiver.py | 4 +-
src/robot_interface/endpoints/audio_sender.py | 11 +++--
.../endpoints/main_receiver.py | 3 +-
src/robot_interface/endpoints/video_sender.py | 19 ++++----
src/robot_interface/main.py | 5 +-
src/robot_interface/utils/microphone.py | 7 +--
8 files changed, 74 insertions(+), 21 deletions(-)
create mode 100644 src/robot_interface/core/__init__.py
create mode 100644 src/robot_interface/core/config.py
diff --git a/src/robot_interface/core/__init__.py b/src/robot_interface/core/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/src/robot_interface/core/config.py b/src/robot_interface/core/config.py
new file mode 100644
index 0000000..e8489bd
--- /dev/null
+++ b/src/robot_interface/core/config.py
@@ -0,0 +1,46 @@
+
+from __future__ import unicode_literals
+
+import os
+
+class AgentSettings(object):
+ """Agent port configuration."""
+ def __init__(self, actuating_receiver_port=5557, main_receiver_port=5555,video_sender_port=5556, audio_sender_port=5558):
+ self.actuating_receiver_port = actuating_receiver_port
+ self.main_receiver_port = main_receiver_port
+ self.video_sender_port = video_sender_port
+ self.audio_sender_port = audio_sender_port
+
+class VideoConfig(object):
+ """Video configuration constants."""
+ def __init__(self, camera_index=0, resolution=2, color_space=11, fps=15, stream_name="Pepper Video", image_buffer=6):
+ self.camera_index = camera_index
+ self.resolution = resolution
+ self.color_space = color_space
+ self.fps = fps
+ self.stream_name = stream_name
+ self.image_buffer = image_buffer
+
+class AudioConfig(object):
+ """Audio configuration constants."""
+ def __init__(self, sample_rate=16000, chunk_size=512, channels=1):
+ self.sample_rate = sample_rate
+ self.chunk_size = chunk_size
+ self.channels = channels
+
+class MainConfig(object):
+ """Main configuration"""
+ def __init__(self, poll_timeout_ms=100, max_handler_time_ms=50):
+ self.poll_timeout_ms = poll_timeout_ms
+ self.max_handler_time_ms = max_handler_time_ms
+
+class Settings(object):
+ """Global settings container."""
+ def __init__(self, agent_settings=None, video_config=None, audio_config=None, main_config=None):
+ self.agent_settings = agent_settings or AgentSettings()
+ self.video_config = video_config or VideoConfig()
+ self.audio_config = audio_config or AudioConfig()
+ self.main_config = main_config or MainConfig()
+
+
+settings = Settings()
diff --git a/src/robot_interface/endpoints/actuation_receiver.py b/src/robot_interface/endpoints/actuation_receiver.py
index aa2511a..7fc6546 100644
--- a/src/robot_interface/endpoints/actuation_receiver.py
+++ b/src/robot_interface/endpoints/actuation_receiver.py
@@ -6,9 +6,11 @@ import zmq
from robot_interface.endpoints.receiver_base import ReceiverBase
from robot_interface.state import state
+from robot_interface.core.config import settings
+
class ActuationReceiver(ReceiverBase):
- def __init__(self, zmq_context, port=5557):
+ def __init__(self, zmq_context, port= settings.agent_settings.actuating_receiver_port):
"""
The actuation receiver endpoint, responsible for handling speech and gesture requests.
diff --git a/src/robot_interface/endpoints/audio_sender.py b/src/robot_interface/endpoints/audio_sender.py
index 7365816..2e1e45e 100644
--- a/src/robot_interface/endpoints/audio_sender.py
+++ b/src/robot_interface/endpoints/audio_sender.py
@@ -8,13 +8,13 @@ import zmq
from robot_interface.endpoints.socket_base import SocketBase
from robot_interface.state import state
from robot_interface.utils.microphone import choose_mic
-
+from robot_interface.core.config import settings
logger = logging.getLogger(__name__)
class AudioSender(SocketBase):
- def __init__(self, zmq_context, port=5558):
+ def __init__(self, zmq_context, port= settings.agent_settings.audio_sender_port):
super(AudioSender, self).__init__(str("audio")) # Convert future's unicode_literal to str
self.create_socket(zmq_context, zmq.PUB, port)
self.thread = None
@@ -49,13 +49,14 @@ class AudioSender(SocketBase):
self.thread = None
def _stream(self):
- chunk = 512 # 320 at 16000 Hz is 20ms, 512 is required for Silero-VAD
+ audio_settings = settings.audio_config
+ chunk = audio_settings.chunk_size # 320 at 16000 Hz is 20ms, 512 is required for Silero-VAD
# Docs say this only raises an error if neither `input` nor `output` is True
stream = self.audio.open(
format=pyaudio.paFloat32,
- channels=1,
- rate=16000,
+ channels=audio_settings.channels,
+ rate=audio_settings.sample_rate,
input=True,
input_device_index=self.microphone["index"],
frames_per_buffer=chunk,
diff --git a/src/robot_interface/endpoints/main_receiver.py b/src/robot_interface/endpoints/main_receiver.py
index 0ce9711..e5367c6 100644
--- a/src/robot_interface/endpoints/main_receiver.py
+++ b/src/robot_interface/endpoints/main_receiver.py
@@ -3,9 +3,10 @@ import zmq
from robot_interface.endpoints.receiver_base import ReceiverBase
from robot_interface.state import state
+from robot_interface.core.config import settings
class MainReceiver(ReceiverBase):
- def __init__(self, zmq_context, port=5555):
+ def __init__(self, zmq_context, port= settings.agent_settings.main_receiver_port):
"""
The main receiver endpoint, responsible for handling ping and negotiation requests.
diff --git a/src/robot_interface/endpoints/video_sender.py b/src/robot_interface/endpoints/video_sender.py
index 9e75447..1eacc3b 100644
--- a/src/robot_interface/endpoints/video_sender.py
+++ b/src/robot_interface/endpoints/video_sender.py
@@ -4,10 +4,10 @@ import logging
from robot_interface.endpoints.socket_base import SocketBase
from robot_interface.state import state
-
+from robot_interface.core.config import settings
class VideoSender(SocketBase):
- def __init__(self, zmq_context, port=5556):
+ def __init__(self, zmq_context, port=settings.agent_settings.video_sender_port):
super(VideoSender, self).__init__("video")
self.create_socket(zmq_context, zmq.PUB, port, [(zmq.CONFLATE,1)])
@@ -20,12 +20,13 @@ class VideoSender(SocketBase):
return
video = state.qi_session.service("ALVideoDevice")
-
- camera_index = 0
- kQVGA = 2
- kRGB = 11
- FPS = 15
- vid_stream_name = video.subscribeCamera("Pepper Video", camera_index, kQVGA, kRGB, FPS)
+ video_settings = settings.video_config
+ camera_index = video_settings.camera_index
+ kQVGA = video_settings.resolution
+ kRGB = video_settings.color_space
+ FPS = video_settings.fps
+ video_name = video_settings.stream_name
+ vid_stream_name = video.subscribeCamera(video_name, camera_index, kQVGA, kRGB, FPS)
thread = threading.Thread(target=self.video_rcv_loop, args=(video, vid_stream_name))
thread.start()
@@ -43,6 +44,6 @@ class VideoSender(SocketBase):
try:
img = vid_service.getImageRemote(vid_stream_name)
#Possibly limit images sent if queuing issues arise
- self.socket.send(img[6])
+ self.socket.send(img[settings.video_config.image_buffer])
except:
logging.warn("Failed to retrieve video image from robot.")
diff --git a/src/robot_interface/main.py b/src/robot_interface/main.py
index 8874f7d..5af10ce 100644
--- a/src/robot_interface/main.py
+++ b/src/robot_interface/main.py
@@ -10,6 +10,7 @@ from robot_interface.endpoints.actuation_receiver import ActuationReceiver
from robot_interface.endpoints.main_receiver import MainReceiver
from robot_interface.endpoints.video_sender import VideoSender
from robot_interface.state import state
+from robot_interface.core.config import settings
from robot_interface.utils.timeblock import TimeBlock
@@ -45,7 +46,7 @@ def main_loop(context):
while True:
if state.exit_event.is_set(): break
- socks = dict(poller.poll(100))
+ socks = dict(poller.poll(settings.main_config.poll_timeout_ms))
for receiver in receivers:
if receiver.socket not in socks: continue
@@ -59,7 +60,7 @@ def main_loop(context):
logging.warn("Endpoint \"%s\" took too long (%.2f ms) on the main thread.",
message["endpoint"], time_ms)
- with TimeBlock(overtime_callback, 50):
+ with TimeBlock(overtime_callback, settings.main_config.max_handler_time_ms):
response = receiver.handle_message(message)
if receiver.socket.getsockopt(zmq.TYPE) == zmq.REP:
diff --git a/src/robot_interface/utils/microphone.py b/src/robot_interface/utils/microphone.py
index 877ca3f..2ec4bd4 100644
--- a/src/robot_interface/utils/microphone.py
+++ b/src/robot_interface/utils/microphone.py
@@ -82,11 +82,12 @@ def choose_mic_arguments(audio):
:rtype: dict | None
"""
microphone_name = None
+ microhopone_prefix = "--microphone="
for i, arg in enumerate(sys.argv):
- if arg == "--microphone" and len(sys.argv) > i+1:
+ if arg == microhopone_prefix and len(sys.argv) > i+1:
microphone_name = sys.argv[i+1].strip()
- if arg.startswith("--microphone="):
- microphone_name = arg[13:].strip()
+ if arg.startswith(microhopone_prefix):
+ microphone_name = arg[len(microhopone_prefix):].strip()
if not microphone_name: return None
From 643d7b919c6dfd1c15068f90ed715893106ddbc4 Mon Sep 17 00:00:00 2001
From: Pim Hutting
Date: Sun, 9 Nov 2025 16:00:36 +0100
Subject: [PATCH 2/5] fix: made all tests pass
before some tests failed because of a faulty edit
to microphone util
ref: N25B-236
---
src/robot_interface/utils/microphone.py | 8 ++++----
1 file changed, 4 insertions(+), 4 deletions(-)
diff --git a/src/robot_interface/utils/microphone.py b/src/robot_interface/utils/microphone.py
index 2ec4bd4..3bf9fe6 100644
--- a/src/robot_interface/utils/microphone.py
+++ b/src/robot_interface/utils/microphone.py
@@ -82,12 +82,12 @@ def choose_mic_arguments(audio):
:rtype: dict | None
"""
microphone_name = None
- microhopone_prefix = "--microphone="
for i, arg in enumerate(sys.argv):
- if arg == microhopone_prefix and len(sys.argv) > i+1:
+ if arg == "--microphone" and len(sys.argv) > i+1:
microphone_name = sys.argv[i+1].strip()
- if arg.startswith(microhopone_prefix):
- microphone_name = arg[len(microhopone_prefix):].strip()
+ if arg.startswith("--microphone="):
+ pre_fix_len = len("--microphone=")
+ microphone_name = arg[pre_fix_len:].strip()
if not microphone_name: return None
From 03519e2a1604c3d904834e51fded14aa84763f1d Mon Sep 17 00:00:00 2001
From: Twirre Meulenbelt <43213592+TwirreM@users.noreply.github.com>
Date: Fri, 14 Nov 2025 13:08:31 +0100
Subject: [PATCH 3/5] test: fix microphone interactive test
This was created with the assumption that all devices were choosable, but now only ones with input channels are.
ref: N25B-119
---
test/common/microphone_utils.py | 10 ++++++++--
1 file changed, 8 insertions(+), 2 deletions(-)
diff --git a/test/common/microphone_utils.py b/test/common/microphone_utils.py
index c82de37..74bd777 100644
--- a/test/common/microphone_utils.py
+++ b/test/common/microphone_utils.py
@@ -41,6 +41,9 @@ class MicrophoneUtils(object):
"""
First mock an input that's not an integer, then a valid integer. There should be no errors.
"""
+ microphones = get_microphones(pyaudio_instance)
+ target_microphone = next(microphones)
+
mock_input = mocker.patch("__builtin__.raw_input", side_effect=["not an integer", "0"])
fake_out = StringIO()
mocker.patch.object(sys, "stdout", fake_out)
@@ -48,7 +51,7 @@ class MicrophoneUtils(object):
result = choose_mic_interactive(pyaudio_instance)
assert "index" in result
assert isinstance(result["index"], (int, long))
- assert result["index"] == 0
+ assert result["index"] == target_microphone["index"]
assert mock_input.called
@@ -58,6 +61,9 @@ class MicrophoneUtils(object):
"""
Make sure that the interactive method does not allow negative integers as input.
"""
+ microphones = get_microphones(pyaudio_instance)
+ target_microphone = next(microphones)
+
mock_input = mocker.patch("__builtin__.raw_input", side_effect=["-1", "0"])
fake_out = StringIO()
mocker.patch.object(sys, "stdout", fake_out)
@@ -65,7 +71,7 @@ class MicrophoneUtils(object):
result = choose_mic_interactive(pyaudio_instance)
assert "index" in result
assert isinstance(result["index"], (int, long))
- assert result["index"] == 0
+ assert result["index"] == target_microphone["index"]
assert mock_input.called
From 16b64e41c86ac141c7c17e0239893f62ea92ba1c Mon Sep 17 00:00:00 2001
From: Pim Hutting
Date: Fri, 14 Nov 2025 14:12:14 +0000
Subject: [PATCH 4/5] style: applied style suggestions
close: N25B-236
---
src/robot_interface/core/config.py | 24 ++++++++++++-------
.../endpoints/actuation_receiver.py | 2 +-
src/robot_interface/endpoints/audio_sender.py | 2 +-
.../endpoints/main_receiver.py | 2 +-
4 files changed, 19 insertions(+), 11 deletions(-)
diff --git a/src/robot_interface/core/config.py b/src/robot_interface/core/config.py
index e8489bd..780f4d2 100644
--- a/src/robot_interface/core/config.py
+++ b/src/robot_interface/core/config.py
@@ -1,39 +1,47 @@
-
from __future__ import unicode_literals
-import os
class AgentSettings(object):
"""Agent port configuration."""
- def __init__(self, actuating_receiver_port=5557, main_receiver_port=5555,video_sender_port=5556, audio_sender_port=5558):
+ def __init__(
+ self,
+ actuating_receiver_port=5557,
+ main_receiver_port=5555,
+ video_sender_port=5556,
+ audio_sender_port=5558,
+ ):
self.actuating_receiver_port = actuating_receiver_port
self.main_receiver_port = main_receiver_port
self.video_sender_port = video_sender_port
self.audio_sender_port = audio_sender_port
-
class VideoConfig(object):
"""Video configuration constants."""
- def __init__(self, camera_index=0, resolution=2, color_space=11, fps=15, stream_name="Pepper Video", image_buffer=6):
+ def __init__(
+ self,
+ camera_index=0,
+ resolution=2,
+ color_space=11,
+ fps=15,
+ stream_name="Pepper Video",
+ image_buffer=6,
+ ):
self.camera_index = camera_index
self.resolution = resolution
self.color_space = color_space
self.fps = fps
self.stream_name = stream_name
self.image_buffer = image_buffer
-
class AudioConfig(object):
"""Audio configuration constants."""
def __init__(self, sample_rate=16000, chunk_size=512, channels=1):
self.sample_rate = sample_rate
self.chunk_size = chunk_size
self.channels = channels
-
class MainConfig(object):
"""Main configuration"""
def __init__(self, poll_timeout_ms=100, max_handler_time_ms=50):
self.poll_timeout_ms = poll_timeout_ms
self.max_handler_time_ms = max_handler_time_ms
-
class Settings(object):
"""Global settings container."""
def __init__(self, agent_settings=None, video_config=None, audio_config=None, main_config=None):
diff --git a/src/robot_interface/endpoints/actuation_receiver.py b/src/robot_interface/endpoints/actuation_receiver.py
index 7fc6546..c5e8ab3 100644
--- a/src/robot_interface/endpoints/actuation_receiver.py
+++ b/src/robot_interface/endpoints/actuation_receiver.py
@@ -10,7 +10,7 @@ from robot_interface.core.config import settings
class ActuationReceiver(ReceiverBase):
- def __init__(self, zmq_context, port= settings.agent_settings.actuating_receiver_port):
+ def __init__(self, zmq_context, port=settings.agent_settings.actuating_receiver_port):
"""
The actuation receiver endpoint, responsible for handling speech and gesture requests.
diff --git a/src/robot_interface/endpoints/audio_sender.py b/src/robot_interface/endpoints/audio_sender.py
index 2e1e45e..e6de258 100644
--- a/src/robot_interface/endpoints/audio_sender.py
+++ b/src/robot_interface/endpoints/audio_sender.py
@@ -14,7 +14,7 @@ logger = logging.getLogger(__name__)
class AudioSender(SocketBase):
- def __init__(self, zmq_context, port= settings.agent_settings.audio_sender_port):
+ def __init__(self, zmq_context, port=settings.agent_settings.audio_sender_port):
super(AudioSender, self).__init__(str("audio")) # Convert future's unicode_literal to str
self.create_socket(zmq_context, zmq.PUB, port)
self.thread = None
diff --git a/src/robot_interface/endpoints/main_receiver.py b/src/robot_interface/endpoints/main_receiver.py
index e5367c6..b0adf24 100644
--- a/src/robot_interface/endpoints/main_receiver.py
+++ b/src/robot_interface/endpoints/main_receiver.py
@@ -6,7 +6,7 @@ from robot_interface.state import state
from robot_interface.core.config import settings
class MainReceiver(ReceiverBase):
- def __init__(self, zmq_context, port= settings.agent_settings.main_receiver_port):
+ def __init__(self, zmq_context, port=settings.agent_settings.main_receiver_port):
"""
The main receiver endpoint, responsible for handling ping and negotiation requests.
From c691e279cde7a8b1633f1025ce5bd804c9bcab6d Mon Sep 17 00:00:00 2001
From: Twirre Meulenbelt <43213592+TwirreM@users.noreply.github.com>
Date: Fri, 14 Nov 2025 15:13:48 +0100
Subject: [PATCH 5/5] style: two lines between top level declarations
ref: N25B-236
---
src/robot_interface/core/config.py | 8 ++++++++
1 file changed, 8 insertions(+)
diff --git a/src/robot_interface/core/config.py b/src/robot_interface/core/config.py
index 780f4d2..f5295b2 100644
--- a/src/robot_interface/core/config.py
+++ b/src/robot_interface/core/config.py
@@ -14,6 +14,8 @@ class AgentSettings(object):
self.main_receiver_port = main_receiver_port
self.video_sender_port = video_sender_port
self.audio_sender_port = audio_sender_port
+
+
class VideoConfig(object):
"""Video configuration constants."""
def __init__(
@@ -31,17 +33,23 @@ class VideoConfig(object):
self.fps = fps
self.stream_name = stream_name
self.image_buffer = image_buffer
+
+
class AudioConfig(object):
"""Audio configuration constants."""
def __init__(self, sample_rate=16000, chunk_size=512, channels=1):
self.sample_rate = sample_rate
self.chunk_size = chunk_size
self.channels = channels
+
+
class MainConfig(object):
"""Main configuration"""
def __init__(self, poll_timeout_ms=100, max_handler_time_ms=50):
self.poll_timeout_ms = poll_timeout_ms
self.max_handler_time_ms = max_handler_time_ms
+
+
class Settings(object):
"""Global settings container."""
def __init__(self, agent_settings=None, video_config=None, audio_config=None, main_config=None):