Skip to content
This repository was archived by the owner on Jul 26, 2024. It is now read-only.

Commit 0d23b99

Browse files
committed
microphone array frames
1 parent 25b1a5f commit 0d23b99

File tree

4 files changed

+71
-20
lines changed

4 files changed

+71
-20
lines changed

launch/driver.launch

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -34,17 +34,17 @@ Licensed under the MIT License.
3434
<arg name="fps" default="5" /> <!-- FPS to run both cameras at. Valid options are 5, 15, and 30 -->
3535
<arg name="point_cloud" default="true" /> <!-- Generate a point cloud from depth data. Requires depth_enabled -->
3636
<arg name="rgb_point_cloud" default="true" /> <!-- Colorize the point cloud using the RBG camera. Requires color_enabled and depth_enabled -->
37-
<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). -->
37+
<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). -->
3838
<arg name="required" default="false" /> <!-- Argument which specified if the entire launch file should terminate if the node dies -->
3939
<arg name="sensor_sn" default="" /> <!-- Sensor serial number. If none provided, the first sensor will be selected -->
4040
<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 -->
4141
<arg name="recording_loop_enabled" default="false" /> <!-- If set to true the recording file will rewind the beginning once end of file is reached -->
42-
<arg name="body_tracking_enabled" default="false" /> <!-- If set to true the joint positions will be published as marker arrays -->
42+
<arg name="body_tracking_enabled" default="false" /> <!-- If set to true the joint positions will be published as marker arrays -->
4343
<arg name="body_tracking_smoothing_factor" default="0.0" /> <!-- Set between 0 for no smoothing and 1 for full smoothing -->
44-
<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. -->
45-
<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. -->
46-
<arg name="imu_rate_target" default="0"/> <!-- Desired output rate of IMU messages. Set to 0 (default) for full rate (1.6 kHz). -->
47-
<arg name="wired_sync_mode" default="0"/> <!-- Wired sync mode. 0: OFF, 1: MASTER, 2: SUBORDINATE. -->
44+
<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. -->
45+
<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. -->
46+
<arg name="imu_rate_target" default="0"/> <!-- Desired output rate of IMU messages. Set to 0 (default) for full rate (1.6 kHz). -->
47+
<arg name="wired_sync_mode" default="0"/> <!-- Wired sync mode. 0: OFF, 1: MASTER, 2: SUBORDINATE. -->
4848
<arg name="subordinate_delay_off_master_usec" default="0"/> <!-- Delay subordinate camera off master camera by specified amount in usec. -->
4949

5050
<node pkg="azure_kinect_ros_driver" type="node" name="azure_kinect_ros_driver" output="screen" required="$(arg required)">
@@ -57,17 +57,17 @@ Licensed under the MIT License.
5757
<param name="fps" type="int" value="$(arg fps)" />
5858
<param name="point_cloud" type="bool" value="$(arg point_cloud)" />
5959
<param name="rgb_point_cloud" type="bool" value="$(arg rgb_point_cloud)" />
60-
<param name="point_cloud_in_depth_frame" type="bool" value="$(arg point_cloud_in_depth_frame)" />
60+
<param name="point_cloud_in_depth_frame" type="bool" value="$(arg point_cloud_in_depth_frame)" />
6161
<param name="sensor_sn" type="string" value="$(arg sensor_sn)" />
6262
<param name="tf_prefix" type="string" value="$(arg tf_prefix)" />
63-
<param name="recording_file" type="string" value="$(arg recording_file)" />
64-
<param name="recording_loop_enabled" type="bool" value="$(arg recording_loop_enabled)" />
65-
<param name="body_tracking_enabled" type="bool" value="$(arg body_tracking_enabled)" />
66-
<param name="body_tracking_smoothing_factor" type="double" value="$(arg body_tracking_smoothing_factor)" />
63+
<param name="recording_file" type="string" value="$(arg recording_file)" />
64+
<param name="recording_loop_enabled" type="bool" value="$(arg recording_loop_enabled)" />
65+
<param name="body_tracking_enabled" type="bool" value="$(arg body_tracking_enabled)" />
66+
<param name="body_tracking_smoothing_factor" type="double" value="$(arg body_tracking_smoothing_factor)" />
6767
<param name="rescale_ir_to_mono8" type="bool" value="$(arg rescale_ir_to_mono8)" />
6868
<param name="ir_mono8_scaling_factor" type="double" value="$(arg ir_mono8_scaling_factor)" />
69-
<param name="imu_rate_target" type="int" value="$(arg imu_rate_target)"/>
70-
<param name="wired_sync_mode" type="int" value="$(arg wired_sync_mode)"/>
69+
<param name="imu_rate_target" type="int" value="$(arg imu_rate_target)"/>
70+
<param name="wired_sync_mode" type="int" value="$(arg wired_sync_mode)"/>
7171
<param name="subordinate_delay_off_master_usec" type="int" value="$(arg subordinate_delay_off_master_usec)"/>
7272
</node>
7373
</launch>

launch/kinect_rgbd.launch

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,9 +3,9 @@
33

44
<arg name="camera" default="k4a" />
55

