Skip to content
This repository was archived by the owner on Nov 17, 2020. It is now read-only.

Commit 2a33123

Browse files
committed
Add launch files for multi ZED and multi GPU, add zed_id
1 parent 6dcf0a3 commit 2a33123

File tree

4 files changed

+220
-3
lines changed

4 files changed

+220
-3
lines changed

README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,7 @@ Open a terminal :
8585
_ | _ | '1': STANDARD
8686
openni_depth_mode | Convert depth to 16bit in millimeters | '0': 32bit float meters
8787
_ | _ | '1': 16bit uchar millimeters
88+
zed_id | ZED Camera ID, ignore if SVO file given | int, default '0'
8889
gpu_id | GPU device ID, define which CUDA device will handle the computation | int, default '-1' (best device found)
8990
frame_rate | Rate at which images are published | int
9091
rgb_topic | Topic to which rgb==default==left images are published | string

launch/zed_multi_cam.launch

Lines changed: 126 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,126 @@
1+
<launch>
2+
3+
<include file="$(find zed_wrapper)/launch/zed_tf.launch" />
4+
5+
<param name="robot_description" textfile="$(find zed_wrapper)/urdf/zed.urdf" />
6+
7+
<arg name="svo_file1" default=""/>
8+
<arg name="svo_file2" default=""/>
9+
<arg name="svo_file3" default="path/to/svo/file.svo"/>
10+
11+
<group ns="camera">
12+
13+
14+
<node name="zed_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
15+
16+
<node name="zed_wrapper_node1" pkg="zed_wrapper" type="zed_wrapper_node" args="$(arg svo_file1)" output="screen">
17+
18+
<param name="resolution" value="2" />
19+
<param name="quality" value="1" />
20+
<param name="sensing_mode" value="1" />
21+
<param name="frame_rate" value="30" />
22+
<param name="odometry_DB" value="" />
23+
<param name="openni_depth_mode" value="0" />
24+
<param name="gpu_id" value="-1" />
25+
<param name="zed_id" value="0" />
26+
27+
<param name="rgb_topic" value="rgb/image_rect_color" />
28+
<param name="rgb_cam_info_topic" value="rgb/camera_info" />
29+
<param name="rgb_frame_id" value="/zed_tracked_frame" />
30+
31+
<param name="left_topic" value="left/image_rect_color" />
32+
<param name="left_cam_info_topic" value="left/camera_info" />
33+
<param name="left_frame_id" value="/zed_tracked_frame" />
34+
35+
<param name="right_topic" value="right/image_rect_color" />
36+
<param name="right_cam_info_topic" value="right/camera_info" />
37+
<param name="right_frame_id" value="/zed_tracked_frame" />
38+
39+
<param name="depth_topic" value="depth/image_rect_color" />
40+
<param name="depth_cam_info_topic" value="depth/camera_info" />
41+
<param name="depth_frame_id" value="/zed_tracked_frame" />
42+
43+
<param name="point_cloud_topic" value="point_cloud/cloud" />
44+
<param name="cloud_frame_id" value="/zed_tracked_frame" />
45+
46+
<param name="odometry_topic" value="odom" />
47+
<param name="odometry_frame_id" value="/zed_initial_frame" />
48+
<param name="odometry_transform_frame_id" value="/zed_tracked_frame" />
49+
50+
51+
</node>
52+
53+
<node name="zed_wrapper_node2" pkg="zed_wrapper" type="zed_wrapper_node" args="$(arg svo_file2)" output="screen">
54+
55+
<param name="resolution" value="2" />
56+
<param name="quality" value="1" />
57+
<param name="sensing_mode" value="1" />
58+
<param name="frame_rate" value="30" />
59+
<param name="odometry_DB" value="" />
60+
<param name="openni_depth_mode" value="0" />
61+
<param name="gpu_id" value="-1" />
62+
<param name="zed_id" value="1" />
63+
64+
<param name="rgb_topic" value="rgb/image_rect_color_1" />
65+
<param name="rgb_cam_info_topic" value="rgb/camera_info_1" />
66+
<param name="rgb_frame_id" value="/zed_tracked_frame_1" />
67+
68+
<param name="left_topic" value="left/image_rect_color_1" />
69+
<param name="left_cam_info_topic" value="left/camera_info_1" />
70+
<param name="left_frame_id" value="/zed_tracked_frame_1" />
71+
72+
<param name="right_topic" value="right/image_rect_color_1" />
73+
<param name="right_cam_info_topic" value="right/camera_info_1" />
74+
<param name="right_frame_id" value="/zed_tracked_frame_1" />
75+
76+
<param name="depth_topic" value="depth/image_rect_color_1" />
77+
<param name="depth_cam_info_topic" value="depth/camera_info_1" />
78+
<param name="depth_frame_id" value="/zed_tracked_frame_1" />
79+
80+
<param name="point_cloud_topic" value="point_cloud/cloud_1" />
81+
<param name="cloud_frame_id" value="/zed_tracked_frame_1" />
82+
83+
<param name="odometry_topic" value="odom_1" />
84+
<param name="odometry_frame_id" value="/zed_initial_frame_1" />
85+
<param name="odometry_transform_frame_id" value="/zed_tracked_frame_1" />
86+
87+
88+
</node>
89+
90+
<!-- <node name="zed_wrapper_node3" pkg="zed_wrapper" type="zed_wrapper_node" args="$(arg svo_file3)" output="screen">
91+
92+
<param name="resolution" value="2" />
93+
<param name="quality" value="1" />
94+
<param name="sensing_mode" value="1" />
95+
<param name="frame_rate" value="15" />
96+
<param name="odometry_DB" value="" />
97+
<param name="openni_depth_mode" value="0" />
98+
<param name="gpu_id" value="-1" />
99+
100+
<param name="rgb_topic" value="rgb/image_rect_color_2" />
101+
<param name="rgb_cam_info_topic" value="rgb/camera_info_2" />
102+
<param name="rgb_frame_id" value="/zed_tracked_frame_2" />
103+
104+
<param name="left_topic" value="left/image_rect_color_2" />
105+
<param name="left_cam_info_topic" value="left/camera_info_2" />
106+
<param name="left_frame_id" value="/zed_tracked_frame_2" />
107+
108+
<param name="right_topic" value="right/image_rect_color_2" />
109+
<param name="right_cam_info_topic" value="right/camera_info_2" />
110+
<param name="right_frame_id" value="/zed_tracked_frame_2" />
111+
112+
<param name="depth_topic" value="depth/image_rect_color_2" />
113+
<param name="depth_cam_info_topic" value="depth/camera_info_2" />
114+
<param name="depth_frame_id" value="/zed_tracked_frame_2" />
115+
116+
<param name="point_cloud_topic" value="point_cloud/cloud_2" />
117+
<param name="cloud_frame_id" value="/zed_tracked_frame_2" />
118+
119+
<param name="odometry_topic" value="odom_2" />
120+
<param name="odometry_frame_id" value="/zed_initial_frame_2" />
121+
<param name="odometry_transform_frame_id" value="/zed_tracked_frame_2" />
122+
123+
124+
</node> -->
125+
</group>
126+
</launch>

