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
35 changes: 23 additions & 12 deletions clearpath_sensors/config/stereolabs_zed.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -10,23 +10,28 @@ stereolabs_zed:
sim_port: 30000 # The connection port of the simulation server. See the documentation of the supported simulation plugins for more information.

svo:
svo_loop: false # Enable loop mode when using an SVO as input source
svo_realtime: true # if true the 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
use_svo_timestamps: true # Use the SVO timestamps to publish data. If false, data will be published at the system time.
svo_loop: false # Enable loop mode when using an SVO as input source. NOTE: ignored if SVO timestamping is used
svo_realtime: false # if true the 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
play_from_frame: 0 # Start playing the SVO from a specific frame

general:
camera_model: 'zed2'
camera_name: 'zed2' # usually overwritten by launch file
camera_timeout_sec: 5
camera_max_reconnect: 5
camera_flip: false
self_calib: false # Enable the self-calibration process at camera opening. See https://www.stereolabs.com/docs/api/structsl_1_1InitParameters.html#affeaa06cfc1d849e311e484ceb8edcc5
serial_number: 0 # usually overwritten by launch file
pub_resolution: "NATIVE" # The resolution used for output. 'NATIVE' to use the same `general.grab_resolution` - `CUSTOM` to apply the `general.pub_downscale_factor` downscale factory to reduce bandwidth in transmission
pub_downscale_factor: 2.0 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM'
grab_resolution: 'AUTO' # The native camera grab resolution. 'HD2K', 'HD1080', 'HD720', 'VGA', 'AUTO'
grab_frame_rate: 30 # ZED SDK internal grabbing rate
pub_frame_rate: 30.0 # frequency of publishing of visual images and depth images
enable_image_validity_check: 1 # [SDK5 required] Sets the image validity check. If set to 1, the SDK will check if the frames are valid before processing.
gpu_id: -1
optional_opencv_calibration_file: "" # Optional path where the ZED SDK can find a file containing the calibration information of the camera computed by OpenCV. Read the ZED SDK documentation for more information: https://www.stereolabs.com/docs/api/structsl_1_1InitParameters.html#a9eab2753374ef3baec1d31960859ba19
async_image_retrieval: false # Enable/disable the asynchronous image retrieval - Note: enable only to improve SVO recording performance

video:
brightness: 4 # [DYNAMIC] Not available for ZED X/ZED X Mini
Expand All @@ -46,7 +51,7 @@ stereolabs_zed:
depth_far_threshold_meters: 2.5 # Filtering how far object in the ROI should be considered, this is useful for a vehicle for instance
image_height_ratio_cutoff: 0.5 # By default consider only the lower half of the image, can be useful to filter out the sky
#manual_polygon: '[]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
#manual_polygon: "[[0.25,0.33],[0.75,0.33],[0.75,0.5],[0.5,0.75],[0.25,0.5]]" # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
#manual_polygon: '[[0.25,0.33],[0.75,0.33],[0.75,0.5],[0.5,0.75],[0.25,0.5]]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
#manual_polygon: '[[0.25,0.25],[0.75,0.25],[0.75,0.75],[0.25,0.75]]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
#manual_polygon: '[[0.5,0.25],[0.75,0.5],[0.5,0.75],[0.25,0.5]]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
apply_to_depth: true # Apply ROI to depth processing
Expand All @@ -56,11 +61,12 @@ stereolabs_zed:
apply_to_spatial_mapping: true # Apply ROI to spatial mapping processing

depth:
depth_mode: "ULTRA" # Matches the ZED SDK setting: 'NONE', 'PERFORMANCE', 'QUALITY', 'ULTRA', 'NEURAL', 'NEURAL_PLUS' - Note: if 'NONE' all the modules that requires depth extraction are disabled by default (Pos. Tracking, Obj. Detection, Mapping, ...)
depth_stabilization: 1 # Forces positional tracking to start if major than 0 - Range: [0,100]
depth_mode: 'NEURAL_LIGHT' # Matches the ZED SDK setting: 'NONE', 'PERFORMANCE', 'QUALITY', 'ULTRA', 'NEURAL', 'NEURAL_PLUS' - Note: if 'NONE' all the modules that requires depth extraction are disabled by default (Pos. Tracking, Obj. Detection, Mapping, ...)
depth_stabilization: 30 # Forces positional tracking to start if major than 0 - Range: [0,100]
openni_depth_mode: false # 'false': 32bit float [meters], 'true': 16bit unsigned int [millimeters]
point_cloud_freq: 10.0 # [DYNAMIC] - frequency of the pointcloud publishing (equal or less to `grab_frame_rate` value)
depth_confidence: 50 # [DYNAMIC]
point_cloud_freq: 30.0 # [DYNAMIC] - frequency of the pointcloud publishing (equal or less to `pub_frame_rate` value)
point_cloud_res: 'COMPACT' # The resolution used for point cloud publishing - 'COMPACT'-Standard resolution. Optimizes processing and bandwidth, 'REDUCED'-Half resolution. Low processing and bandwidth requirements
depth_confidence: 95 # [DYNAMIC]
depth_texture_conf: 100 # [DYNAMIC]
remove_saturated_areas: true # [DYNAMIC]

