Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
fc8edd8
Add virtual param parser
Myzhar Nov 7, 2025
39b455f
Add Static TF broadcast function
Myzhar Nov 7, 2025
41ff5e3
Merge branch 'master' into publish_tf_from_extrinsic
Myzhar Nov 7, 2025
dbb6617
Trying to make the baseline dynamic
Myzhar Nov 7, 2025
2a16a65
Real baseline TF
Myzhar Nov 8, 2025
d9e5898
Improve IMU/Sensor TF and topic
Myzhar Nov 9, 2025
8b21227
Merge branch 'add_new_virtual_stereo' into publish_tf_from_extrinsic
Myzhar Nov 9, 2025
6128ff6
Fix IMU/Camera transform QoS
Myzhar Nov 9, 2025
ca46f72
Fix debug info
Myzhar Nov 9, 2025
123d200
Fix log info
Myzhar Nov 9, 2025
7a884c0
Minor fixes
Myzhar Nov 9, 2025
b6a650e
Improve perf
Myzhar Nov 9, 2025
0d50fc4
Merge pull request #390 from stereolabs/publish_tf_from_extrinsic
Myzhar Nov 9, 2025
3308282
Merge branch 'master' into add_new_virtual_stereo
Myzhar Nov 11, 2025
3367422
Fix IMU TF broadcasting behavior in changelog
Myzhar Nov 12, 2025
2e3de05
Fix CHANGELOG formatting and remove duplicates
Myzhar Nov 12, 2025
f674f03
Parse IDs and Serials for virtual stereo launch
Myzhar Nov 21, 2025
0ba7db4
Add new Virtual Stereo API with SDK v5.1
Myzhar Nov 21, 2025
30d258e
Merge branch 'add_new_virtual_stereo' of github.com:stereolabs/zed-ro…
Myzhar Nov 21, 2025
a22a4ab
Update zed_components/src/zed_camera/src/zed_camera_component_main.cpp
Myzhar Nov 21, 2025
3f18df1
Minor fixes
Myzhar Nov 21, 2025
e021d2b
Merge branch 'add_new_virtual_stereo' of github.com:stereolabs/zed-ro…
Myzhar Nov 21, 2025
ff8e995
Fix param description
Myzhar Nov 21, 2025
6c4f9f6
Fix comment
Myzhar Nov 21, 2025
95f51ed
Double comparison check fix
Myzhar Nov 21, 2025
95b7fa1
Merge branch 'add_new_virtual_stereo' of github.com:stereolabs/zed-ro…
Myzhar Nov 21, 2025
c81c8fa
Merge branch 'master' into add_new_virtual_stereo
Myzhar Nov 24, 2025
a4361eb
Fix changelog
Myzhar Nov 24, 2025
8b73005
Fix launch with SVO for virtual stereo on a PC
Myzhar Nov 24, 2025
65ab4de
fIX CHANGELOG
Myzhar Nov 24, 2025
7245714
Copilot suggested fixes
Myzhar Nov 24, 2025
a76c463
Fix parse_array_param python function
Myzhar Nov 24, 2025
5b364f7
Set default sirtual stereo resolution to HD1200
Myzhar Nov 24, 2025
41bfe44
Merge branch 'add_new_virtual_stereo' of github.com:stereolabs/zed-ro…
Myzhar Nov 24, 2025
f6c43a4
Fix baseline value check
Myzhar Nov 24, 2025
be867ad
Minor fix
Myzhar Nov 24, 2025
8e5acf3
Update zed_components/src/zed_camera/src/zed_camera_component_main.cpp
Myzhar Nov 24, 2025
386de39
Update zed_components/src/zed_camera/src/zed_camera_component_main.cpp
Myzhar Nov 24, 2025
f00f8ef
Merge branch 'master' into add_new_virtual_stereo
Myzhar Dec 1, 2025
0d836f7
Update SDK version
Myzhar Dec 1, 2025
bf45342
Merge branch 'add_new_virtual_stereo' of github.com:stereolabs/zed-ro…
Myzhar Dec 1, 2025
b8ac8cc
Code linting
Myzhar Dec 1, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 19 additions & 5 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,12 @@ LATEST CHANGES

2025-11-24
----------
- Add twist information to the `odom` topic
- Added twist information to the `odom` topic
- Added support for the new Virtual Stereo API with SDK v5.1.

- New launch arguments to setup the virtual camera: `serial_numbers` and `camera_ids`
- New `ZedCamera` component parameters to setup the virtual camera: `general.virtual_serial_numbers` and `general.virtual_camera_ids`
- **NOTE** ZED MEDIA SERVER IS NO LONGER REQUIRED to create a virtual Stereo camera using two ZED X One cameras.

2025-11-21
----------
Expand All @@ -35,7 +40,7 @@ LATEST CHANGES
- From `<camera_name>_left_camera_optical_frame` to `<camera_name>_left_camera_frame_optical`
- From `<camera_name>_right_camera_optical_frame` to `<camera_name>_right_camera_frame_optical`
- From `<camera_name>_camera_optical_frame` to `<camera_name>_rgb_camera_frame_optical`
**NOTE** THIS IS A BREAKING CHANGE. Please update your TF references accordingly.
- **NOTE** THIS IS A BREAKING CHANGE. Please update your TF references accordingly.

