Skip to content

Commit

Permalink
Merge pull request #255 from stereolabs/test_ffmpeg
Browse files Browse the repository at this point in the history
Test ffmpeg
  • Loading branch information
Myzhar authored Sep 23, 2024
2 parents baad42b + 3756d70 commit b1b9b1c
Show file tree
Hide file tree
Showing 10 changed files with 53 additions and 12 deletions.
5 changes: 5 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
LATEST CHANGES
==============

2024-09-23
----------
- Add support for FFMPEG image transport
- Add new `ffmpeg.yaml` configuration file

2024-07-31
----------
- Add support for point cloud transport
Expand Down
2 changes: 1 addition & 1 deletion zed-ros2-interfaces
4 changes: 2 additions & 2 deletions zed_components/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(zed_components)

################################################
Expand Down Expand Up @@ -96,7 +96,7 @@ set(DEPENDENCIES
tf2
tf2_ros
tf2_geometry_msgs
geometry_msgs
geometry_msgs
nav_msgs
nmea_msgs
geographic_msgs
Expand Down
1 change: 1 addition & 0 deletions zed_components/src/zed_camera/include/sl_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ typedef std::unique_ptr<sensor_msgs::msg::MagneticField> magMsgPtr;
typedef std::unique_ptr<stereo_msgs::msg::DisparityImage> dispMsgPtr;

typedef std::unique_ptr<geometry_msgs::msg::PoseStamped> poseMsgPtr;

typedef std::unique_ptr<zed_interfaces::msg::PosTrackStatus> poseStatusMsgPtr;
typedef std::unique_ptr<zed_interfaces::msg::GnssFusionStatus> gnssFusionStatusMsgPtr;
typedef std::unique_ptr<geometry_msgs::msg::PoseWithCovarianceStamped>
Expand Down
14 changes: 7 additions & 7 deletions zed_components/src/zed_camera/src/zed_camera_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1625,7 +1625,7 @@ void ZedCamera::getOdParams()
bool matched = false;
for (int idx =
static_cast<int>(sl::OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX_FAST);
idx < static_cast<int>(sl::OBJECT_DETECTION_MODEL::CUSTOM_BOX_OBJECTS);
idx < static_cast<int>(sl::OBJECT_DETECTION_MODEL::LAST);
idx++)
{
sl::OBJECT_DETECTION_MODEL test_model =
Expand Down Expand Up @@ -3592,9 +3592,9 @@ void ZedCamera::initPublishers()
<< mPubDisparity->get_topic_name());
#ifndef FOUND_FOXY
mPubCloud = point_cloud_transport::create_publisher(
this->shared_from_this(),
this->shared_from_this(),
pointcloud_topic, mQos.get_rmw_qos_profile(), mPubOpt);
RCLCPP_INFO_STREAM(
RCLCPP_INFO_STREAM(
get_logger(),
"Advertised on topic: " << mPubCloud.getTopic());
#else
Expand All @@ -3603,7 +3603,7 @@ void ZedCamera::initPublishers()
RCLCPP_INFO_STREAM(
get_logger(),
"Advertised on topic: " << mPubCloud->get_topic_name());
#endif
#endif
// <---- Depth publishers

// ----> Pos Tracking
Expand Down Expand Up @@ -3681,7 +3681,7 @@ void ZedCamera::initPublishers()
if (mMappingEnabled) {
#ifndef FOUND_FOXY
mPubFusedCloud = point_cloud_transport::create_publisher(
this->shared_from_this(), mPointcloudFusedTopic, mQos.get_rmw_qos_profile());
this->shared_from_this(), mPointcloudFusedTopic, mQos.get_rmw_qos_profile(), mPubOpt);
RCLCPP_INFO_STREAM(
get_logger(), "Advertised on topic "
<< mPubFusedCloud.getTopic()
Expand Down Expand Up @@ -5027,7 +5027,7 @@ bool ZedCamera::start3dMapping()
#ifndef FOUND_FOXY
mPubFusedCloud = point_cloud_transport::create_publisher(
this->shared_from_this(), mPointcloudFusedTopic,
mQos.get_rmw_qos_profile());
mQos.get_rmw_qos_profile(), mPubOpt);
RCLCPP_INFO_STREAM(
get_logger(), "Advertised on topic "
<< mPubFusedCloud.getTopic()
Expand Down Expand Up @@ -5170,7 +5170,7 @@ bool ZedCamera::startObjDetect()
mObjectDetTopic, mQos, mPubOpt);
RCLCPP_INFO_STREAM(
get_logger(),
"Advertised on topic " << mPubObjDet->get_topic_name());
" * Advertised on topic " << mPubObjDet->get_topic_name());
}

