Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
4 changes: 2 additions & 2 deletions .github/ISSUE_TEMPLATE/2_bug_report.yml
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ body:
OS: Operating System
CPU: e.g. ARM
GPU: Nvidia Jetson Xavier NX
ZED SDK version: e.g. v3.5.3
Other info: e.g. ROS Melodic
ZED SDK version: e.g. v4.0
Other info: e.g. ROS Noetic
validations:
required: true
- type: textarea
Expand Down
11 changes: 11 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,17 @@
CHANGELOG
=========

2023-03-31
----------
- Support for ZED SDK v4.0
- Remove parameter `object_detection.body_fitting`
- Remove parameter `depth.sensing_mode`
- Remove parameter `video.extrinsic_in_camera_frame`
- Skeleton Tracking is no more available. Migrate to ROS 2 Wrapper if you need it
- `sensors` and `object_detection` parameters are now in `common.yaml`
- Move parameters `general.resolution` and `general.grab_frame_rate` to cameras yaml files to support the different configurations on ZED X and ZED X Mini.
- Remove support for ROS Melodic that reached EOL

v3.8.x
------
- Fix the frame links of barometer, magnetometer, and temperature sensors for ZED2i
Expand Down
2 changes: 1 addition & 1 deletion LICENSE
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
MIT License

Copyright (c) 2020 Stereolabs
Copyright (c) 2023 Stereolabs

Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
Expand Down
35 changes: 21 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,9 @@ This package lets you use the ZED stereo camera with ROS. It outputs the camera
### Prerequisites