launch/zed_multi_gpu.launch

Lines changed: 89 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,89 @@
1+
<launch>
2+
3+
<include file="$(find zed_wrapper)/launch/zed_tf.launch" />
4+
5+
<param name="robot_description" textfile="$(find zed_wrapper)/urdf/zed.urdf" />
6+
7+
<arg name="svo_file0" default=""/>
8+
<arg name="svo_file1" default=""/>
9+
10+
<group ns="camera">
11+
12+
13+
<node name="zed_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
14+
15+
<node name="zed_wrapper_node_gpu0" pkg="zed_wrapper" type="zed_wrapper_node" args="$(arg svo_file0)" output="screen">
16+
17+
<param name="resolution" value="2" />
18+
<param name="quality" value="1" />
19+
<param name="sensing_mode" value="1" />
20+
<param name="frame_rate" value="30" />
21+
<param name="odometry_DB" value="" />
22+
<param name="openni_depth_mode" value="0" />
23+
<param name="gpu_id" value="0" />
24+
<param name="zed_id" value="0" />
25+
26+
<param name="rgb_topic" value="rgb/image_rect_color" />
27+
<param name="rgb_cam_info_topic" value="rgb/camera_info" />
28+
<param name="rgb_frame_id" value="/zed_tracked_frame" />
29+
30+
<param name="left_topic" value="left/image_rect_color" />
31+
<param name="left_cam_info_topic" value="left/camera_info" />
32+
<param name="left_frame_id" value="/zed_tracked_frame" />
33+
34+
<param name="right_topic" value="right/image_rect_color" />
35+
<param name="right_cam_info_topic" value="right/camera_info" />
36+
<param name="right_frame_id" value="/zed_tracked_frame" />
37+
38+
<param name="depth_topic" value="depth/image_rect_color" />
39+
<param name="depth_cam_info_topic" value="depth/camera_info" />
40+
<param name="depth_frame_id" value="/zed_tracked_frame" />
41+
42+
<param name="point_cloud_topic" value="point_cloud/cloud" />
43+
<param name="cloud_frame_id" value="/zed_tracked_frame" />
44+
45+
<param name="odometry_topic" value="odom" />
46+
<param name="odometry_frame_id" value="/zed_initial_frame" />
47+
<param name="odometry_transform_frame_id" value="/zed_tracked_frame" />
48+
49+
50+
</node>
51+
52+
<node name="zed_wrapper_node_gpu1" pkg="zed_wrapper" type="zed_wrapper_node" args="$(arg svo_file1)" output="screen">
53+
54+
<param name="resolution" value="2" />
55+
<param name="quality" value="1" />
56+
<param name="sensing_mode" value="1" />
57+
<param name="frame_rate" value="30" />
58+
<param name="odometry_DB" value="" />
59+
<param name="openni_depth_mode" value="0" />
60+
<param name="gpu_id" value="1" />
61+
<param name="zed_id" value="1" />
62+
63+
<param name="rgb_topic" value="rgb/image_rect_color_1" />
64+
<param name="rgb_cam_info_topic" value="rgb/camera_info_1" />
65+
<param name="rgb_frame_id" value="/zed_tracked_frame_1" />
66+
67+
<param name="left_topic" value="left/image_rect_color_1" />
68+
<param name="left_cam_info_topic" value="left/camera_info_1" />
69+
<param name="left_frame_id" value="/zed_tracked_frame_1" />
70+
71+
<param name="right_topic" value="right/image_rect_color_1" />
72+
<param name="right_cam_info_topic" value="right/camera_info_1" />
73+
<param name="right_frame_id" value="/zed_tracked_frame_1" />
74+
75+
<param name="depth_topic" value="depth/image_rect_color_1" />
76+
<param name="depth_cam_info_topic" value="depth/camera_info_1" />
77+
<param name="depth_frame_id" value="/zed_tracked_frame_1" />
78+
79+
<param name="point_cloud_topic" value="point_cloud/cloud_1" />
80+
<param name="cloud_frame_id" value="/zed_tracked_frame_1" />
81+
82+
<param name="odometry_topic" value="odom_1" />
83+
<param name="odometry_frame_id" value="/zed_initial_frame_1" />
84+
<param name="odometry_transform_frame_id" value="/zed_tracked_frame_1" />
85+
86+
87+
</node>
88+
</group>
89+
</launch>

