Skip to content
This repository was archived by the owner on Jul 26, 2024. It is now read-only.
Open
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
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -56,3 +56,6 @@ modules.order
Module.symvers
Mkfile.old
dkms.conf

#Blender Autosave
*.blend?
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@ class K4ACalibrationTransformData
k4a::image transformed_depth_image_;

std::string tf_prefix_ = "";
std::string camera_base_frame_ = "camera_base";
std::string rgb_camera_frame_ = "rgb_camera_link";
std::string depth_camera_frame_ = "depth_camera_link";
std::string imu_frame_ = "imu_link";
std::string camera_base_frame_ = "azure_camera_base";
std::string rgb_camera_frame_ = "azure_rgb";
std::string depth_camera_frame_ = "azure_depth";
std::string imu_frame_ = "azure_imu";

private:
void initialize(K4AROSDeviceParams params);
Expand Down
3 changes: 2 additions & 1 deletion include/azure_kinect_ros_driver/k4a_ros_device_params.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,9 +57,10 @@
"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)", \
bool, true) \
LIST_ENTRY(calibration_url, 'URL to folder with calibration files (default: "file://$HOME/.ros/camera_info/").', \
LIST_ENTRY(calibration_url, 'URL to folder with calibration files (default: "file://$HOME/.ros/camera_info/").', \
std::string, {}) \
LIST_ENTRY(tf_prefix, "The prefix prepended to tf frame ID's", std::string, std::string()) \
LIST_ENTRY(publish_calibrated_poses, "Publish calibrated sensors poses at runtime", bool, true) \
LIST_ENTRY(recording_file, "Path to a recording file to open instead of opening a device", std::string, \
std::string("")) \
LIST_ENTRY(recording_loop_enabled, "True if the recording should be rewound at EOF", bool, false) \
Expand Down
32 changes: 17 additions & 15 deletions launch/driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,19 @@ Licensed under the MIT License.

<launch>
<arg name="tf_prefix" default="" /> <!-- Prefix added to tf frame IDs. It typically contains a trailing '_' unless empty. -->
<arg name="publish_calibrated_poses" default="true" /> <!-- Flag to publish the relative poses between IMU, RGB and depth camera from factory calibration parameters during runtime. -->
<arg name="overwrite_robot_description" default="true" /> <!-- Flag to publish a standalone azure_description instead of the default robot_descrition parameter-->

<group if="$(arg overwrite_robot_description)">
<param name="robot_description"
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect.urdf.xacro tf_prefix:=$(arg tf_prefix)" />
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect.urdf.xacro tf_prefix:=$(arg tf_prefix) publish_calibrated_poses:=$(arg publish_calibrated_poses)" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
</group>

<group unless="$(arg overwrite_robot_description)">
<param name="azure_description"
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect.urdf.xacro tf_prefix:=$(arg tf_prefix)" />
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect_standalone.urdf.xacro tf_prefix:=$(arg tf_prefix)" />
<node name="joint_state_publisher_azure" pkg="joint_state_publisher" type="joint_state_publisher">
<remap from="robot_description" to="azure_description" />
</node>
Expand All @@ -34,17 +35,17 @@ Licensed under the MIT License.
<arg name="fps" default="5" /> <!-- 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="true" /> <!-- 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="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="false" /> <!-- If set to true the joint positions will be published as marker arrays -->
<arg name="body_tracking_enabled" default="false" /> <!-- If set to true the joint positions will be published as marker arrays -->
<arg name="body_tracking_smoothing_factor" default="0.0" /> <!-- 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="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. -->

<node pkg="azure_kinect_ros_driver" type="node" name="azure_kinect_ros_driver" output="screen" required="$(arg required)">
Expand All @@ -57,17 +58,18 @@ Licensed under the MIT License.
<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="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="publish_calibrated_poses" type="bool" value="$(arg publish_calibrated_poses)" />
<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="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)"/>
</node>
</launch>
10 changes: 6 additions & 4 deletions launch/kinect_rgbd.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,14 @@

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

<!-- publish Azure Kinect coordiante frames -->
<arg name="tf_prefix" default="" /> <!-- Prefix added to tf frame IDs. It typically contains a trailing '_' unless empty. -->
<arg name="overwrite_robot_description" default="true" /> <!-- Flag to publish a standalone azure_description instead of the default robot_descrition parameter-->
<!-- publish Azure Kinect coordinate frames -->
<arg name="tf_prefix" default="" /> <!-- Prefix added to tf frame IDs. It typically contains a trailing '_' unless empty. -->
<arg name="publish_calibrated_poses" default="true" /> <!-- Flag to publish the relative poses between IMU, RGB and depth camera from factory calibration parameters during runtime. -->
<arg name="overwrite_robot_description" default="true" /> <!-- Flag to publish a standalone azure_description instead of the default robot_description parameter-->

<group if="$(arg overwrite_robot_description)">
<param name="robot_description"
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect.urdf.xacro tf_prefix:=$(arg tf_prefix)" />
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect_standalone.urdf.xacro tf_prefix:=$(arg tf_prefix) publish_calibrated_poses:=$(arg publish_calibrated_poses)" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
</group>
Expand Down Expand Up @@ -95,6 +96,7 @@
<param name="point_cloud_in_depth_frame" value="$(arg point_cloud_in_depth_frame)" />
<param name="sensor_sn" value="$(arg sensor_sn)" />
<param name="tf_prefix" value="$(arg tf_prefix)" />
<param name="publish_calibrated_poses" value="$(arg publish_calibrated_poses)" />
<param name="recording_file" value="$(arg recording_file)" />
<param name="recording_loop_enabled" value="$(arg recording_loop_enabled)" />
<param name="calibration_url" value="$(arg calibration_url)" />
Expand Down
2 changes: 1 addition & 1 deletion launch/slam_rtabmap.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ Licensed under the MIT License.
<launch>

<param name="robot_description"
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect.urdf.xacro" />
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect_standalone.urdf.xacro" />

<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" />
Expand Down
Loading