- Ubuntu 20.04
- [ZED SDK **≥ 3.8**](https://www.stereolabs.com/developers/) and its dependency [CUDA](https://developer.nvidia.com/cuda-downloads)
- [ZED SDK **≥ 4.0**](https://www.stereolabs.com/developers/) and its dependency [CUDA](https://developer.nvidia.com/cuda-downloads)
- [ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu)

or

- Ubuntu 18.04
- [ZED SDK **≥ 3.8**](https://www.stereolabs.com/developers/) and its dependency [CUDA](https://developer.nvidia.com/cuda-downloads)
- [ROS Melodic](http://wiki.ros.org/melodic/Installation/Ubuntu)

### Build the repository

The zed_ros_wrapper is a catkin package. It depends on the following ROS packages:
Expand Down Expand Up @@ -68,8 +62,7 @@ Remember to always clean the cache of your catkin workspace before compiling wit

$ roscd
$ cd ..
$ rm -rf build
$ rm -rf devel
$ rm -rf build devel
$ catkin_make -DCMAKE_BUILD_TYPE=Release

### Run the ZED wrapper
Expand All @@ -84,20 +77,28 @@ ZED Mini camera:

$ roslaunch zed_wrapper zedm.launch

ZED2 camera:
ZED 2 camera:

$ roslaunch zed_wrapper zed2.launch

ZED2i camera:
ZED 2i camera:

$ roslaunch zed_wrapper zed2i.launch

ZED X camera:

$ roslaunch zed_wrapper zed2i.launch
$ roslaunch zed_wrapper zedx.launch

ZED X Mini camera:

$ roslaunch zed_wrapper zedxm.launch

To select the ZED from its serial number:

$ roslaunch zed_wrapper zed.launch serial_number:=1010 #replace 1010 with the actual SN

### Rviz visualization
Example launch files to start a pre-configured Rviz environment to visualize the data of ZED, ZED Mini and ZED 2 cameras are provided in the [`zed-ros-examples` repository](https://github.com/stereolabs/zed-ros-examples/tree/master/zed_display_rviz)
Example launch files to start a pre-configured Rviz environment to visualize the data of ZED, ZED Mini, ZED 2, ZED X, and ZED X Mini cameras are provided in the [`zed-ros-examples` repository](https://github.com/stereolabs/zed-ros-examples/tree/master/zed_display_rviz)

### SVO recording
[SVO recording](https://www.stereolabs.com/docs/video/#video-recording) can be started and stopped while the ZED node is running using the service `start_svo_recording` and the service `stop_svo_recording`.
Expand All @@ -106,14 +107,20 @@ Example launch files to start a pre-configured Rviz environment to visualize the
### Object Detection
The SDK v3.0 introduces the Object Detection and Tracking module. **The Object Detection module is available only with a ZED 2 camera**.

The Object Detection can be enabled *automatically* when the node start setting the parameter `object_detection/od_enabled` to `true` in the file `zed2.yaml`.
The Object Detection can be enabled *automatically* when the node start setting the parameter `object_detection/od_enabled` to `true` in the file `common.yaml`.

The Object Detection can be enabled/disabled *manually* calling the services `start_object_detection` and `stop_object_detection`.

### Body Tracking
The Body Tracking module is not available for the ZED ROS Wrapper. Please consider migrating to the [ZED ROS2 Wrapper](https://github.com/stereolabs/zed-ros2-wrapper) if you need it.

### Spatial Mapping
The Spatial Mapping can be enabled automatically when the node start setting the parameter `mapping/mapping_enabled` to `true` in the file `common.yaml`.
The Spatial Mapping can be enabled/disabled manually calling the services `start_3d_mapping` and `stop_3d_mapping`.

### Geo Tracking (GNSS Fusion)
The Geo tracking module is not available for the ZED ROS Wrapper. Please consider migrating to the [ZED ROS2 Wrapper](https://github.com/stereolabs/zed-ros2-wrapper) if you need it.

### Diagnostic
The ZED node publishes diagnostic information that can be used by the robotic system using a [diagnostic_aggregator node](http://wiki.ros.org/diagnostic_aggregator).

Expand Down
2 changes: 1 addition & 1 deletion zed-ros-interfaces
7 changes: 5 additions & 2 deletions zed_nodelets/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@ cmake_minimum_required(VERSION 3.5)

project(zed_nodelets)

## Generate symbols for IDE indexer
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)

# if CMAKE_BUILD_TYPE is not specified, take 'Release' as default
IF(NOT CMAKE_BUILD_TYPE)
SET(CMAKE_BUILD_TYPE Release)
Expand All @@ -19,8 +22,8 @@ function(checkPackage package customMessage)
endif()
endfunction(checkPackage)

find_package(ZED 3)
checkPackage("ZED" "ZED SDK v3.x not found, install it from:\n https://www.stereolabs.com/developers/")
find_package(ZED 4)
checkPackage("ZED" "ZED SDK v4.x not found, install it from:\n https://www.stereolabs.com/developers/")

exec_program(uname ARGS -p OUTPUT_VARIABLE CMAKE_SYSTEM_NAME2)
if ( CMAKE_SYSTEM_NAME2 MATCHES "aarch64" ) # Jetson TX
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2020, STEREOLABS.
// Copyright (c) 2023, STEREOLABS.
//
// All rights reserved.
//
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2020, STEREOLABS.
// Copyright (c) 2023, STEREOLABS.
//
// All rights reserved.
//
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2020, STEREOLABS.
// Copyright (c) 2023, STEREOLABS.
//
// All rights reserved.
//
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2020, STEREOLABS.
// Copyright (c) 2023, STEREOLABS.
//
// All rights reserved.
//
Expand Down
20 changes: 4 additions & 16 deletions zed_nodelets/src/tools/include/sl_tools.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
#ifndef SL_TOOLS_H
#define SL_TOOLS_H

///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2020, STEREOLABS.
// Copyright (c) 2023, STEREOLABS.
//
// All rights reserved.
//
Expand All @@ -21,6 +18,9 @@
//
///////////////////////////////////////////////////////////////////////////

#ifndef SL_TOOLS_H
#define SL_TOOLS_H

#include <ros/time.h>
#include <sensor_msgs/Image.h>
#include <sl/Camera.hpp>
Expand All @@ -29,18 +29,6 @@

namespace sl_tools
{
/*! \brief Check if a ZED camera is ready
* \param serial_number : the serial number of the camera to be checked
*/
int checkCameraReady(unsigned int serial_number);

/*! \brief Get ZED camera properties
* \param serial_number : the serial number of the camera
*/
sl::DeviceProperties getZEDFromSN(unsigned int serial_number);

std::vector<float> convertRodrigues(sl::float3 r);

/*! \brief Test if a file exist
* \param name : the path to the file
*/
Expand Down
101 changes: 1 addition & 100 deletions zed_nodelets/src/tools/src/sl_tools.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2020, STEREOLABS.
// Copyright (c) 2023, STEREOLABS.
//
// All rights reserved.
//
Expand Down Expand Up @@ -30,105 +30,6 @@

namespace sl_tools
{
int checkCameraReady(unsigned int serial_number)
{
int id = -1;
auto f = sl::Camera::getDeviceList();

for (auto& it : f)
if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::AVAILABLE)
{
id = it.id;
}

return id;
}

sl::DeviceProperties getZEDFromSN(unsigned int serial_number)
{
sl::DeviceProperties prop;
auto f = sl::Camera::getDeviceList();

for (auto& it : f)
{
if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::AVAILABLE)
{
prop = it;
}
}

return prop;
}

std::vector<float> convertRodrigues(sl::float3 r)
{
float theta = sqrt(r.x * r.x + r.y * r.y + r.z * r.z);

std::vector<float> R = { 1.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 1.0f };

if (theta < DBL_EPSILON)
{
return R;
}
else
{
float c = cos(theta);
float s = sin(theta);
float c1 = 1.f - c;
float itheta = theta ? 1.f / theta : 0.f;

r *= itheta;

std::vector<float> rrt = { 1.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 1.0f };

float* p = rrt.data();
p[0] = r.x * r.x;
p[1] = r.x * r.y;
p[2] = r.x * r.z;
p[3] = r.x * r.y;
p[4] = r.y * r.y;
p[5] = r.y * r.z;
p[6] = r.x * r.z;
p[7] = r.y * r.z;
p[8] = r.z * r.z;

std::vector<float> r_x = { 1.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 1.0f };
p = r_x.data();
p[0] = 0;
p[1] = -r.z;
p[2] = r.y;
p[3] = r.z;
p[4] = 0;
p[5] = -r.x;
p[6] = -r.y;
p[7] = r.x;
p[8] = 0;

// R = cos(theta)*I + (1 - cos(theta))*r*rT + sin(theta)*[r_x]

sl::Matrix3f eye;
eye.setIdentity();

sl::Matrix3f sl_R(R.data());
sl::Matrix3f sl_rrt(rrt.data());
sl::Matrix3f sl_r_x(r_x.data());

sl_R = eye * c + sl_rrt * c1 + sl_r_x * s;

R[0] = sl_R.r00;
R[1] = sl_R.r01;
R[2] = sl_R.r02;
R[3] = sl_R.r10;
R[4] = sl_R.r11;
R[5] = sl_R.r12;
R[6] = sl_R.r20;
R[7] = sl_R.r21;
R[8] = sl_R.r22;
}

return R;
}

bool file_exist(const std::string& name)
{
struct stat buffer;
Expand Down
14 changes: 6 additions & 8 deletions zed_nodelets/src/zed_nodelet/include/zed_wrapper_nodelet.hpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
#ifndef ZED_WRAPPER_NODELET_H
#define ZED_WRAPPER_NODELET_H

///////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2020, STEREOLABS.
// Copyright (c) 2023, STEREOLABS.
//
// All rights reserved.
//
Expand All @@ -21,6 +18,9 @@
//
///////////////////////////////////////////////////////////////////////////

#ifndef ZED_WRAPPER_NODELET_H
#define ZED_WRAPPER_NODELET_H

#include <diagnostic_updater/diagnostic_updater.h>
#include <dynamic_reconfigure/server.h>
#include <geometry_msgs/PointStamped.h>
Expand Down Expand Up @@ -541,7 +541,6 @@ class ZEDWrapperNodelet : public nodelet::Nodelet {
sl::RESOLUTION mCamResol;
int mCamFrameRate;
sl::DEPTH_MODE mDepthMode;
sl::SENSING_MODE mCamSensingMode;
int mGpuId;
int mZedId;
int mDepthStabilization;
Expand Down Expand Up @@ -645,7 +644,6 @@ class ZEDWrapperNodelet : public nodelet::Nodelet {
bool mAreaMemory;
bool mInitOdomWithPose;
bool mResetOdom = false;
bool mUseOldExtrinsic = false;
bool mUpdateDynParams = false;
bool mPublishingData = false;

Expand Down Expand Up @@ -726,7 +724,7 @@ class ZEDWrapperNodelet : public nodelet::Nodelet {
bool mObjDetFruitsEnable = true;
bool mObjDetSportsEnable = true;

sl::DETECTION_MODEL mObjDetModel = sl::DETECTION_MODEL::MULTI_CLASS_BOX;
sl::OBJECT_DETECTION_MODEL mObjDetModel = sl::OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX_MEDIUM;

ros::Publisher mPubObjDet;
}; // class ZEDROSWrapperNodelet
Expand Down
Loading