Skip to content

Commit

Permalink
Add video and audio queue size parameter to RosStreamBridge. (#85)
Browse files Browse the repository at this point in the history
* Add video and audio queue size parameter to RosStreamBridge.

* Update opentera-webrtc
  • Loading branch information
mamaheux authored Jul 26, 2024
1 parent 9414d7e commit 201c1e0
Show file tree
Hide file tree
Showing 6 changed files with 34 additions and 32 deletions.
28 changes: 3 additions & 25 deletions face_cropping/src/FaceCropper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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))
{
Expand All @@ -76,7 +54,7 @@ FaceCropperParameters FaceCropperParameters::fromFaceDetector(
parameters.heightScale = 1.75f;
parameters.frameBeforeChangeTarget = 10;

parameters.rPosition = 60.0f;
parameters.rPosition = 125.0f;
}
#endif
else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
6 changes: 5 additions & 1 deletion opentera_webrtc_ros/launch/ros_stream_client.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
<!-- Arguments -->
<arg name="name" default="topic_streamer"/>
<arg name="is_stand_alone" default="true"/>
<arg name="video_queue_size" default="1"/>
<arg name="audio_queue_size" default="1"/>

<!-- Video -->
<arg name="can_send_video_stream" default="false"/>
Expand Down Expand Up @@ -41,7 +43,9 @@
<arg name="output_webrtc_audio_topic" default="webrtc_audio"/>

<node name="$(var name)" pkg="opentera_webrtc_ros" exec="topic_streamer" respawn="true">
<param name="is_stand_alone" value="$(var is_stand_alone)" />
<param name="is_stand_alone" value="$(var is_stand_alone)"/>
<param name="video_queue_size" value="$(var video_queue_size)"/>
<param name="audio_queue_size" value="$(var audio_queue_size)"/>

<param name="video_stream">
<param name="can_send_video_stream" value="$(var can_send_video_stream)"/> <!-- Can send video stream to the signaling server -->
Expand Down
12 changes: 12 additions & 0 deletions opentera_webrtc_ros/src/RosNodeParameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
Expand Down Expand Up @@ -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
*
Expand Down
16 changes: 11 additions & 5 deletions opentera_webrtc_ros/src/RosStreamBridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,8 +121,12 @@ void RosStreamBridge::init(

if (m_canReceiveAudioStream)
{
m_audioPublisher = this->create_publisher<opentera_webrtc_ros_msgs::msg::PeerAudio>("webrtc_audio", 100);
m_mixedAudioPublisher = this->create_publisher<audio_utils_msgs::msg::AudioFrame>("audio_mixed", 100);
m_audioPublisher = this->create_publisher<opentera_webrtc_ros_msgs::msg::PeerAudio>(
"webrtc_audio",
m_nodeParameters.audioQueueSize());
m_mixedAudioPublisher = this->create_publisher<audio_utils_msgs::msg::AudioFrame>(
"audio_mixed",
m_nodeParameters.audioQueueSize());

m_signalingClient->setOnAudioFrameReceived(
[this](auto&& PH1, auto&& PH2, auto&& PH3, auto&& PH4, auto&& PH5, auto&& PH6)
Expand Down Expand Up @@ -150,7 +154,9 @@ void RosStreamBridge::init(

if (m_canReceiveVideoStream)
{
m_imagePublisher = this->create_publisher<opentera_webrtc_ros_msgs::msg::PeerImage>("webrtc_image", 10);
m_imagePublisher = this->create_publisher<opentera_webrtc_ros_msgs::msg::PeerImage>(
"webrtc_image",
m_nodeParameters.videoQueueSize());
// Video and audio frame
m_signalingClient->setOnVideoFrameReceived(
[this](auto&& PH1, auto&& PH2, auto&& PH3)
Expand Down Expand Up @@ -210,7 +216,7 @@ void RosStreamBridge::onSignalingConnectionOpened()
// Audio
m_audioSubscriber = this->create_subscription<audio_utils_msgs::msg::AudioFrame>(
"audio_in",
10,
m_nodeParameters.audioQueueSize(),
bind_this<audio_utils_msgs::msg::AudioFrame>(this, &RosStreamBridge::audioCallback));
}

Expand All @@ -219,7 +225,7 @@ void RosStreamBridge::onSignalingConnectionOpened()
// Video
m_imageSubscriber = this->create_subscription<sensor_msgs::msg::Image>(
"ros_image",
10,
m_nodeParameters.videoQueueSize(),
bind_this<sensor_msgs::msg::Image>(this, &RosStreamBridge::imageCallback));
}
}
Expand Down

0 comments on commit 201c1e0

Please sign in to comment.