src/zed_wrapper_node.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -354,6 +354,7 @@ int main(int argc, char **argv) {
354354
int sensing_mode = sl::zed::SENSING_MODE::STANDARD;
355355
int rate = 30;
356356
int gpu_id = -1;
357+
int zed_id = 0;
357358
string odometry_DB = "";
358359

359360
std::string img_topic = "image_rect";
@@ -401,7 +402,7 @@ int main(int argc, char **argv) {
401402
nh_ns.getParam("odometry_DB", odometry_DB);
402403
nh_ns.getParam("openni_depth_mode", openniDepthMode);
403404
nh_ns.getParam("gpu_id", gpu_id);
404-
405+
nh_ns.getParam("zed_id", zed_id);
405406
if (openniDepthMode)
406407
ROS_INFO_STREAM("Openni depth mode activated");
407408

@@ -434,7 +435,7 @@ int main(int argc, char **argv) {
434435
zed.reset(new sl::zed::Camera(argv[1])); // Argument "svo_file" in launch file
435436
ROS_INFO_STREAM("Reading SVO file : " << argv[1]);
436437
} else {
437-
zed.reset(new sl::zed::Camera(static_cast<sl::zed::ZEDResolution_mode> (resolution), rate));
438+
zed.reset(new sl::zed::Camera(static_cast<sl::zed::ZEDResolution_mode> (resolution), rate, zed_id));
438439
ROS_INFO_STREAM("Using ZED Camera");
439440
}
440441

@@ -571,7 +572,7 @@ int main(int argc, char **argv) {
571572
zed.reset(new sl::zed::Camera(argv[1])); // Argument "svo_file" in launch file
572573
ROS_INFO_STREAM("Reading SVO file : " << argv[1]);
573574
} else {
574-
zed.reset(new sl::zed::Camera(static_cast<sl::zed::ZEDResolution_mode> (resolution), rate));
575+
zed.reset(new sl::zed::Camera(static_cast<sl::zed::ZEDResolution_mode> (resolution), rate, zed_id));
575576
ROS_INFO_STREAM("Using ZED Camera");
576577
}
577578
ROS_INFO("Reinit camera");

0 commit comments

Comments
 (0)