Skip to content

Commit f06d937

Browse files
RoseFlunderStuart Alldritt
authored andcommitted
Add body tracking data publishing (opencv#50)
1 parent 1a106d4 commit f06d937

File tree

6 files changed

+140
-7
lines changed

6 files changed

+140
-7
lines changed

README.md

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,6 @@ The camera is fully configurable using a variety of options which can be specifi
2121

2222
However, this node does ***not*** expose all the sensor data from the Azure Kinect Developer Kit hardware. It does not provide access to:
2323

24-
- Body tracking data
2524
- Microphone array
2625

2726
For more information about how to use the node, please see the [usage guide](docs/usage.md).

docs/usage.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ The node accepts the following parameters:
2222
- `rgb_point_cloud` (bool) : Defaults to `false`. If this parameter is set to `true`, the node will generate a sensor_msgs::PointCloud2 message from the depth camera data and colorize it using the color camera data. This requires that the `point_cloud` parameter be `true`, and the `color_enabled` parameter be `true`.
2323
- `recording_file` (string) : No default value. If this parameter contains a valid absolute path to a k4arecording file, the node will use the playback api with this file instead of opening a device.
2424
- `recording_loop_enabled` (bool) : Defaults to `false`. If this parameter is set to `true`, the node will rewind the recording file to the beginning after reaching the last frame. Otherwise the node will stop working after reaching the end of the recording file.
25+
- `body_tracking_enabled` (bool) : Defaults to `false`. If this parameter is set to `true`, the node will generate visualization_msgs::MarkerArray messages for the body tracking data. This requires that the `depth_enabled` parameter is set to `true` and an installed azure kinect body tracking sdk.
2526

2627
#### Parameter Restrictions
2728

@@ -49,6 +50,7 @@ The node emits a variety of topics into its namespace.
4950
- `ir/image_raw` (`sensor_msgs::Image`) : The raw infrared image from the depth camera sensor. In most depth modes, this image will be illuminated by the infrared illuminator built into the Azure Kinect DK. In `PASSIVE_IR` mode, this image will not be illuminated by the Azure Kinect DK.
5051
- `ir/camera_info` (`sensor_msgs::CameraInfo`) : Calibration information for the infrared camera, converted from the Azure Kinect Sensor SDK format. Since the depth camera and infrared camera are physically the same camera, this `camera_info` is a copy of the camera info published for the depth camera.
5152
- `imu` (`sensor_msgs::Imu`) : The intrinsics-corrected IMU sensor stream, provided by the Azure Kinect Sensor SDK. The sensor SDK automatically corrects for IMU intrinsics before sensor data is emitted.
53+
- `body_tracking_data` (`visualization_msgs::MarkerArray`) : Topic for receiving body tracking data. Each message contains all joints for all bodies for the most recent depth image. The markers are grouped by the [body id](https://microsoft.github.io/Azure-Kinect-Body-Tracking/release/0.9.x/structk4abt__body__t.html#a38fed6c7125f92b41165ffe2e1da9dd4) and the joints are in the same order as in the [joint enum of body tracking sdk](https://microsoft.github.io/Azure-Kinect-Body-Tracking/release/0.9.x/group__btenums.html#ga5fe6fa921525a37dec7175c91c473781). The id field of a marker is calculated by: `body_id * 100 + joint_index` where body_id is the corresponding body id from the body tracking sdk and the joint index is analogue to enum value for joints in the body tracking sdk. Subscribers can calculate the body.id by `floor(marker.id / 100)` and the joint_index by `marker.id % 100`.
5254

5355
## Azure Kinect Developer Kit Calibration
5456

include/azure_kinect_ros_driver/k4a_ros_device.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,11 @@
2323
#include <sensor_msgs/Temperature.h>
2424
#include <image_transport/image_transport.h>
2525

26+
#if defined(K4A_BODY_TRACKING)
27+
#include <k4abt.hpp>
28+
#include <visualization_msgs/MarkerArray.h>
29+
#endif
30+
2631
// Project headers
2732
//
2833
#include "azure_kinect_ros_driver/k4a_ros_device_params.h"
@@ -58,6 +63,10 @@ class K4AROSDevice
5863

5964
k4a_result_t getIrFrame(const k4a::capture &capture, sensor_msgs::ImagePtr ir_image);
6065

66+
#if defined(K4A_BODY_TRACKING)
67+
k4a_result_t getBodyMarker(const k4abt_body_t& body, visualization_msgs::MarkerPtr marker_msg, int jointType, ros::Time capture_time);
68+
#endif
69+
6170
private:
6271
k4a_result_t renderBGRA32ToROS(sensor_msgs::ImagePtr rgb_frame, k4a::image& k4a_bgra_frame);
6372
k4a_result_t renderDepthToROS(sensor_msgs::ImagePtr depth_image, k4a::image& k4a_depth_frame);
@@ -100,6 +109,10 @@ class K4AROSDevice
100109

101110
ros::Publisher pointcloud_publisher_;
102111

112+
#if defined(K4A_BODY_TRACKING)
113+
ros::Publisher body_marker_publisher_;
114+
#endif
115+
103116
// Parameters
104117
K4AROSDeviceParams params_;
105118

@@ -110,6 +123,11 @@ class K4AROSDevice
110123
// K4A Recording
111124
k4a_playback_t k4a_playback_handle_;
112125
std::mutex k4a_playback_handle_mutex_;
126+
127+
#if defined(K4A_BODY_TRACKING)
128+
// Body tracker
129+
k4abt::tracker k4abt_tracker_;
130+
#endif
113131

114132
ros::Time start_time_;
115133

include/azure_kinect_ros_driver/k4a_ros_device_params.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
LIST_ENTRY(tf_prefix, "The prefix prepended to tf frame ID's", std::string, std::string()) \
4040
LIST_ENTRY(recording_file, "Path to a recording file to open instead of opening a device", std::string, std::string("")) \
4141
LIST_ENTRY(recording_loop_enabled, "True if the recording should be rewound at EOF", bool, false) \
42+
LIST_ENTRY(body_tracking_enabled, "True if body joints should be published as a marker array message", bool, false) \
4243

4344
class K4AROSDeviceParams
4445
{

launch/driver.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@ Licensed under the MIT License.
2323
<arg name="sensor_sn" default="" /> <!-- Sensor serial number. If none provided, the first sensor will be selected -->
2424
<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 -->
2525
<arg name="recording_loop_enabled" default="false" /> <!-- If set to true the recording file will rewind the beginning once end of file is reached -->
26+
<arg name="body_tracking_enabled" default="false" /> <!-- If set to true the joint positions will be published as marker arrays -->
2627

2728
<node pkg="azure_kinect_ros_driver" type="node" name="node" output="screen" required="$(arg required)">
2829
<param name="depth_enabled" type="bool" value="$(arg depth_enabled)" />
@@ -36,5 +37,6 @@ Licensed under the MIT License.
3637
<param name="tf_prefix" type="string" value="$(arg tf_prefix)" />
3738
<param name="recording_file" type="string" value="$(arg recording_file)" />
3839
<param name="recording_loop_enabled" type="bool" value="$(arg recording_loop_enabled)" />
40+
<param name="body_tracking_enabled" type="bool" value="$(arg body_tracking_enabled)" />
3941
</node>
4042
</launch>

src/k4a_ros_device.cpp

Lines changed: 117 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,15 @@ using namespace sensor_msgs;
2727
using namespace image_transport;
2828
using namespace std;
2929

30+
#if defined(K4A_BODY_TRACKING)
31+
using namespace visualization_msgs;
32+
#endif
33+
3034
K4AROSDevice::K4AROSDevice(const NodeHandle &n, const NodeHandle &p) : k4a_device_(nullptr),
3135
k4a_playback_handle_(nullptr),
36+
#if defined(K4A_BODY_TRACKING)
37+
k4abt_tracker_(nullptr),
38+
#endif
3239
node_(n),
3340
private_node_(p),
3441
image_transport_(n),
@@ -223,6 +230,10 @@ K4AROSDevice::K4AROSDevice(const NodeHandle &n, const NodeHandle &p) : k4a_devic
223230
imu_orientation_publisher_ = node_.advertise<Imu>("imu", 200);
224231

225232
pointcloud_publisher_ = node_.advertise<PointCloud2>("points2", 1);
233+
234+
#if defined(K4A_BODY_TRACKING)
235+
body_marker_publisher_ = node_.advertise<MarkerArray>("body_tracking_data", 1);
236+
#endif
226237
}
227238

228239
K4AROSDevice::~K4AROSDevice()
@@ -247,16 +258,23 @@ K4AROSDevice::~K4AROSDevice()
247258
{
248259
k4a_playback_close(k4a_playback_handle_);
249260
}
261+
262+
#if defined(K4A_BODY_TRACKING)
263+
if (k4abt_tracker_)
264+
{
265+
k4abt_tracker_.shutdown();
266+
}
267+
#endif
250268
}
251269

252270

253271
k4a_result_t K4AROSDevice::startCameras()
254272
{
273+
k4a_device_configuration_t k4a_configuration = K4A_DEVICE_CONFIG_INIT_DISABLE_ALL;
274+
k4a_result_t result = params_.GetDeviceConfig(&k4a_configuration);
275+
255276
if (k4a_device_)
256277
{
257-
k4a_device_configuration_t k4a_configuration = K4A_DEVICE_CONFIG_INIT_DISABLE_ALL;
258-
k4a_result_t result = params_.GetDeviceConfig(&k4a_configuration);
259-
260278
if (result != K4A_RESULT_SUCCEEDED)
261279
{
262280
ROS_ERROR("Failed to generate a device configuration. Not starting camera!");
@@ -266,16 +284,28 @@ k4a_result_t K4AROSDevice::startCameras()
266284
// Now that we have a proposed camera configuration, we can
267285
// initialize the class which will take care of device calibration information
268286
calibration_data_.initialize(k4a_device_, k4a_configuration.depth_mode, k4a_configuration.color_resolution, params_);
269-
270-
ROS_INFO_STREAM("STARTING CAMERAS");
271-
k4a_device_.start_cameras(&k4a_configuration);
272287
}
273288
else if (k4a_playback_handle_)
274289
{
275290
// initialize the class which will take care of device calibration information from the playback_handle
276291
calibration_data_.initialize(k4a_playback_handle_, params_);
277292
}
293+
294+
278295

296+
#if defined(K4A_BODY_TRACKING)
297+
// When calibration is initialized the body tracker can be created with the device calibration
298+
if (params_.body_tracking_enabled)
299+
{
300+
k4abt_tracker_ = k4abt::tracker::create(calibration_data_.k4a_calibration_);
301+
}
302+
#endif
303+
304+
if (k4a_device_)
305+
{
306+
ROS_INFO_STREAM("STARTING CAMERAS");
307+
k4a_device_.start_cameras(&k4a_configuration);
308+
}
279309

280310
// Cannot assume the device timestamp begins increasing upon starting the cameras.
281311
// If we set the time base here, depending on the machine performance, the new timestamp
@@ -742,6 +772,42 @@ k4a_result_t K4AROSDevice::getImuFrame(const k4a_imu_sample_t& sample, sensor_ms
742772
return K4A_RESULT_SUCCEEDED;
743773
}
744774

775+
#if defined(K4A_BODY_TRACKING)
776+
k4a_result_t K4AROSDevice::getBodyMarker(const k4abt_body_t& body, MarkerPtr marker_msg, int jointType, ros::Time capture_time)
777+
{
778+
k4a_float3_t position = body.skeleton.joints[jointType].position;
779+
k4a_quaternion_t orientation = body.skeleton.joints[jointType].orientation;
780+
781+
marker_msg->header.frame_id = calibration_data_.tf_prefix_ + calibration_data_.depth_camera_frame_;
782+
marker_msg->header.stamp = capture_time;
783+
784+
// Set the lifetime to 0.25 to prevent flickering for even 5fps configurations.
785+
// New markers with the same ID will replace old markers as soon as they arrive.
786+
marker_msg->lifetime = ros::Duration(0.25);
787+
marker_msg->id = body.id * 100 + jointType;
788+
marker_msg->type = Marker::SPHERE;
789+
790+
marker_msg->color.a = 1.0;
791+
marker_msg->color.r = 255;
792+
marker_msg->color.g = 0;
793+
marker_msg->color.b = 0;
794+
795+
marker_msg->scale.x = 0.05;
796+
marker_msg->scale.y = 0.05;
797+
marker_msg->scale.z = 0.05;
798+
799+
marker_msg->pose.position.x = position.v[0] / 1000.0f;
800+
marker_msg->pose.position.y = position.v[1] / 1000.0f;
801+
marker_msg->pose.position.z = position.v[2] / 1000.0f;
802+
marker_msg->pose.orientation.x = orientation.v[0];
803+
marker_msg->pose.orientation.y = orientation.v[1];
804+
marker_msg->pose.orientation.z = orientation.v[2];
805+
marker_msg->pose.orientation.w = orientation.v[3];
806+
807+
return K4A_RESULT_SUCCEEDED;
808+
}
809+
#endif
810+
745811
void K4AROSDevice::framePublisherThread()
746812
{
747813
ros::Rate loop_rate(params_.fps);
@@ -916,6 +982,51 @@ void K4AROSDevice::framePublisherThread()
916982
depth_rect_camerainfo_publisher_.publish(depth_rect_camera_info);
917983
}
918984
}
985+
986+
#if defined(K4A_BODY_TRACKING)
987+
// Publish body markers when body tracking is enabled and a depth image is available
988+
if (params_.body_tracking_enabled && body_marker_publisher_.getNumSubscribers() > 0)
989+
{
990+
capture_time = timestampToROS(capture.get_depth_image().get_device_timestamp());
991+
992+
if (!k4abt_tracker_.enqueue_capture(capture))
993+
{
994+
ROS_ERROR("Error! Add capture to tracker process queue failed!");
995+
ros::shutdown();
996+
return;
997+
}
998+
else
999+
{
1000+
k4abt::frame body_frame = k4abt_tracker_.pop_result();
1001+
if (body_frame == nullptr)
1002+
{
1003+
ROS_ERROR_STREAM("Pop body frame result failed!");
1004+
ros::shutdown();
1005+
return;
1006+
}
1007+
else
1008+
{
1009+
auto num_bodies = body_frame.get_num_bodies();
1010+
if (num_bodies > 0)
1011+
{
1012+
MarkerArrayPtr markerArrayPtr(new MarkerArray);
1013+
for (size_t i = 0; i < num_bodies; ++i)
1014+
{
1015+
k4abt_body_t body = body_frame.get_body(i);
1016+
for (int j = 0; j < (int) K4ABT_JOINT_COUNT; ++j)
1017+
{
1018+
MarkerPtr markerPtr(new Marker);
1019+
getBodyMarker(body, markerPtr, j, capture_time);
1020+
markerArrayPtr->markers.push_back(*markerPtr);
1021+
}
1022+
}
1023+
1024+
body_marker_publisher_.publish(markerArrayPtr);
1025+
}
1026+
}
1027+
}
1028+
}
1029+
#endif
9191030
}
9201031
}
9211032

0 commit comments

Comments
 (0)