From 201c1e0af91f49ea4a2698b4729d7d81d7d2a31a Mon Sep 17 00:00:00 2001
From: Marc-Antoine Maheux <35638081+mamaheux@users.noreply.github.com>
Date: Fri, 26 Jul 2024 14:03:48 -0400
Subject: [PATCH] Add video and audio queue size parameter to RosStreamBridge.
(#85)
* Add video and audio queue size parameter to RosStreamBridge.
* Update opentera-webrtc
---
face_cropping/src/FaceCropper.cpp | 28 ++-----------------
.../opentera_webrtc_ros/RosNodeParameters.h | 2 ++
.../launch/ros_stream_client.launch.xml | 6 +++-
opentera_webrtc_ros/opentera-webrtc | 2 +-
opentera_webrtc_ros/src/RosNodeParameters.cpp | 12 ++++++++
opentera_webrtc_ros/src/RosStreamBridge.cpp | 16 +++++++----
6 files changed, 34 insertions(+), 32 deletions(-)
diff --git a/face_cropping/src/FaceCropper.cpp b/face_cropping/src/FaceCropper.cpp
index fa5e695..ace1ec4 100644
--- a/face_cropping/src/FaceCropper.cpp
+++ b/face_cropping/src/FaceCropper.cpp
@@ -41,31 +41,9 @@ FaceCropperParameters FaceCropperParameters::fromFaceDetector(
#ifndef NO_TORCH
else if (
faceDetector.type() == typeid(SmallYunet025Silu160FaceDetector) ||
- faceDetector.type() == typeid(SmallYunet05Silu160FaceDetector))
- {
- parameters.detectionInterval = 2;
- parameters.xOffsetRatio = 0.f;
- parameters.yOffsetRatio = 0.f;
- parameters.widthScale = 1.25f;
- parameters.heightScale = 1.5f;
- parameters.frameBeforeChangeTarget = 10;
-
- parameters.rPosition = 100.0f;
- }
- else if (
+ faceDetector.type() == typeid(SmallYunet05Silu160FaceDetector) ||
faceDetector.type() == typeid(SmallYunet025Silu320FaceDetector) ||
- faceDetector.type() == typeid(SmallYunet05Silu320FaceDetector))
- {
- parameters.detectionInterval = 2;
- parameters.xOffsetRatio = 0.f;
- parameters.yOffsetRatio = 0.f;
- parameters.widthScale = 1.5f;
- parameters.heightScale = 1.75f;
- parameters.frameBeforeChangeTarget = 10;
-
- parameters.rPosition = 80.0f;
- }
- else if (
+ faceDetector.type() == typeid(SmallYunet05Silu320FaceDetector) ||
faceDetector.type() == typeid(SmallYunet025Silu640FaceDetector) ||
faceDetector.type() == typeid(SmallYunet05Silu640FaceDetector))
{
@@ -76,7 +54,7 @@ FaceCropperParameters FaceCropperParameters::fromFaceDetector(
parameters.heightScale = 1.75f;
parameters.frameBeforeChangeTarget = 10;
- parameters.rPosition = 60.0f;
+ parameters.rPosition = 125.0f;
}
#endif
else
diff --git a/opentera_webrtc_ros/include/opentera_webrtc_ros/RosNodeParameters.h b/opentera_webrtc_ros/include/opentera_webrtc_ros/RosNodeParameters.h
index ae5fde3..b79fc11 100644
--- a/opentera_webrtc_ros/include/opentera_webrtc_ros/RosNodeParameters.h
+++ b/opentera_webrtc_ros/include/opentera_webrtc_ros/RosNodeParameters.h
@@ -18,6 +18,8 @@ namespace opentera
RosNodeParameters(rclcpp::Node& node);
bool isStandAlone() const;
+ size_t videoQueueSize() const;
+ size_t audioQueueSize() const;
void loadSignalingParams(std::string& clientName, std::string& room) const;
void loadSignalingParams(
diff --git a/opentera_webrtc_ros/launch/ros_stream_client.launch.xml b/opentera_webrtc_ros/launch/ros_stream_client.launch.xml
index 0049a88..ae40985 100644
--- a/opentera_webrtc_ros/launch/ros_stream_client.launch.xml
+++ b/opentera_webrtc_ros/launch/ros_stream_client.launch.xml
@@ -3,6 +3,8 @@
+
+
@@ -41,7 +43,9 @@
-
+
+
+
diff --git a/opentera_webrtc_ros/opentera-webrtc b/opentera_webrtc_ros/opentera-webrtc
index 9a296d6..b90291b 160000
--- a/opentera_webrtc_ros/opentera-webrtc
+++ b/opentera_webrtc_ros/opentera-webrtc
@@ -1 +1 @@
-Subproject commit 9a296d626f6f9e8baa2a04963895f9794bbb9433
+Subproject commit b90291b143fb5f4a912164d98f38144017ade9f2
diff --git a/opentera_webrtc_ros/src/RosNodeParameters.cpp b/opentera_webrtc_ros/src/RosNodeParameters.cpp
index e78d3c3..74923da 100644
--- a/opentera_webrtc_ros/src/RosNodeParameters.cpp
+++ b/opentera_webrtc_ros/src/RosNodeParameters.cpp
@@ -23,6 +23,8 @@ namespace
RosNodeParameters::RosNodeParameters(rclcpp::Node& node) : m_node{node}
{
m_node.declare_parameter("is_stand_alone", true);
+ m_node.declare_parameter("video_queue_size", 1);
+ m_node.declare_parameter("audio_queue_size", 1);
// Signaling params
m_node.declare_parameter("signaling.client_name", "streamer");
@@ -59,6 +61,16 @@ bool RosNodeParameters::isStandAlone() const
return m_node.get_parameter("is_stand_alone").as_bool();
}
+size_t RosNodeParameters::videoQueueSize() const
+{
+ return m_node.get_parameter("video_queue_size").as_int();
+}
+
+size_t RosNodeParameters::audioQueueSize() const
+{
+ return m_node.get_parameter("audio_queue_size").as_int();
+}
+
/**
* @brief Load signaling parameters from ROS parameter server
*
diff --git a/opentera_webrtc_ros/src/RosStreamBridge.cpp b/opentera_webrtc_ros/src/RosStreamBridge.cpp
index 353d668..9abfca7 100644
--- a/opentera_webrtc_ros/src/RosStreamBridge.cpp
+++ b/opentera_webrtc_ros/src/RosStreamBridge.cpp
@@ -121,8 +121,12 @@ void RosStreamBridge::init(
if (m_canReceiveAudioStream)
{
- m_audioPublisher = this->create_publisher("webrtc_audio", 100);
- m_mixedAudioPublisher = this->create_publisher("audio_mixed", 100);
+ m_audioPublisher = this->create_publisher(
+ "webrtc_audio",
+ m_nodeParameters.audioQueueSize());
+ m_mixedAudioPublisher = this->create_publisher(
+ "audio_mixed",
+ m_nodeParameters.audioQueueSize());
m_signalingClient->setOnAudioFrameReceived(
[this](auto&& PH1, auto&& PH2, auto&& PH3, auto&& PH4, auto&& PH5, auto&& PH6)
@@ -150,7 +154,9 @@ void RosStreamBridge::init(
if (m_canReceiveVideoStream)
{
- m_imagePublisher = this->create_publisher("webrtc_image", 10);
+ m_imagePublisher = this->create_publisher(
+ "webrtc_image",
+ m_nodeParameters.videoQueueSize());
// Video and audio frame
m_signalingClient->setOnVideoFrameReceived(
[this](auto&& PH1, auto&& PH2, auto&& PH3)
@@ -210,7 +216,7 @@ void RosStreamBridge::onSignalingConnectionOpened()
// Audio
m_audioSubscriber = this->create_subscription(
"audio_in",
- 10,
+ m_nodeParameters.audioQueueSize(),
bind_this(this, &RosStreamBridge::audioCallback));
}
@@ -219,7 +225,7 @@ void RosStreamBridge::onSignalingConnectionOpened()
// Video
m_imageSubscriber = this->create_subscription(
"ros_image",
- 10,
+ m_nodeParameters.videoQueueSize(),
bind_this(this, &RosStreamBridge::imageCallback));
}
}