6-
<!-- publish Azure Kinect coordiante frames -->
7-
<arg name="tf_prefix" default="" /> <!-- Prefix added to tf frame IDs. It typically contains a trailing '_' unless empty. -->
8-
<arg name="overwrite_robot_description" default="true" /> <!-- Flag to publish a standalone azure_description instead of the default robot_descrition parameter-->
6+
<!-- publish Azure Kinect coordinate frames -->
7+
<arg name="tf_prefix" default="" /> <!-- Prefix added to tf frame IDs. It typically contains a trailing '_' unless empty. -->
8+
<arg name="overwrite_robot_description" default="true" /> <!-- Flag to publish a standalone azure_description instead of the default robot_description parameter-->
99

1010
<group if="$(arg overwrite_robot_description)">
1111
<param name="robot_description"

urdf/azure_kinect_macro.urdf.xacro

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,13 @@
4848
<link name="${prefix}azure_rgb" />
4949
<link name="${prefix}azure_depth" />
5050
<link name="${prefix}azure_gyro" />
51+
<link name="${prefix}azure_microphone_0" />
52+
<link name="${prefix}azure_microphone_1" />
53+
<link name="${prefix}azure_microphone_2" />
54+
<link name="${prefix}azure_microphone_3" />
55+
<link name="${prefix}azure_microphone_4" />
56+
<link name="${prefix}azure_microphone_5" />
57+
<link name="${prefix}azure_microphone_6" />
5158

5259
<joint name="${prefix}azure_base_to_camera_base" type="fixed">
5360
<parent link="${prefix}azure_base" />
@@ -73,6 +80,48 @@
7380
<origin xyz="0.0618 -0.0005 0.0065" rpy="0 ${pi} 0" />
7481
</joint>
7582

83+
<joint name="${prefix}azure_base_to_microphone_0" type="fixed">
84+
<parent link="${prefix}azure_base" />
85+
<child link="${prefix}azure_microphone_0" />
86+
<origin xyz="-0.018625 0 0.024632" rpy="0 0 0" />
87+
</joint>
88+
89+
<joint name="${prefix}azure_base_to_microphone_1" type="fixed">
90+
<parent link="${prefix}azure_base" />
91+
<child link="${prefix}azure_microphone_1" />
92+
<origin xyz="0.021376 0 0.024632" rpy="0 0 0" />
93+
</joint>
94+
95+
<joint name="${prefix}azure_base_to_microphone_2" type="fixed">
96+
<parent link="${prefix}azure_base" />
97+
<child link="${prefix}azure_microphone_2" />
98+
<origin xyz="0.001375 -0.034634 0.024632" rpy="0 0 0" />
99+
</joint>
100+
101+
<joint name="${prefix}azure_base_to_microphone_3" type="fixed">
102+
<parent link="${prefix}azure_base" />
103+
<child link="${prefix}azure_microphone_3" />
104+
<origin xyz="-0.038624 -0.034634 0.024632" rpy="0 0 0" />
105+
</joint>
106+
107+
<joint name="${prefix}azure_base_to_microphone_4" type="fixed">
108+
<parent link="${prefix}azure_base" />
109+
<child link="${prefix}azure_microphone_4" />
110+
<origin xyz="-0.058624 0 0.024632" rpy="0 0 0" />
111+
</joint>
112+
113+
<joint name="${prefix}azure_base_to_microphone_5" type="fixed">
114+
<parent link="${prefix}azure_base" />
115+
<child link="${prefix}azure_microphone_5" />
116+
<origin xyz="-0.038624 0.034634 0.024632" rpy="0 0 0" />
117+
</joint>
118+
119+
<joint name="${prefix}azure_base_to_microphone_6" type="fixed">
120+
<parent link="${prefix}azure_base" />
121+
<child link="${prefix}azure_microphone_6" />
122+
<origin xyz="0.001375 0.034634 0.024632" rpy="0 0 0" />
123+
</joint>
124+
76125
<xacro:if value="${gazebo}">
77126
<!-- Create a dummy frame for Gazebo, as the depth image is wrongly flipped and rotated
78127
(see #243 https://github.com/ros-simulation/gazebo_ros_pkgs/issues/243) -->

urdf/azure_kinect_standalone.urdf.xacro

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,9 @@
77
-->
88

99
<robot name="azure_kinect" xmlns:xacro="http://www.ros.org/wiki/xacro">
10-
<xacro:include filename="$(find azure_kinect_ros_driver)/urdf/azure_kinect_macro.urdf.xacro" />
10+
<xacro:arg name="tf_prefix" default=""/>
1111

12-
<link name="azure_stand">
12+
<link name="$(arg tf_prefix)azure_stand">
1313
<visual>
1414
<origin xyz="0 0 0" rpy="0 0 0" />
1515
<geometry>
@@ -24,7 +24,9 @@
2424
</collision>
2525
</link>
2626

27-
<xacro:azure_kinect prefix="" parent="azure_stand" gazebo="false">
27+
<xacro:include filename="$(find azure_kinect_ros_driver)/urdf/azure_kinect_macro.urdf.xacro" />
28+
29+
<xacro:azure_kinect prefix="$(arg tf_prefix)" parent="$(arg tf_prefix)azure_stand" gazebo="false">
2830
<origin xyz="0 0 0.0235" rpy="0 -0.06 0" />
2931
</xacro:azure_kinect>
30-
</robot>
32+
</robot>

0 commit comments

Comments
 (0)