2025-11-11
----------
Expand All @@ -45,13 +50,22 @@ LATEST CHANGES
----------
- Fixed `camera_info` publishing when no image topics are subscribed

2025-11-05
2025-11-09
----------
- Remapped `robot_description` topic to `<camera_name>_description` to allow multi-camera URDF integration
- Added debug option for TF broadcasting

- Improved TF debug logs to show frame transformations when enabled

- Static baseline information from URDF is now overwritten by the real baseline value retrieved from the camera calibration file.
- Removed mandatory `custom_baseline` launch argument for virtual stereo cameras made with two ZED X One cameras.
The value is retrieved from the calibration file.
- IMU TF is now broadcast as static if IPC is disabled.
- IMU Transform topic is now published with TRANSIENT LOCAL durability if IPC is disabled.

2025-11-05
----------
- Changed minimum depth value to 0.01 meters when using ZED SDK v5.1 or higher
- Remapped `robot_description` topic to `<camera_name>_description` to allow multi-camera URDF integration
- Changed minimum depth value to 0.01 meters when using ZED SDK v5.1 or higher

2025-10-31
----------
Expand Down
2 changes: 1 addition & 1 deletion zed_components/src/include/sl_version.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ namespace stereolabs
{
const size_t WRAPPER_MAJOR = 5;
const size_t WRAPPER_MINOR = 1;
const size_t WRAPPER_PATCH = 0;
const size_t WRAPPER_PATCH = 1;

const size_t SDK_MAJOR_MIN_SUPP = 4;
const size_t SDK_MINOR_MIN_SUPP = 2;
Expand Down
15 changes: 15 additions & 0 deletions zed_components/src/tools/include/sl_logging.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,21 @@
#define DEBUG_STREAM_PC(stream_arg) \
if (_debugPointCloud) RCLCPP_DEBUG_STREAM(get_logger(), stream_arg)

// TF
#define DEBUG_TF(...) \
if (_debugTf) RCLCPP_DEBUG(get_logger(), __VA_ARGS__)
#define DEBUG_ONCE_TF(...) \
if (_debugTf) RCLCPP_DEBUG_ONCE(get_logger(), __VA_ARGS__)
#define DEBUG_STREAM_TF(stream_arg) \
if (_debugTf) RCLCPP_DEBUG_STREAM(get_logger(), stream_arg)
#define DEBUG_STREAM_THROTTLE_TF(duration, stream_arg) \
if (_debugTf) { \
rclcpp::Clock steady_clock(RCL_STEADY_TIME); \
RCLCPP_DEBUG_STREAM_THROTTLE( \
get_logger(), steady_clock, duration, \
stream_arg); \
}

// Positional Tracking
#define DEBUG_PT(...) \
if (_debugPosTracking) RCLCPP_DEBUG(get_logger(), __VA_ARGS__)
Expand Down
10 changes: 9 additions & 1 deletion zed_components/src/tools/include/sl_tools.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,9 +165,17 @@ bool generateROI(const std::vector<sl::float2> & poly, sl::Mat & out_roi);
* \param input
* \param error_return
* Syntax is [[1.0, 2.0], [3.3, 4.4, 5.5], ...] */
std::vector<std::vector<float>> parseStringVector(
std::vector<std::vector<float>> parseStringMultiVector_float(
const std::string & input, std::string & error_return);

/*! \brief Parse a vector of integer values from a string.
* \param input
* \param error_return
* Syntax is [1, 2, 3, ...] */
std::vector<int> parseStringVector_int(
const std::string & input,
std::string & error_return);

/*!
* @brief Convert thread policy to string
* @param thread_sched_policy
Expand Down
49 changes: 48 additions & 1 deletion zed_components/src/tools/src/sl_tools.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -431,7 +431,54 @@ bool generateROI(const std::vector<sl::float2> & poly, sl::Mat & out_roi)
return true;
}

std::vector<std::vector<float>> parseStringVector(
std::vector<int> parseStringVector_int(
const std::string & input,
std::string & error_return)
{
std::vector<int> result;

if (input == "[]") {
error_return = "";
return result;
}

if (input.empty() || input.front() != '[' || input.back() != ']') {
error_return = "Vector string must start with [ and end with ]";
return result;
}

std::string trimmed = input;
trimmed.erase(
std::remove(trimmed.begin(), trimmed.end(), '['),
trimmed.end());
trimmed.erase(
std::remove(trimmed.begin(), trimmed.end(), ']'),
trimmed.end());

std::stringstream ss(trimmed);
std::string token;
while (std::getline(ss, token, ',')) {
// Trim leading and trailing whitespace
token.erase(0, token.find_first_not_of(" \t\n\r"));
token.erase(token.find_last_not_of(" \t\n\r") + 1);

if (token.empty()) {
continue;
}

try {
int value = std::stoi(token);
result.push_back(value);
} catch (const std::exception & e) {
error_return = "Failed to parse integer: " + token;
return result;
}
}
error_return = "";
return result;
}

std::vector<std::vector<float>> parseStringMultiVector_float(
const std::string & input, std::string & error_return)
{
std::vector<std::vector<float>> result;
Expand Down
45 changes: 26 additions & 19 deletions zed_components/src/zed_camera/include/zed_camera_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,6 +304,7 @@ class ZedCamera : public rclcpp::Node
void publishGnssPoseStatus();
void publishGeoPoseStatus();
void publishTFs(rclcpp::Time t);
void publishCameraTFs(rclcpp::Time t);
void publishOdomTF(rclcpp::Time t);
void publishPoseTF(rclcpp::Time t);
bool publishSensorsData(rclcpp::Time force_ts = TIMEZERO_ROS);
Expand Down Expand Up @@ -371,7 +372,6 @@ class ZedCamera : public rclcpp::Node
sl::InitParameters mInitParams;
sl::RuntimeParameters mRunParams;


// ----> Fusion module
std::shared_ptr<sl::FusionConfiguration> mFusionConfig;
sl::Fusion mFusion;
Expand Down Expand Up @@ -436,6 +436,7 @@ class ZedCamera : public rclcpp::Node
bool _debugVideoDepth = false;
bool _debugCamCtrl = false;
bool _debugPointCloud = false;
bool _debugTf = false;
bool _debugPosTracking = false;
bool _debugGnss = false;
bool _debugSensors = false;
Expand Down Expand Up @@ -481,6 +482,8 @@ class ZedCamera : public rclcpp::Node
// General
int mCamSerialNumber = 0;
int mCamId = -1;
std::vector<int> mCamVirtualSerialNumbers;
std::vector<int> mCamVirtualCameraIds;
bool mSimMode = false; // Expecting simulation data?
bool mUseSimTime = false; // Use sim time?
std::string mSimAddr =
Expand Down Expand Up @@ -617,7 +620,6 @@ class ZedCamera : public rclcpp::Node
std::unordered_map<int, std::string> mCustomLabels;
std::unordered_map<std::string, int> mCustomClassIdMap;


bool mBodyTrkEnabled = false;
sl::BODY_TRACKING_MODEL mBodyTrkModel =
sl::BODY_TRACKING_MODEL::HUMAN_BODY_FAST;
Expand Down Expand Up @@ -692,30 +694,33 @@ class ZedCamera : public rclcpp::Node
// <---- QoS

// ----> Frame IDs
std::string mDepthFrameId;
std::string mDepthOptFrameId;
bool mStaticTfPublished = false;
bool mStaticImuTfPublished = false;

std::string mBaseFrameId = "";
std::string mCenterFrameId = "";

std::string mRightCamFrameId = "";
std::string mRightCamOptFrameId = "";
std::string mLeftCamFrameId = "";
std::string mLeftCamOptFrameId = "";

std::string mImuFrameId = "";
std::string mBaroFrameId = "";
std::string mMagFrameId = "";
std::string mTempLeftFrameId = "";
std::string mTempRightFrameId = "";

std::string mPointCloudFrameId;
std::string mDepthFrameId = "";
std::string mDepthOptFrameId = "";

std::string mPointCloudFrameId = "";

std::string mUtmFrameId = "utm";
std::string mMapFrameId = "map";
std::string mOdomFrameId = "odom";
std::string mBaseFrameId = "";
std::string mGnssFrameId = "";
std::string mGnssOriginFrameId = "gnss_ref_pose";

std::string mCameraFrameId;

std::string mRightCamFrameId;
std::string mRightCamOptFrameId;
std::string mLeftCamFrameId;
std::string mLeftCamOptFrameId;

std::string mImuFrameId;
std::string mBaroFrameId;
std::string mMagFrameId;
std::string mTempLeftFrameId;
std::string mTempRightFrameId;
// <---- Frame IDs

// ----> Stereolabs Mat Info
Expand All @@ -731,6 +736,7 @@ class ZedCamera : public rclcpp::Node
// ----> initialization Transform listener
std::unique_ptr<tf2_ros::Buffer> mTfBuffer;
std::unique_ptr<tf2_ros::TransformListener> mTfListener;
std::unique_ptr<tf2_ros::StaticTransformBroadcaster> mStaticTfBroadcaster;
std::unique_ptr<tf2_ros::TransformBroadcaster> mTfBroadcaster;
// <---- initialization Transform listener

Expand Down Expand Up @@ -1035,6 +1041,7 @@ class ZedCamera : public rclcpp::Node

// ----> Diagnostic
sl_tools::StopWatch mUptimer;
bool mUsingIPC = false;
float mTempImu = NOT_VALID_TEMP;
float mTempLeft = NOT_VALID_TEMP;
float mTempRight = NOT_VALID_TEMP;
Expand Down
Loading