Skip to content

Commit 55a4302

Browse files
authored
Merge pull request #80 from stereolabs/devel_v3.7
Devel v3.7
2 parents c9fba52 + 278e9df commit 55a4302

File tree

9 files changed

+196
-69
lines changed

9 files changed

+196
-69
lines changed

README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ $ sudo apt remove ros-foxy-image-transport-plugins ros-foxy-compressed-depth-ima
4848
### Prerequisites
4949

5050
- [Ubuntu 20.04 (Focal Fossa)](https://releases.ubuntu.com/focal/)
51-
- [ZED SDK](https://www.stereolabs.com/developers/release/latest/) v3.6
51+
- [ZED SDK](https://www.stereolabs.com/developers/release/latest/) v3.7
5252
- [CUDA](https://developer.nvidia.com/cuda-downloads) dependency
5353
- ROS2 Foxy Fitxroy:
5454
- [Ubuntu 20.04](https://docs.ros.org/en/foxy/Installation/Linux-Install-Debians.html)

last_changes.md

+5-4
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,13 @@
11
LATEST CHANGES
22
==============
33

4-
2022-01-04
4+
v3.7.x
55
----------
6+
- Add support for sport-related OD objects
7+
- Add `remove_saturated_areas` dynamic parameter to disable depth filtering when luminance >=255
8+
- Add `sl::ObjectDetectionParameters::filtering_mode` parameter
9+
- Publish `depth_info` topic with current min/max depth information
610
- Fix parameter override problem (Issue #71). Thx @kevinanschau
7-
8-
2021-12-16
9-
----------
1011
- Add default xacro path value in `zed_camera.launch.py`. Thx @sttobia
1112
- Fix `zed-ros2-interfaces` sub-module url, changing from `ssh` to `https`.
1213

zed_components/src/zed_camera/include/zed_camera_component.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@
5050
#include <sensor_msgs/msg/imu.hpp>
5151
#include <sensor_msgs/msg/magnetic_field.hpp>
5252
#include <sensor_msgs/msg/fluid_pressure.hpp>
53+
5354
#include <sensor_msgs/msg/temperature.hpp>
5455
#include <nav_msgs/msg/odometry.hpp>
5556
#include <nav_msgs/msg/path.hpp>
@@ -61,6 +62,7 @@
6162

6263
#include <zed_interfaces/msg/objects_stamped.hpp>
6364
#include <zed_interfaces/msg/object.hpp>
65+
#include <zed_interfaces/msg/depth_info_stamped.hpp>
6466
#include <zed_interfaces/srv/set_pose.hpp>
6567
#include <zed_interfaces/srv/start_svo_rec.hpp>
6668

@@ -88,6 +90,7 @@ typedef std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odomPub;
8890
typedef std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Path>> pathPub;
8991

9092
typedef std::shared_ptr<rclcpp::Publisher<zed_interfaces::msg::ObjectsStamped>> objPub;
93+
typedef std::shared_ptr<rclcpp::Publisher<zed_interfaces::msg::DepthInfoStamped>> depthInfoPub;
9194

9295
typedef std::unique_ptr<sensor_msgs::msg::Image> imageMsgPtr;
9396
typedef std::shared_ptr<sensor_msgs::msg::CameraInfo> camInfoMsgPtr;
@@ -105,6 +108,7 @@ typedef std::unique_ptr<nav_msgs::msg::Odometry> odomMsgPtr;
105108
typedef std::unique_ptr<nav_msgs::msg::Path> pathMsgPtr;
106109

107110
typedef std::unique_ptr<zed_interfaces::msg::ObjectsStamped> objDetMsgPtr;
111+
typedef std::unique_ptr<zed_interfaces::msg::DepthInfoStamped> depthInfoMsgPtr;
108112

109113
typedef rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr resetOdomSrvPtr;
110114
typedef rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr resetPosTrkSrvPtr;
@@ -320,9 +324,11 @@ class ZedCamera : public rclcpp::Node
320324
bool mObjDetAnimalsEnable = true;
321325
bool mObjDetElectronicsEnable = true;
322326
bool mObjDetFruitsEnable = true;
327+
bool mObjDetSportEnable = true;
323328
bool mObjDetBodyFitting = false;
324329
sl::BODY_FORMAT mObjDetBodyFmt = sl::BODY_FORMAT::POSE_34;
325330
sl::DETECTION_MODEL mObjDetModel = sl::DETECTION_MODEL::HUMAN_BODY_FAST;
331+
sl::OBJECT_FILTERING_MODE mObjFilterMode = sl::OBJECT_FILTERING_MODE::NMS3D;
326332
// QoS parameters
327333
// https://github.com/ros2/ros2/wiki/About-Quality-of-Service-Settings
328334
rclcpp::QoS mVideoQos;
@@ -355,6 +361,7 @@ class ZedCamera : public rclcpp::Node
355361
double mDepthPubRate = 15.0;
356362
double mPcPubRate = 15.0;
357363
double mFusedPcPubRate = 1.0;
364+
bool mRemoveSatAreas = true;
358365
// <---- Dynamic params
359366

360367
// ----> Frame IDs
@@ -474,6 +481,7 @@ class ZedCamera : public rclcpp::Node
474481
tempPub mPubTempR; //
475482
transfPub mPubCamImuTransf; //;
476483
objPub mPubObjDet;
484+
depthInfoPub mPubDepthInfo;
477485
// <---- Publishers
478486

479487
// ----> Threads and Timers

zed_components/src/zed_camera/src/zed_camera_component.cpp

+138-29
Large diffs are not rendered by default.

zed_wrapper/config/common.yaml

+7-6
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
ros__parameters:
99
general:
1010
svo_file: ''
11-
svo_loop: true # Enable loop mode when using an SVO as input source
11+
svo_loop: false # Enable loop mode when using an SVO as input source
1212
svo_realtime: false # if true SVO will be played trying to respect the original framerate eventually skipping frames, otherwise every frame will be processed respecting the `pub_frame_rate` setting
1313
camera_timeout_sec: 5
1414
camera_max_reconnect: 5
@@ -17,13 +17,13 @@
1717
serial_number: 0
1818
resolution: 2 # '0': HD2K, '1': HD1080, '2': HD720, '3': VGA
1919
sdk_verbose: true
20-
grab_frame_rate: 30 # ZED SDK internal grabbing rate
20+
grab_frame_rate: 15 # ZED SDK internal grabbing rate
2121
pub_frame_rate: 15.0 # [DYNAMIC] - frequency of publishing of visual images and depth images
2222
gpu_id: -1
2323

2424
video:
2525
extrinsic_in_camera_frame: false # if `false` extrinsic parameter in `camera_info` will use ROS native frame (X FORWARD, Z UP) instead of the camera frame (Z FORWARD, Y DOWN) [`true` use old behavior as for version < v3.1]
26-
img_downsample_factor: 0.5 # Resample factor for image data matrices [0.01,1.0] The SDK works with native data sizes, but publishes rescaled matrices
26+
img_downsample_factor: 1.0 # Resample factor for image data matrices [0.01,1.0] The SDK works with native data sizes, but publishes rescaled matrices
2727
brightness: 4 # [DYNAMIC]
2828
contrast: 4 # [DYNAMIC]
2929
hue: 0 # [DYNAMIC]
@@ -41,14 +41,15 @@
4141
qos_durability: 2 # '1': TRANSIENT_LOCAL - '2': VOLATILE
4242

4343
depth:
44-
quality: 1 # '0': NONE, '1': PERFORMANCE, '2': QUALITY, '3': ULTRA - Note: if '0' all the modules that requires depth extraction are disabled by default (Pos. Tracking, Obj. Detection, Mapping, ...)
44+
quality: 4 # '0': NONE, '1': PERFORMANCE, '2': QUALITY, '3': ULTRA - '4': NEURAL - Note: if '0' all the modules that requires depth extraction are disabled by default (Pos. Tracking, Obj. Detection, Mapping, ...)
4545
sensing_mode: 0 # '0': STANDARD, '1': FILL
4646
depth_stabilization: true # Forces positional tracking to start if 'true'
4747
openni_depth_mode: false # 'false': 32bit float [meters], 'true': 16bit unsigned int [millimeters]
48-
depth_downsample_factor: 0.5 # Resample factor for depth data matrices [0.01,1.0] The SDK works with native data sizes, but publishes rescaled matrices (depth map, point cloud, ...)
48+
depth_downsample_factor: 1.0 # Resample factor for depth data matrices [0.01,1.0] The SDK works with native data sizes, but publishes rescaled matrices (depth map, point cloud, ...)
4949
point_cloud_freq: 10.0 # [DYNAMIC] - frequency of the pointcloud publishing (equal or less to `grab_frame_rate` value)
50-
depth_confidence: 50 # [DYNAMIC]
50+
depth_confidence: 30 # [DYNAMIC]
5151
depth_texture_conf: 100 # [DYNAMIC]
52+
remove_saturated_areas: true # [DYNAMIC]
5253
qos_history: 1 # '1': KEEP_LAST - '2': KEEP_ALL
5354
qos_depth: 1 # Queue size if using KEEP_LAST
5455
qos_reliability: 1 # '1': RELIABLE - '2': BEST_EFFORT -

zed_wrapper/config/zed2.yaml

+12-10
Original file line numberDiff line numberDiff line change
@@ -28,16 +28,18 @@
2828
object_detection:
2929
od_enabled: false # True to enable Object Detection [only ZED 2]
3030
confidence_threshold: 50.0 # [DYNAMIC] - Minimum value of the detection confidence of an object [0,100]
31-
model: 3 # '0': MULTI_CLASS_BOX - '1': MULTI_CLASS_BOX_ACCURATE - '2': HUMAN_BODY_FAST - '3': HUMAN_BODY_ACCURATE - '4': MULTI_CLASS_BOX_MEDIUM - '5': HUMAN_BODY_MEDIUM - '6': PERSON_HEAD_BOX
32-
mc_people: true # [DYNAMIC] - Enable/disable the detection of persons for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
33-
mc_vehicle: true # [DYNAMIC] - Enable/disable the detection of vehicles for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
34-
mc_bag: true # [DYNAMIC] - Enable/disable the detection of bags for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
35-
mc_animal: true # [DYNAMIC] - Enable/disable the detection of animals for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
36-
mc_electronics: true # [DYNAMIC] - Enable/disable the detection of electronic devices for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
37-
mc_fruit_vegetable: true # [DYNAMIC] - Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
38-
body_fitting: false # Enable/disable body fitting for 'HUMAN_BODY_FAST' and 'HUMAN_BODY_ACCURATE' models
31+
model: 0 # '0': MULTI_CLASS_BOX - '1': MULTI_CLASS_BOX_ACCURATE - '2': HUMAN_BODY_FAST - '3': HUMAN_BODY_ACCURATE - '4': MULTI_CLASS_BOX_MEDIUM - '5': HUMAN_BODY_MEDIUM - '6': PERSON_HEAD_BOX
32+
filtering_mode: 1 # '0': NONE - '1': NMS3D - '2': NMS3D_PER_CLASS
33+
mc_people: true # [DYNAMIC] - Enable/disable the detection of persons for 'MULTI_CLASS_X' models
34+
mc_vehicle: true # [DYNAMIC] - Enable/disable the detection of vehicles for 'MULTI_CLASS_X' models
35+
mc_bag: true # [DYNAMIC] - Enable/disable the detection of bags for 'MULTI_CLASS_X' models
36+
mc_animal: true # [DYNAMIC] - Enable/disable the detection of animals for 'MULTI_CLASS_X' models
37+
mc_electronics: true # [DYNAMIC] - Enable/disable the detection of electronic devices for 'MULTI_CLASS_X' models
38+
mc_fruit_vegetable: true # [DYNAMIC] - Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_X' models
39+
mc_sport: true # [DYNAMIC] - Enable/disable the detection of sport-related objects for 'MULTI_CLASS_X' models
40+
body_fitting: true # Enable/disable body fitting for 'HUMAN_BODY_FAST' and 'HUMAN_BODY_ACCURATE' models
3941
body_format: 1 # '0': POSE_18 - '1': POSE_34 [Only if `HUMAN_BODY_*` model is selected]
4042
qos_history: 1 # '1': KEEP_LAST - '2': KEEP_ALL
4143
qos_depth: 1 # Queue size if using KEEP_LAST
42-
qos_reliability: 1 # '1': RELIABLE - '2': BEST_EFFORT -
43-
qos_durability: 2 # '1': TRANSIENT_LOCAL - '2': VOLATILE
44+
qos_reliability: 1 # '1': RELIABLE - '2': BEST_EFFORT
45+
qos_durability: 2 # '1': TRANSIENT_LOCAL - '2': VOLATILE

zed_wrapper/config/zed2i.yaml

+12-9
Original file line numberDiff line numberDiff line change
@@ -28,15 +28,18 @@
2828
object_detection:
2929
od_enabled: false # True to enable Object Detection [only ZED 2]
3030
confidence_threshold: 50.0 # [DYNAMIC] - Minimum value of the detection confidence of an object [0,100]
31-
model: 2 # '0': MULTI_CLASS_BOX - '1': MULTI_CLASS_BOX_ACCURATE - '2': HUMAN_BODY_FAST - '3': HUMAN_BODY_ACCURATE - '4': MULTI_CLASS_BOX_MEDIUM - '5': HUMAN_BODY_MEDIUM - '6': PERSON_HEAD_BOX
32-
mc_people: true # [DYNAMIC] - Enable/disable the detection of persons for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
33-
mc_vehicle: true # [DYNAMIC] - Enable/disable the detection of vehicles for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
34-
mc_bag: true # [DYNAMIC] - Enable/disable the detection of bags for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
35-
mc_animal: true # [DYNAMIC] - Enable/disable the detection of animals for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
36-
mc_electronics: true # [DYNAMIC] - Enable/disable the detection of electronic devices for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
37-
mc_fruit_vegetable: true # [DYNAMIC] - Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
38-
body_fitting: false # Enable/disable body fitting for 'HUMAN_BODY_FAST' and 'HUMAN_BODY_ACCURATE' models
31+
model: 0 # '0': MULTI_CLASS_BOX - '1': MULTI_CLASS_BOX_ACCURATE - '2': HUMAN_BODY_FAST - '3': HUMAN_BODY_ACCURATE - '4': MULTI_CLASS_BOX_MEDIUM - '5': HUMAN_BODY_MEDIUM - '6': PERSON_HEAD_BOX
32+
filtering_mode: 1 # '0': NONE - '1': NMS3D - '2': NMS3D_PER_CLASS
33+
mc_people: true # [DYNAMIC] - Enable/disable the detection of persons for 'MULTI_CLASS_X' models
34+
mc_vehicle: true # [DYNAMIC] - Enable/disable the detection of vehicles for 'MULTI_CLASS_X' models
35+
mc_bag: true # [DYNAMIC] - Enable/disable the detection of bags for 'MULTI_CLASS_X' models
36+
mc_animal: true # [DYNAMIC] - Enable/disable the detection of animals for 'MULTI_CLASS_X' models
37+
mc_electronics: true # [DYNAMIC] - Enable/disable the detection of electronic devices for 'MULTI_CLASS_X' models
38+
mc_fruit_vegetable: true # [DYNAMIC] - Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_X' models
39+
mc_sport: true # [DYNAMIC] - Enable/disable the detection of sport-related objects for 'MULTI_CLASS_X' models
40+
body_fitting: true # Enable/disable body fitting for 'HUMAN_BODY_FAST' and 'HUMAN_BODY_ACCURATE' models
41+
body_format: 1 # '0': POSE_18 - '1': POSE_34 [Only if `HUMAN_BODY_*` model is selected]
3942
qos_history: 1 # '1': KEEP_LAST - '2': KEEP_ALL
4043
qos_depth: 1 # Queue size if using KEEP_LAST
41-
qos_reliability: 1 # '1': RELIABLE - '2': BEST_EFFORT -
44+
qos_reliability: 1 # '1': RELIABLE - '2': BEST_EFFORT
4245
qos_durability: 2 # '1': TRANSIENT_LOCAL - '2': VOLATILE

zed_wrapper/config/zedm.yaml

+12-9
Original file line numberDiff line numberDiff line change
@@ -28,15 +28,18 @@
2828
object_detection:
2929
od_enabled: false # True to enable Object Detection [only ZED 2]
3030
confidence_threshold: 50.0 # [DYNAMIC] - Minimum value of the detection confidence of an object [0,100]
31-
model: 6 # '0': MULTI_CLASS_BOX - '1': MULTI_CLASS_BOX_ACCURATE - '2': HUMAN_BODY_FAST - '3': HUMAN_BODY_ACCURATE - '4': MULTI_CLASS_BOX_MEDIUM - '5': HUMAN_BODY_MEDIUM - '6': PERSON_HEAD_BOX
32-
mc_people: true # [DYNAMIC] - Enable/disable the detection of persons for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
33-
mc_vehicle: true # [DYNAMIC] - Enable/disable the detection of vehicles for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
34-
mc_bag: true # [DYNAMIC] - Enable/disable the detection of bags for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
35-
mc_animal: true # [DYNAMIC] - Enable/disable the detection of animals for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
36-
mc_electronics: true # [DYNAMIC] - Enable/disable the detection of electronic devices for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
37-
mc_fruit_vegetable: true # [DYNAMIC] - Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_BOX' and 'MULTI_CLASS_BOX_ACCURATE' models
38-
body_fitting: false # Enable/disable body fitting for 'HUMAN_BODY_FAST' and 'HUMAN_BODY_ACCURATE' models
31+
model: 0 # '0': MULTI_CLASS_BOX - '1': MULTI_CLASS_BOX_ACCURATE - '2': HUMAN_BODY_FAST - '3': HUMAN_BODY_ACCURATE - '4': MULTI_CLASS_BOX_MEDIUM - '5': HUMAN_BODY_MEDIUM - '6': PERSON_HEAD_BOX
32+
filtering_mode: 1 # '0': NONE - '1': NMS3D - '2': NMS3D_PER_CLASS
33+
mc_people: true # [DYNAMIC] - Enable/disable the detection of persons for 'MULTI_CLASS_X' models
34+
mc_vehicle: true # [DYNAMIC] - Enable/disable the detection of vehicles for 'MULTI_CLASS_X' models
35+
mc_bag: true # [DYNAMIC] - Enable/disable the detection of bags for 'MULTI_CLASS_X' models
36+
mc_animal: true # [DYNAMIC] - Enable/disable the detection of animals for 'MULTI_CLASS_X' models
37+
mc_electronics: true # [DYNAMIC] - Enable/disable the detection of electronic devices for 'MULTI_CLASS_X' models
38+
mc_fruit_vegetable: true # [DYNAMIC] - Enable/disable the detection of fruits and vegetables for 'MULTI_CLASS_X' models
39+
mc_sport: true # [DYNAMIC] - Enable/disable the detection of sport-related objects for 'MULTI_CLASS_X' models
40+
body_fitting: true # Enable/disable body fitting for 'HUMAN_BODY_FAST' and 'HUMAN_BODY_ACCURATE' models
41+
body_format: 1 # '0': POSE_18 - '1': POSE_34 [Only if `HUMAN_BODY_*` model is selected]
3942
qos_history: 1 # '1': KEEP_LAST - '2': KEEP_ALL
4043
qos_depth: 1 # Queue size if using KEEP_LAST
41-
qos_reliability: 1 # '1': RELIABLE - '2': BEST_EFFORT -
44+
qos_reliability: 1 # '1': RELIABLE - '2': BEST_EFFORT
4245
qos_durability: 2 # '1': TRANSIENT_LOCAL - '2': VOLATILE

0 commit comments

Comments
 (0)