29 #include <Image/ImageProcessor.h>
30 #include <Calibration/Calibration.h>
51 k4aToIvtImage(
const k4a::image& color_image, ::CByteImage& result)
53 auto cw =
static_cast<unsigned int>(color_image.get_width_pixels());
54 auto ch =
static_cast<unsigned int>(color_image.get_height_pixels());
57 auto color_buffer =
reinterpret_cast<const unsigned char*
>(color_image.get_buffer());
58 auto rgb_buffer_ivt = result.pixels;
62 for (
unsigned int y = 0; y < ch; ++y)
64 for (
unsigned int x = 0; x < cw; ++x)
66 rgb_buffer_ivt[index_ivt] =
float(color_buffer[index_k4a] + color_buffer[index_k4a + 1]) / 2.f;
94 const uint32_t DEVICE_COUNT = k4a::device::get_installed_count();
95 if (DEVICE_COUNT == 0)
98 throw armarx::LocalException(
"No Azure Kinect devices detected!");
101 device = k4a::device::open(K4A_DEVICE_DEFAULT);
102 k4aCalibration = device.get_calibration(config.depth_mode, config.color_resolution);
104 transformation = k4a::transformation(k4aCalibration);
106 device.start_cameras(&config);
122 const std::chrono::milliseconds TIMEOUT{1000};
129 catch (
const std::exception&)
131 ARMARX_WARNING <<
"Failed to get capture from device. Restarting camera.";
133 device.stop_cameras();
134 device.start_cameras(&config);
135 ARMARX_INFO <<
"Restarting took " << sw.stop() <<
".";
143 const k4a::image irImage =
capture.get_ir_image();
144 CByteImage buffer(depthDim.first, depthDim.second, CByteImage::eGrayScale);
145 k4aToIvtImage(irImage, buffer);
147 std::memcpy(pp_image_buffers[0], buffer.pixels, 1024 * 1024);
159 return "AzureKinectIRImageProvider";
165 config = K4A_DEVICE_CONFIG_INIT_DISABLE_ALL;
166 auto fps = getProperty<float>(
"framerate").getValue();
169 config.camera_fps = K4A_FRAMES_PER_SECOND_5;
171 else if (fps == 15.0f)
173 config.camera_fps = K4A_FRAMES_PER_SECOND_15;
175 else if (fps == 30.0f)
177 config.camera_fps = K4A_FRAMES_PER_SECOND_30;
181 throw armarx::LocalException(
"Invalid framerate: ") << fps <<
" - Only framerates 5, 15 and 30 are "
182 <<
"supported by Azure Kinect.";
185 config.depth_mode = K4A_DEPTH_MODE_PASSIVE_IR;
186 config.color_format = K4A_IMAGE_FORMAT_COLOR_BGRA32;
187 config.color_resolution = K4A_COLOR_RESOLUTION_1080P;
191 config.synchronized_images_only =
true;
196 ARMARX_INFO <<
"Depth image size: " << depthDim.first <<
"x" << depthDim.second;
197 ARMARX_INFO <<
"Color image size: " << color_dim.first <<
"x" << color_dim.second;
200 visionx::ImageDimension(depthDim.first, depthDim.second),
202 visionx::eBayerPatternGr);
218 return std::string();
230 using namespace Eigen;
234 const auto convert_calibration = [](
const k4a_calibration_camera_t& k4a_calib,
237 MonocularCalibration calibration;
239 const k4a_calibration_intrinsic_parameters_t& params = k4a_calib.intrinsics.parameters;
240 calibration.cameraParam.principalPoint = {params.param.cx * scale,
241 params.param.cy* scale
243 calibration.cameraParam.focalLength = {params.param.fx * scale,
244 params.param.fy* scale
258 calibration.cameraParam.distortion = { params.param.k1, params.param.k2,
259 params.param.p1, params.param.p2,
261 calibration.cameraParam.width = k4a_calib.resolution_width;
262 calibration.cameraParam.height = k4a_calib.resolution_height;
264 Map<const Matrix3fRowMajor> {k4a_calib.extrinsics.rotation};
266 calibration.cameraParam.translation = { k4a_calib.extrinsics.translation,
267 k4a_calib.extrinsics.translation + 3
273 StereoCalibration calibration;
275 calibration.calibrationLeft = calibration.calibrationRight = convert_calibration(k4aCalibration.color_camera_calibration);