mObjDetRunning = true;
Expand Down
2 changes: 1 addition & 1 deletion zed_ros2/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(zed_ros2 NONE)

## Generate symbols for IDE indexer
Expand Down
2 changes: 1 addition & 1 deletion zed_wrapper/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)
project(zed_wrapper)

## Generate symbols for IDE indexer
Expand Down
20 changes: 20 additions & 0 deletions zed_wrapper/config/ffmpeg.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# config/ffmpeg.yaml
# Parameters to setup FFMPEG encoding in image_transport

# Full parameter documentation: https://github.com/ros-misc-utilities/ffmpeg_image_transport/blob/master/README.md

---
/**:
ros__parameters:
ffmpeg_image_transport:
bit_rate: 4194304 # Default: 8242880
delay: '0' # default is 4 frames for parallel processing. 0 is lowest latency
encoding: 'hevc_nvenc' # Only ever tested: libx264, h264_nvenc, h264, hevc_nvenc, h264_vaapi. If you have an Nvidia card it most likely supports hevc_nvenc. This will dramatically reduce the CPU load compare to libx264 (the default). You can list all available codecs with ffmpeg -codecs. In the relevant row, look for what it says under (encoders).
gop_size: 10 # The number of frames inbetween keyframes. Default is 15. The larger this number the more latency you will have, but also the more efficient the transmission becomes.
measure_performance: false # Enable performance analysis
performance_interval: 100 # number of frames between perf printouts
pixel_format: ''
preset: '' # 'll','ultrafast','superfast','veryfast','faster','fast','medium','slow','slower','veryslow' -> https://trac.ffmpeg.org/wiki/Encode/H.264#Preset
profile: '' # 'baseline','main' -> https://trac.ffmpeg.org/wiki/Encode/H.264#Tune
qmax: 0 # max allowed quantization. The lower the better quality
tune: '' # 'film','animation','grain','stillimage','fastdecode','zerolatency'
13 changes: 13 additions & 0 deletions zed_wrapper/launch/zed_camera.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,13 @@
'common.yaml'
)

# FFMPEG Configuration to be loaded by ZED Node
default_config_ffmpeg = os.path.join(
get_package_share_directory('zed_wrapper'),
'config',
'ffmpeg.yaml'
)

# URDF/xacro file to be loaded by the Robot State Publisher node
default_xacro_path = os.path.join(
get_package_share_directory('zed_wrapper'),
Expand Down Expand Up @@ -75,6 +82,7 @@ def launch_setup(context, *args, **kwargs):
node_name = LaunchConfiguration('node_name')

config_common_path = LaunchConfiguration('config_path')
config_ffmpeg = LaunchConfiguration('ffmpeg_config_path')

serial_number = LaunchConfiguration('serial_number')

Expand Down Expand Up @@ -157,6 +165,7 @@ def launch_setup(context, *args, **kwargs):
# YAML files
config_common_path, # Common parameters
config_camera_path, # Camera related parameters
config_ffmpeg, # FFMPEG parameters
# Overriding
{
'use_sim_time': use_sim_time,
Expand Down Expand Up @@ -218,6 +227,10 @@ def generate_launch_description():
'config_path',
default_value=TextSubstitution(text=default_config_common),
description='Path to the YAML configuration file for the camera.'),
DeclareLaunchArgument(
'ffmpeg_config_path',
default_value=TextSubstitution(text=default_config_ffmpeg),
description='Path to the YAML configuration file for the FFMPEG parameters when using FFMPEG image transport plugin.'),
DeclareLaunchArgument(
'serial_number',
default_value='0',
Expand Down
2 changes: 2 additions & 0 deletions zed_wrapper/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
<exec_depend>compressed_image_transport</exec_depend>
<exec_depend>compressed_depth_image_transport</exec_depend>
<exec_depend>theora_image_transport</exec_depend>
<exec_depend>ffmpeg_image_transport</exec_depend>
<exec_depend>ffmpeg_encoder_decoder</exec_depend>
<exec_depend>point_cloud_transport_plugins</exec_depend>
<exec_depend>draco_point_cloud_transport</exec_depend>
<exec_depend>zlib_point_cloud_transport</exec_depend>
Expand Down

0 comments on commit b1b9b1c

Please sign in to comment.