Skip to content

Commit 03be2de

Browse files
committed
✨ feat: launchの追加とconfigの調整(確認コマンド:ros2 topic hz /zed_node/rgb/image_rect_color 出力:average rate: 112.232)
1 parent ead884b commit 03be2de

3 files changed

Lines changed: 43 additions & 14 deletions

File tree

zed_wrapper/config/common.yaml

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,9 @@
2020
camera_max_reconnect: 5
2121
camera_flip: false
2222
serial_number: 0 # usually overwritten by launch file
23-
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
23+
pub_resolution: "CUSTOM" # 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
2424
pub_downscale_factor: 2.0 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM'
25-
pub_frame_rate: 30.0 # frequency of publishing of visual images and depth images
25+
pub_frame_rate: 120.0 # frequency of publishing of visual images and depth images
2626
gpu_id: -1
2727
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
2828

@@ -54,7 +54,7 @@
5454
apply_to_spatial_mapping: true # Apply ROI to spatial mapping processing
5555

5656
depth:
57-
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, ...)
57+
depth_mode: "NONE" # 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, ...)
5858
depth_stabilization: 1 # Forces positional tracking to start if major than 0 - Range: [0,100]
5959
openni_depth_mode: false # 'false': 32bit float [meters], 'true': 16bit unsigned int [millimeters]
6060
point_cloud_freq: 10.0 # [DYNAMIC] - frequency of the pointcloud publishing (equal or less to `grab_frame_rate` value)
@@ -63,16 +63,16 @@
6363
remove_saturated_areas: true # [DYNAMIC]
6464

6565
pos_tracking:
66-
pos_tracking_enabled: true # True to enable positional tracking from start
66+
pos_tracking_enabled: false # True to enable positional tracking from start
6767
pos_tracking_mode: "GEN_2" # Matches the ZED SDK setting: 'GEN_1', 'GEN_2'
68-
imu_fusion: true # enable/disable IMU fusion. When set to false, only the optical odometry will be used.
69-
publish_tf: true # [usually overwritten by launch file] publish `odom -> camera_link` TF
70-
publish_map_tf: true # [usually overwritten by launch file] publish `map -> odom` TF
68+
imu_fusion: false # enable/disable IMU fusion. When set to false, only the optical odometry will be used.
69+
publish_tf: false # [usually overwritten by launch file] publish `odom -> camera_link` TF
70+
publish_map_tf: false # [usually overwritten by launch file] publish `map -> odom` TF
7171
map_frame: "map"
7272
odometry_frame: "odom"
7373
area_memory_db_path: ""
74-
area_memory: true # Enable to detect loop closure
75-
reset_odom_with_loop_closure: true # Re-initialize odometry to the last valid pose when loop closure happens (reset camera odometry drift)
74+
area_memory: false # Enable to detect loop closure
75+
reset_odom_with_loop_closure: false # Re-initialize odometry to the last valid pose when loop closure happens (reset camera odometry drift)
7676
depth_min_range: 0.0 # Set this value for removing fixed zones of the robot in the FoV of the camerafrom the visual odometry evaluation
7777
set_as_static: false # If 'true' the camera will be static and not move in the environment
7878
set_gravity_as_origin: true # If 'true' align the positional tracking world to imu gravity measurement. Keep the yaw from the user initial pose.
@@ -90,10 +90,10 @@
9090
gnss_zero_altitude: false # Set to `true` to ignore GNSS altitude information
9191
h_covariance_mul: 1.0 # Multiplier factor to be applied to horizontal covariance of the received fix (plane X/Y)
9292
v_covariance_mul: 1.0 # Multiplier factor to be applied to vertical covariance of the received fix (Z axis)
93-
publish_utm_tf: true # Publish `utm` -> `map` TF
93+
publish_utm_tf: false # Publish `utm` -> `map` TF
9494
broadcast_utm_transform_as_parent_frame: false # if 'true' publish `utm` -> `map` TF, otherwise `map` -> `utm`
9595
enable_reinitialization: false # determines whether reinitialization should be performed between GNSS and VIO fusion when a significant disparity is detected between GNSS data and the current fusion data. It becomes particularly crucial during prolonged GNSS signal loss scenarios.
96-
enable_rolling_calibration: true # If this parameter is set to true, the fusion algorithm will used a rough VIO / GNSS calibration at first and then refine it. This allow you to quickly get a fused position.
96+
enable_rolling_calibration: false # If this parameter is set to true, the fusion algorithm will used a rough VIO / GNSS calibration at first and then refine it. This allow you to quickly get a fused position.
9797
enable_translation_uncertainty_target: false # When this parameter is enabled (set to true), the calibration process between GNSS and VIO accounts for the uncertainty in the determined translation, thereby facilitating the calibration termination. The maximum allowable uncertainty is controlled by the 'target_translation_uncertainty' parameter.
9898
gnss_vio_reinit_threshold: 5.0 # determines the threshold for GNSS/VIO reinitialization. If the fused position deviates beyond out of the region defined by the product of the GNSS covariance and the gnss_vio_reinit_threshold, a reinitialization will be triggered.
9999
target_translation_uncertainty: 10e-2 # defines the target translation uncertainty at which the calibration process between GNSS and VIO concludes. By default, the threshold is set at 10 centimeters.
@@ -109,7 +109,7 @@
109109
pd_normal_similarity_threshold: 15.0 # Plane detection: controls the spread of plane by checking the angle difference.
110110

