-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathdisplay.launch
69 lines (62 loc) · 6.8 KB
/
display.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
<launch>
<arg name="tf_prefix" default="" /> <!-- Prefix added to tf frame IDs. It typically contains a trailing '_' unless empty. -->
<param name="robot_description"
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect.urdf.xacro tf_prefix:=$(arg tf_prefix)" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<arg name="depth_enabled" default="true" /> <!-- Enable or disable the depth camera -->
<arg name="depth_mode" default="WFOV_2X2BINNED" /> <!-- Set the depth camera mode, which affects FOV, depth range, and camera resolution. See Azure Kinect documentation for full details. Valid options: NFOV_UNBINNED, NFOV_2X2BINNED, WFOV_UNBINNED, WFOV_2X2BINNED, and PASSIVE_IR -->
<arg name="color_enabled" default="false" /> <!-- Enable or disable the color camera -->
<arg name="color_format" default="bgra" /> <!-- The format of RGB camera. Valid options: bgra, jpeg -->
<arg name="color_resolution" default="720P" /> <!-- Resolution at which to run the color camera. Valid options: 720P, 1080P, 1440P, 1536P, 2160P, 3072P -->
<arg name="fps" default="15" /> <!-- FPS to run both cameras at. Valid options are 5, 15, and 30 -->
<arg name="point_cloud" default="true" /> <!-- Generate a point cloud from depth data. Requires depth_enabled -->
<arg name="rgb_point_cloud" default="false" /> <!-- Colorize the point cloud using the RBG camera. Requires color_enabled and depth_enabled -->
<arg name="point_cloud_in_depth_frame" default="false" /> <!-- Whether the RGB pointcloud is rendered in the depth frame (true) or RGB frame (false). Will either match the resolution of the depth camera (true) or the RGB camera (false). -->
<arg name="required" default="false" /> <!-- Argument which specified if the entire launch file should terminate if the node dies -->
<arg name="sensor_sn" default="" /> <!-- Sensor serial number. If none provided, the first sensor will be selected -->
<arg name="recording_file" default="" /> <!-- Absolute path to a mkv recording file which will be used with the playback api instead of opening a device -->
<arg name="recording_loop_enabled" default="false" /> <!-- If set to true the recording file will rewind the beginning once end of file is reached -->
<arg name="body_tracking_enabled" default="true" /> <!-- If set to true the joint positions will be published as marker arrays -->
<arg name="body_tracking_smoothing_factor" default="0.5" /> <!-- Set between 0 for no smoothing and 1 for full smoothing -->
<arg name="rescale_ir_to_mono8" default="false" /> <!-- Whether to rescale the IR image to an 8-bit monochrome image for visualization and further processing. A scaling factor (ir_mono8_scaling_factor) is applied. -->
<arg name="ir_mono8_scaling_factor" default="1.0" /> <!-- Scaling factor to apply when converting IR to mono8 (see rescale_ir_to_mono8). If using illumination, use the value 0.5-1. If using passive IR, use 10. -->
<arg name="imu_rate_target" default="0"/> <!-- Desired output rate of IMU messages. Set to 0 (default) for full rate (1.6 kHz). -->
<arg name="wired_sync_mode" default="0"/> <!-- Wired sync mode. 0: OFF, 1: MASTER, 2: SUBORDINATE. -->
<arg name="subordinate_delay_off_master_usec" default="0"/> <!-- Delay subordinate camera off master camera by specified amount in usec. -->
<arg name="imu_publishing_enabled" default="false" />
<arg name="depth_publishing_enabled" default="false" />
<arg name="ir_publishing_enabled" default="false" />
<arg name="rgbrect_publishing_enabled" default="false" />
<arg name="body_index_map_publishing_enabled" default="false" />
<node pkg="azure_kinect_ros_driver" type="node" name="azure_kinect_ros_driver" output="screen" required="$(arg required)">
<param name="depth_enabled" type="bool" value="$(arg depth_enabled)" />
<param name="depth_mode" type="string" value="$(arg depth_mode)" />
<param name="color_enabled" type="bool" value="$(arg color_enabled)" />
<param name="color_format" type="string" value="$(arg color_format)" />
<param name="color_resolution" type="string" value="$(arg color_resolution)" />
<param name="fps" type="int" value="$(arg fps)" />
<param name="point_cloud" type="bool" value="$(arg point_cloud)" />
<param name="rgb_point_cloud" type="bool" value="$(arg rgb_point_cloud)" />
<param name="point_cloud_in_depth_frame" type="bool" value="$(arg point_cloud_in_depth_frame)" />
<param name="sensor_sn" type="string" value="$(arg sensor_sn)" />
<param name="tf_prefix" type="string" value="$(arg tf_prefix)" />
<param name="recording_file" type="string" value="$(arg recording_file)" />
<param name="recording_loop_enabled" type="bool" value="$(arg recording_loop_enabled)" />
<param name="body_tracking_enabled" type="bool" value="$(arg body_tracking_enabled)" />
<param name="body_tracking_smoothing_factor" type="double" value="$(arg body_tracking_smoothing_factor)" />
<param name="rescale_ir_to_mono8" type="bool" value="$(arg rescale_ir_to_mono8)" />
<param name="ir_mono8_scaling_factor" type="double" value="$(arg ir_mono8_scaling_factor)" />
<param name="imu_rate_target" type="int" value="$(arg imu_rate_target)"/>
<param name="wired_sync_mode" type="int" value="$(arg wired_sync_mode)"/>
<param name="subordinate_delay_off_master_usec" type="int" value="$(arg subordinate_delay_off_master_usec)"/>
<param name="imu_publishing_enabled" type="bool" value="$(arg imu_publishing_enabled)" />
<param name="depth_publishing_enabled" type="bool" value="$(arg depth_publishing_enabled)" />
<param name="ir_publishing_enabled" type="bool" value="$(arg ir_publishing_enabled)" />
<param name="rgbrect_publishing_enabled" type="bool" value="$(arg rgbrect_publishing_enabled)" />
<param name="body_index_map_publishing_enabled" type="bool" value="$(arg body_index_map_publishing_enabled)" />
</node>
<!--<node name="rviz" pkg="rviz" type="rviz" args="-d roman2020_display.rviz" output="screen"/>-->
<!-- 'Attach' real camera frame to the real robot model camera frame -->
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 1 real/kinect_depth_optical_frame depth_camera_link 100" />
</launch>