Expand All @@ -85,6 +91,7 @@ stereolabs_zed:
two_d_mode: false # Force navigation on a plane. If true the Z value will be fixed to 'fixed_z_value', roll and pitch to zero
fixed_z_value: 0.00 # Value to be used for Z coordinate if `two_d_mode` is true
transform_time_offset: 0.0 # The value added to the timestamp of `map->odom` and `odom->camera_link` transform being generated
reset_pose_with_svo_loop: true # Reset the camera pose the `initial_base_pose` when the SVO loop is enabled and the SVO playback reaches the end of the file.

gnss_fusion:
gnss_fusion_enabled: false # fuse 'sensor_msg/NavSatFix' message information into pose data
Expand Down Expand Up @@ -117,11 +124,15 @@ stereolabs_zed:

object_detection:
od_enabled: false # True to enable Object Detection
model: "MULTI_CLASS_BOX_MEDIUM" # 'MULTI_CLASS_BOX_FAST', 'MULTI_CLASS_BOX_MEDIUM', 'MULTI_CLASS_BOX_ACCURATE', 'PERSON_HEAD_BOX_FAST', 'PERSON_HEAD_BOX_ACCURATE'
model: 'MULTI_CLASS_BOX_FAST' # 'MULTI_CLASS_BOX_FAST', 'MULTI_CLASS_BOX_MEDIUM', 'MULTI_CLASS_BOX_ACCURATE', 'PERSON_HEAD_BOX_FAST', 'PERSON_HEAD_BOX_ACCURATE', 'CUSTOM_YOLOLIKE_BOX_OBJECTS'
custom_onnx_file: '' # Only used if 'model' is 'CUSTOM_YOLOLIKE_BOX_OBJECTS'. Path to the YOLO-like ONNX file for custom object detection directly performed by the ZED SDK.
custom_onnx_input_size: 512 # Resolution used with the YOLO-like ONNX file. For example, 512 means a input tensor '1x3x512x512'
custom_label_yaml: '' # Only used if 'model' is 'CUSTOM_YOLOLIKE_BOX_OBJECTS'. Path to the COCO-like YAML file storing the custom class labels.
allow_reduced_precision_inference: true # Allow inference to run at a lower precision to improve runtime and memory usage
max_range: 20.0 # [m] Defines a upper depth range for detections
confidence_threshold: 50.0 # [DYNAMIC] - Minimum value of the detection confidence of an object [0,99]
confidence_threshold: 75.0 # [DYNAMIC] - Minimum value of the detection confidence of an object [0,99]
prediction_timeout: 0.5 # During this time [sec], the object will have OK state even if it is not detected. Set this parameter to 0 to disable SDK predictions
enable_tracking: true # Defines if the object detection will track objects across images flow
filtering_mode: 1 # '0': NONE - '1': NMS3D - '2': NMS3D_PER_CLASS
mc_people: true # [DYNAMIC] - Enable/disable the detection of persons for 'MULTI_CLASS_X' models
mc_vehicle: true # [DYNAMIC] - Enable/disable the detection of vehicles for 'MULTI_CLASS_X' models
Expand All @@ -133,11 +144,11 @@ stereolabs_zed:

body_tracking:
bt_enabled: false # True to enable Body Tracking
model: "HUMAN_BODY_MEDIUM" # 'HUMAN_BODY_FAST', 'HUMAN_BODY_MEDIUM', 'HUMAN_BODY_ACCURATE'
body_format: "BODY_38" # 'BODY_18','BODY_34','BODY_38','BODY_70'
model: 'HUMAN_BODY_MEDIUM' # 'HUMAN_BODY_FAST', 'HUMAN_BODY_MEDIUM', 'HUMAN_BODY_ACCURATE'
body_format: 'BODY_38' # 'BODY_18','BODY_34','BODY_38','BODY_70'
allow_reduced_precision_inference: false # Allow inference to run at a lower precision to improve runtime and memory usage
max_range: 20.0 # [m] Defines a upper depth range for detections
body_kp_selection: "FULL" # 'FULL', 'UPPER_BODY'
body_kp_selection: 'FULL' # 'FULL', 'UPPER_BODY'
enable_body_fitting: false # Defines if the body fitting will be applied
enable_tracking: true # Defines if the object detection will track objects across images flow
prediction_timeout_s: 0.5 # During this time [sec], the skeleton will have OK state even if it is not detected. Set this parameter to 0 to disable SDK predictions
Expand Down
18 changes: 9 additions & 9 deletions clearpath_sensors/launch/stereolabs_zed.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution

from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare

HIDDEN = [
Expand Down Expand Up @@ -148,29 +149,28 @@ def generate_launch_description():
remappings.append(('/tf', PathJoinSubstitution(['/', robot_namespace, 'tf'])))
remappings.append(('/tf_static', PathJoinSubstitution(['/', robot_namespace, 'tf_static'])))

stereolabs_zed_node = Node(
package='zed_wrapper',
stereolabs_zed_node = ComposableNode(
package='zed_components',
namespace=namespace,
executable='zed_wrapper',
plugin='stereolabs::ZedCamera',
name='stereolabs_zed',
output='screen',
parameters=[parameters],
remappings=remappings,
remappings=remappings
)

image_processing_container = ComposableNodeContainer(
name='image_processing_container',
namespace=namespace,
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[],
output='screen'
composable_node_descriptions=[stereolabs_zed_node],
output='screen',
remappings=remappings
)

ld = LaunchDescription()
ld.add_action(arg_parameters)
ld.add_action(arg_namespace)
ld.add_action(arg_robot_namespace)
ld.add_action(stereolabs_zed_node)
ld.add_action(image_processing_container)
return ld