111111
sensors:
112-
publish_imu_tf: true # [usually overwritten by launch file] enable/disable the IMU TF broadcasting
112+
publish_imu_tf: false # [usually overwritten by launch file] enable/disable the IMU TF broadcasting
113113
sensors_image_sync: false # Synchronize Sensors messages with latest published video/depth message
114114
sensors_pub_rate: 200. # frequency of publishing of sensors data. MAX: 400. - MIN: grab rate
115115

zed_wrapper/config/zedx.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@
66
general:
77
camera_model: 'zedx'
88
camera_name: 'zedx' # usually overwritten by launch file
9-
grab_resolution: 'HD1200' # The native camera grab resolution. 'HD1200', 'HD1080', 'SVGA', 'AUTO'
10-
grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200/HD1080: 60, 30, 15 - SVGA: 120, 60, 30, 15)
9+
grab_resolution: 'SVGA' # The native camera grab resolution. 'HD1200', 'HD1080', 'SVGA', 'AUTO'
10+
grab_frame_rate: 120 # ZED SDK internal grabbing rate (HD1200/HD1080: 60, 30, 15 - SVGA: 120, 60, 30, 15)
1111

1212
video:
1313
exposure_time: 16000 # Defines the real exposure time in microseconds. Recommended to control manual exposure (instead of `video.exposure` setting)
Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
import os.path as osp
2+
from ament_index_python.packages import get_package_share_directory
3+
4+
from launch import LaunchDescription
5+
from launch.actions import SetEnvironmentVariable
6+
from launch_ros.actions import Node
7+
8+
9+
def generate_launch_description():
10+
zed_wrapper_dir = get_package_share_directory("zed_wrapper")
11+
config_common_path = osp.join(zed_wrapper_dir, "config", "common.yaml")
12+
config_camera_path = osp.join(zed_wrapper_dir, "config", "zedx.yaml")
13+
14+
zed_node = Node(
15+
package="zed_wrapper",
16+
executable="zed_wrapper",
17+
name="zed_node",
18+
output="screen",
19+
parameters=[
20+
config_common_path,
21+
config_camera_path,
22+
],
23+
)
24+
25+
return LaunchDescription([
26+
SetEnvironmentVariable(name="RCUTILS_COLORIZED_OUTPUT", value="1"),
27+
zed_node,
28+
])
29+

0 commit comments

Comments
 (0)