97 std::unique_lock<std::mutex> u(
m_delegate.m_sampleLock);
102 if (
m_delegate.m_cameraType == ST::StructureCoreCameraType::Color)
104 reinterpret_cast<unsigned char *
>(rgb.
bitmap),
111 reinterpret_cast<unsigned char *
>(rgb.
bitmap),
115 reinterpret_cast<unsigned char *
>(rgb.
bitmap),
120 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
136 vpColVector *gyroscope_data,
bool undistorted,
double *ts)
138 std::unique_lock<std::mutex> u(
m_delegate.m_sampleLock);
141 if (rgb !=
nullptr &&
m_delegate.m_visibleFrame.isValid()) {
143 if (
m_delegate.m_cameraType == ST::StructureCoreCameraType::Color)
145 reinterpret_cast<unsigned char *
>(rgb->
bitmap),
152 reinterpret_cast<unsigned char *
>(rgb->
bitmap),
156 reinterpret_cast<unsigned char *
>(rgb->
bitmap),
161 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
165 memcpy((
unsigned char *)
depth->bitmap,
m_delegate.m_depthFrame.convertDepthToRgba(),
168 if (acceleration_data !=
nullptr) {
169 ST::Acceleration accel =
m_delegate.m_accelerometerEvent.acceleration();
170 acceleration_data[0] = accel.x;
171 acceleration_data[1] = accel.y;
172 acceleration_data[2] = accel.z;
175 if (gyroscope_data !=
nullptr) {
176 ST::RotationRate gyro_data =
m_delegate.m_gyroscopeEvent.rotationRate();
177 gyroscope_data[0] = gyro_data.x;
178 gyroscope_data[1] = gyro_data.y;
179 gyroscope_data[2] = gyro_data.z;
183 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
198 vpColVector *gyroscope_data,
bool undistorted,
double *ts)
200 std::unique_lock<std::mutex> u(
m_delegate.m_sampleLock);
203 if (gray !=
nullptr &&
m_delegate.m_visibleFrame.isValid()) {
210 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
214 memcpy((
unsigned char *)
depth->bitmap,
m_delegate.m_depthFrame.convertDepthToRgba(),
217 if (acceleration_data !=
nullptr) {
218 ST::Acceleration accel =
m_delegate.m_accelerometerEvent.acceleration();
219 acceleration_data[0] = accel.x;
220 acceleration_data[1] = accel.y;
221 acceleration_data[2] = accel.z;
224 if (gyroscope_data !=
nullptr) {
225 ST::RotationRate gyro_data =
m_delegate.m_gyroscopeEvent.rotationRate();
226 gyroscope_data[0] = gyro_data.x;
227 gyroscope_data[1] = gyro_data.y;
228 gyroscope_data[2] = gyro_data.z;
232 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
249 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
253 std::unique_lock<std::mutex> u(
m_delegate.m_sampleLock);
256 if (
m_delegate.m_depthFrame.isValid() && data_depth !=
nullptr)
257 memcpy(data_depth,
m_delegate.m_depthFrame.depthInMillimeters(),
260 if (
m_delegate.m_visibleFrame.isValid() && data_image !=
nullptr) {
261 if (
m_delegate.m_cameraType == ST::StructureCoreCameraType::Color)
263 reinterpret_cast<unsigned char *
>(data_image),
270 reinterpret_cast<unsigned char *
>(data_image),
274 reinterpret_cast<unsigned char *
>(data_image),
279 if (
m_delegate.m_infraredFrame.isValid() && data_infrared !=
nullptr)
280 memcpy(data_infrared,
m_delegate.m_infraredFrame.data(),
283 if (data_pointCloud !=
nullptr)
286 if (acceleration_data !=
nullptr) {
287 ST::Acceleration accel =
m_delegate.m_accelerometerEvent.acceleration();
288 acceleration_data[0] = accel.x;
289 acceleration_data[1] = accel.y;
290 acceleration_data[2] = accel.z;
293 if (gyroscope_data !=
nullptr) {
294 ST::RotationRate gyro_data =
m_delegate.m_gyroscopeEvent.rotationRate();
295 gyroscope_data[0] = gyro_data.x;
296 gyroscope_data[1] = gyro_data.y;
297 gyroscope_data[2] = gyro_data.z;
301 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
320 std::vector<vpColVector> *
const data_pointCloud,
321 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
unsigned char *
const data_infrared,
325 std::unique_lock<std::mutex> u(
m_delegate.m_sampleLock);
329 if (
m_delegate.m_cameraType == ST::StructureCoreCameraType::Color)
331 reinterpret_cast<unsigned char *
>(data_image),
338 reinterpret_cast<unsigned char *
>(data_image),
342 reinterpret_cast<unsigned char *
>(data_image),
347 if (
m_delegate.m_depthFrame.isValid() && data_depth !=
nullptr)
348 memcpy(data_depth,
m_delegate.m_depthFrame.depthInMillimeters(),
351 if (
m_delegate.m_infraredFrame.isValid() && data_infrared !=
nullptr)
352 memcpy(data_infrared,
m_delegate.m_infraredFrame.data(),
355 if (data_pointCloud !=
nullptr)
358 if (
m_delegate.m_depthFrame.isValid() && pointcloud !=
nullptr)
361 if (acceleration_data !=
nullptr) {
362 ST::Acceleration accel =
m_delegate.m_accelerometerEvent.acceleration();
363 acceleration_data[0] = accel.x;
364 acceleration_data[1] = accel.y;
365 acceleration_data[2] = accel.z;
368 if (gyroscope_data !=
nullptr) {
369 ST::RotationRate gyro_data =
m_delegate.m_gyroscopeEvent.rotationRate();
370 gyroscope_data[0] = gyro_data.x;
371 gyroscope_data[1] = gyro_data.y;
372 gyroscope_data[2] = gyro_data.z;
376 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
394 std::vector<vpColVector> *
const data_pointCloud,
395 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
396 unsigned char *
const data_infrared,
vpColVector *acceleration_data,
397 vpColVector *gyroscope_data,
bool undistorted,
double *ts)
399 std::unique_lock<std::mutex> u(
m_delegate.m_sampleLock);
402 if (
m_delegate.m_depthFrame.isValid() && data_depth !=
nullptr)
403 memcpy(data_depth,
m_delegate.m_depthFrame.depthInMillimeters(),
406 if (
m_delegate.m_visibleFrame.isValid() && data_image !=
nullptr) {
407 if (
m_delegate.m_cameraType == ST::StructureCoreCameraType::Color)
409 reinterpret_cast<unsigned char *
>(data_image),
416 reinterpret_cast<unsigned char *
>(data_image),
420 reinterpret_cast<unsigned char *
>(data_image),
425 if (
m_delegate.m_infraredFrame.isValid() && data_infrared !=
nullptr)
426 memcpy(data_infrared,
m_delegate.m_infraredFrame.data(),
429 if (
m_delegate.m_depthFrame.isValid() && data_pointCloud !=
nullptr)
432 if (
m_delegate.m_depthFrame.isValid() &&
m_delegate.m_visibleFrame.isValid() && pointcloud !=
nullptr)
435 if (acceleration_data !=
nullptr) {
436 ST::Acceleration accel =
m_delegate.m_accelerometerEvent.acceleration();
437 acceleration_data[0] = accel.x;
438 acceleration_data[1] = accel.y;
439 acceleration_data[2] = accel.z;
442 if (gyroscope_data !=
nullptr) {
443 ST::RotationRate gyro_data =
m_delegate.m_gyroscopeEvent.rotationRate();
444 gyroscope_data[0] = gyro_data.x;
445 gyroscope_data[1] = gyro_data.y;
446 gyroscope_data[2] = gyro_data.z;
450 *ts =
m_delegate.m_visibleFrame.arrivalTimestamp();
562 std::unique_lock<std::mutex> u(
m_delegate.m_sampleLock);
564 double imu_vel_timestamp = 0., imu_acc_timestamp = 0.;
566 if (imu_vel !=
nullptr) {
567 imu_vel->
resize(3,
false);
568 ST::RotationRate imu_rotationRate =
m_delegate.m_gyroscopeEvent.rotationRate();
569 (*imu_vel)[0] = imu_rotationRate.x;
570 (*imu_vel)[1] = imu_rotationRate.y;
571 (*imu_vel)[2] = imu_rotationRate.z;
573 m_delegate.m_gyroscopeEvent.arrivalTimestamp();
576 if (imu_acc !=
nullptr) {
577 imu_acc->
resize(3,
false);
578 ST::Acceleration imu_acceleration =
m_delegate.m_accelerometerEvent.acceleration();
579 (*imu_acc)[0] = imu_acceleration.x;
580 (*imu_acc)[1] = imu_acceleration.y;
581 (*imu_acc)[2] = imu_acceleration.z;
582 imu_acc_timestamp =
m_delegate.m_accelerometerEvent.arrivalTimestamp();
586 *ts = std::max<double>(imu_vel_timestamp, imu_acc_timestamp);
757 ST::Matrix4 v_M_d =
m_delegate.m_depthFrame.visibleCameraPoseInDepthCoordinateFrame();
759 result[0][0] = v_M_d.m00;
760 result[0][1] = v_M_d.m10;
761 result[0][2] = v_M_d.m20;
762 result[0][3] = v_M_d.m30;
763 result[1][0] = v_M_d.m01;
764 result[1][1] = v_M_d.m11;
765 result[1][2] = v_M_d.m21;
766 result[1][3] = v_M_d.m31;
767 result[2][0] = v_M_d.m02;
768 result[2][1] = v_M_d.m12;
769 result[2][2] = v_M_d.m22;
770 result[2][3] = v_M_d.m32;
774 ST::Matrix4 imu_M_d =
m_captureSession.getImuFromDepthExtrinsics().inversed();
776 result[0][0] = imu_M_d.m00;
777 result[0][1] = imu_M_d.m10;
778 result[0][2] = imu_M_d.m20;
779 result[0][3] = imu_M_d.m30;
780 result[1][0] = imu_M_d.m01;
781 result[1][1] = imu_M_d.m11;
782 result[1][2] = imu_M_d.m21;
783 result[1][3] = imu_M_d.m31;
784 result[2][0] = imu_M_d.m02;
785 result[2][1] = imu_M_d.m12;
786 result[2][2] = imu_M_d.m22;
787 result[2][3] = imu_M_d.m32;
793 ST::Matrix4 d_M_v =
m_delegate.m_depthFrame.visibleCameraPoseInDepthCoordinateFrame().inversed();
795 result[0][0] = d_M_v.m00;
796 result[0][1] = d_M_v.m10;
797 result[0][2] = d_M_v.m20;
798 result[0][3] = d_M_v.m30;
799 result[1][0] = d_M_v.m01;
800 result[1][1] = d_M_v.m11;
801 result[1][2] = d_M_v.m21;
802 result[1][3] = d_M_v.m31;
803 result[2][0] = d_M_v.m02;
804 result[2][1] = d_M_v.m12;
805 result[2][2] = d_M_v.m22;
806 result[2][3] = d_M_v.m32;
810 ST::Matrix4 imu_M_v =
m_captureSession.getImuFromVisibleExtrinsics().inversed();
812 result[0][0] = imu_M_v.m00;
813 result[0][1] = imu_M_v.m10;
814 result[0][2] = imu_M_v.m20;
815 result[0][3] = imu_M_v.m30;
816 result[1][0] = imu_M_v.m01;
817 result[1][1] = imu_M_v.m11;
818 result[1][2] = imu_M_v.m21;
819 result[1][3] = imu_M_v.m31;
820 result[2][0] = imu_M_v.m02;
821 result[2][1] = imu_M_v.m12;
822 result[2][2] = imu_M_v.m22;
823 result[2][3] = imu_M_v.m32;
834 result[0][0] = d_M_imu.m00;
835 result[0][1] = d_M_imu.m10;
836 result[0][2] = d_M_imu.m20;
837 result[0][3] = d_M_imu.m30;
838 result[1][0] = d_M_imu.m01;
839 result[1][1] = d_M_imu.m11;
840 result[1][2] = d_M_imu.m21;
841 result[1][3] = d_M_imu.m31;
842 result[2][0] = d_M_imu.m02;
843 result[2][1] = d_M_imu.m12;
844 result[2][2] = d_M_imu.m22;
845 result[2][3] = d_M_imu.m32;
851 result[0][0] = v_M_imu.m00;
852 result[0][1] = v_M_imu.m10;
853 result[0][2] = v_M_imu.m20;
854 result[0][3] = v_M_imu.m30;
855 result[1][0] = v_M_imu.m01;
856 result[1][1] = v_M_imu.m11;
857 result[1][2] = v_M_imu.m21;
858 result[1][3] = v_M_imu.m31;
859 result[2][0] = v_M_imu.m02;
860 result[2][1] = v_M_imu.m12;
861 result[2][2] = v_M_imu.m22;
862 result[2][3] = v_M_imu.m32;
952 ST::DepthFrame last_df =
m_delegate.m_depthFrame;
953 const int width = last_df.width();
954 const int height = last_df.height();
955 pointcloud.resize(
static_cast<size_t>(width * height));
957 const float *p_depth_frame =
reinterpret_cast<const float *
>(last_df.depthInMillimeters());
961#pragma omp parallel for schedule(dynamic)
962 for (
int i = 0; i < height; i++) {
963 auto depth_pixel_index = i * width;
965 for (
int j = 0; j < width; j++, depth_pixel_index++) {
966 if (std::isnan(p_depth_frame[depth_pixel_index])) {
967 pointcloud[
static_cast<size_t>(depth_pixel_index)].resize(4,
false);
971 pointcloud[
static_cast<size_t>(depth_pixel_index)][3] = 1.0;
976 auto pixels_distance = p_depth_frame[depth_pixel_index];
978 ST::Vector3f point_3D = last_df.unprojectPoint(i, j);
980 if (pixels_distance >
m_maxZ)
983 pointcloud[
static_cast<size_t>(depth_pixel_index)].resize(4,
false);
984 pointcloud[
static_cast<size_t>(depth_pixel_index)][0] = point_3D.x * 0.001;
985 pointcloud[
static_cast<size_t>(depth_pixel_index)][1] = point_3D.y * 0.001;
986 pointcloud[
static_cast<size_t>(depth_pixel_index)][2] = point_3D.z * 0.001;
987 pointcloud[
static_cast<size_t>(depth_pixel_index)][3] = 1.0;
995 ST::DepthFrame last_df =
m_delegate.m_depthFrame;
996 const int width = last_df.width();
997 const int height = last_df.height();
998 pointcloud->width =
static_cast<uint32_t
>(width);
999 pointcloud->height =
static_cast<uint32_t
>(height);
1000 pointcloud->resize(
static_cast<size_t>(width * height));
1002#if MANUAL_POINTCLOUD
1003 const float *p_depth_frame =
reinterpret_cast<const float *
>(last_df.depthInMillimeters());
1007#pragma omp parallel for schedule(dynamic)
1008 for (
int i = 0; i < height; i++) {
1009 auto depth_pixel_index = i * width;
1011 for (
int j = 0; j < width; j++, depth_pixel_index++) {
1012 if (p_depth_frame[depth_pixel_index] == 0) {
1020 auto pixels_distance = p_depth_frame[depth_pixel_index];
1023 ST::Vector3f point_3D = last_df.unprojectPoint(i, j);
1025 if (pixels_distance >
m_maxZ)
1028 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].x = point_3D.x * 0.001;
1029 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].y = point_3D.y * 0.001;
1030 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].z = point_3D.z * 0.001;
1053 ST::DepthFrame last_df =
m_delegate.m_depthFrame;
1054 ST::ColorFrame last_cf =
m_delegate.m_visibleFrame;
1056 const int depth_width = last_df.width();
1057 const int depth_height = last_df.height();
1058 pointcloud->width =
static_cast<uint32_t
>(depth_width);
1059 pointcloud->height =
static_cast<uint32_t
>(depth_height);
1060 pointcloud->resize(
static_cast<uint32_t
>(depth_width * depth_height));
1062 const int color_width = last_cf.width();
1063 const int color_height = last_cf.height();
1065 const float *p_depth_frame =
reinterpret_cast<const float *
>(last_df.depthInMillimeters());
1066 const ST::Matrix4 depth2ColorExtrinsics = last_df.visibleCameraPoseInDepthCoordinateFrame();
1068 const bool swap_rb =
false;
1069 unsigned int nb_color_pixel = 3;
1070 const uint8_t *p_color_frame =
static_cast<const uint8_t *
>(last_cf.rgbData());
1072 const bool registered_streams = last_df.isRegisteredTo(last_cf);
1076#pragma omp parallel for schedule(dynamic)
1077 for (
int i = 0; i < depth_height; i++) {
1078 auto depth_pixel_index = i * depth_width;
1080 for (
int j = 0; j < depth_width; j++, depth_pixel_index++) {
1081 if (std::isnan(p_depth_frame[depth_pixel_index])) {
1087#if (VISP_HAVE_PCL_VERSION < 0x010100)
1088 unsigned int r = 0, g = 0, b = 0;
1089 uint32_t rgb = (
static_cast<uint32_t
>(r) << 16 |
static_cast<uint32_t
>(g) << 8 |
static_cast<uint32_t
>(b));
1091 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].rgb = *
reinterpret_cast<float *
>(&rgb);
1093 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].r = (uint8_t)0;
1094 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].g = (uint8_t)0;
1095 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].b = (uint8_t)0;
1101 auto pixels_distance = p_depth_frame[depth_pixel_index];
1103 ST::Vector3f depth_point_3D = last_df.unprojectPoint(i, j);
1105 if (pixels_distance >
m_maxZ) {
1109 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].x = depth_point_3D.x * 0.001;
1110 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].y = depth_point_3D.y * 0.001;
1111 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].z = depth_point_3D.z * 0.001;
1113 if (!registered_streams) {
1115 ST::Vector3f color_point_3D = depth2ColorExtrinsics * depth_point_3D;
1117 ST::Vector2f color_pixel;
1120 if (color_point_3D.z != 0) {
1121 double x, y, pixel_x = 0., pixel_y = 0.;
1122 x =
static_cast<double>(color_point_3D.y / color_point_3D.z);
1123 y =
static_cast<double>(color_point_3D.x / color_point_3D.z);
1125 color_pixel.x = pixel_x;
1126 color_pixel.y = pixel_y;
1129 if (color_pixel.y < 0 || color_pixel.y >= color_height || color_pixel.x < 0 || color_pixel.x >= color_width) {
1131#if (VISP_HAVE_PCL_VERSION < 0x010100)
1132 unsigned int r = 0, g = 0, b = 0;
1133 uint32_t rgb = (
static_cast<uint32_t
>(r) << 16 |
static_cast<uint32_t
>(g) << 8 |
static_cast<uint32_t
>(b));
1135 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].rgb = *
reinterpret_cast<float *
>(&rgb);
1137 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].r = (uint8_t)0;
1138 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].g = (uint8_t)0;
1139 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].b = (uint8_t)0;
1143 unsigned int i_ =
static_cast<unsigned int>(color_pixel.x);
1144 unsigned int j_ =
static_cast<unsigned int>(color_pixel.y);
1146#if (VISP_HAVE_PCL_VERSION < 0x010100)
1150 (
static_cast<uint32_t
>(p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel]) |
1151 static_cast<uint32_t
>(p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 1]) << 8 |
1152 static_cast<uint32_t
>(p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 2])
1157 (
static_cast<uint32_t
>(p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel]) << 16 |
1158 static_cast<uint32_t
>(p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 1]) << 8 |
1159 static_cast<uint32_t
>(p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 2]));
1162 pointcloud->points[
static_cast<size_t>(i * depth_width + j)].rgb = *
reinterpret_cast<float *
>(&rgb);
1165 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].b =
1166 p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel];
1167 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].g =
1168 p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 1];
1169 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].r =
1170 p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 2];
1173 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].r =
1174 p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel];
1175 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].g =
1176 p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 1];
1177 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].b =
1178 p_color_frame[(i_ *
static_cast<unsigned int>(color_width) + j_) * nb_color_pixel + 2];
1184#if (VISP_HAVE_PCL_VERSION < 0x010100)
1187 rgb = (
static_cast<uint32_t
>(p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel]) |
1188 static_cast<uint32_t
>(p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 1]) << 8 |
1189 static_cast<uint32_t
>(p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 2]) << 16);
1192 rgb = (
static_cast<uint32_t
>(p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel]) << 16 |
1193 static_cast<uint32_t
>(p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 1]) << 8 |
1194 static_cast<uint32_t
>(p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 2]));
1197 pointcloud->points[
static_cast<size_t>(i * depth_width + j)].rgb = *
reinterpret_cast<float *
>(&rgb);
1200 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].b =
1201 p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel];
1202 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].g =
1203 p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 1];
1204 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].r =
1205 p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 2];
1208 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].r =
1209 p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel];
1210 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].g =
1211 p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 1];
1212 pointcloud->points[
static_cast<size_t>(depth_pixel_index)].b =
1213 p_color_frame[(i *
static_cast<unsigned int>(color_width) + j) * nb_color_pixel + 2];