4 #include "../include/librealsense2/hpp/rs_sensor.hpp" 5 #include "../include/librealsense2/hpp/rs_processing.hpp" 17 template<
class GET_DEPTH,
class TRANSFER_PIXEL>
19 const rs2_intrinsics& other_intrin, GET_DEPTH get_depth, TRANSFER_PIXEL transfer_pixel)
22 #pragma omp parallel for schedule(dynamic) 23 for (
int depth_y = 0; depth_y < depth_intrin.
height; ++depth_y)
25 int depth_pixel_index = depth_y * depth_intrin.
width;
26 for (
int depth_x = 0; depth_x < depth_intrin.
width; ++depth_x, ++depth_pixel_index)
29 if (
float depth = get_depth(depth_pixel_index))
32 float depth_pixel[2] = { depth_x - 0.5f, depth_y - 0.5f }, depth_point[3], other_point[3], other_pixel[2];
36 const int other_x0 =
static_cast<int>(other_pixel[0] + 0.5f);
37 const int other_y0 =
static_cast<int>(other_pixel[1] + 0.5f);
40 depth_pixel[0] = depth_x + 0.5f; depth_pixel[1] = depth_y + 0.5f;
44 const int other_x1 =
static_cast<int>(other_pixel[0] + 0.5f);
45 const int other_y1 =
static_cast<int>(other_pixel[1] + 0.5f);
47 if (other_x0 < 0 || other_y0 < 0 || other_x1 >= other_intrin.
width || other_y1 >= other_intrin.
height)
51 for (
int y = other_y0;
y <= other_y1; ++
y)
53 for (
int x = other_x0;
x <= other_x1; ++
x)
55 transfer_pixel(depth_pixel_index,
y * other_intrin.
width +
x);
69 byte* aligned_data =
reinterpret_cast<byte*
>(
const_cast<void*
>(aligned.
get_data()));
71 memset(aligned_data, 0, aligned_profile.height() * aligned_profile.width() * aligned.
get_bytes_per_pixel());
77 auto z_to_other = depth_profile.get_extrinsics_to(other_profile);
80 auto out_z = (
uint16_t *)(aligned_data);
83 [z_pixels, z_scale](
int z_pixel_index) {
return z_scale * z_pixels[z_pixel_index]; },
84 [out_z, z_pixels](
int z_pixel_index,
int other_pixel_index)
86 out_z[other_pixel_index] = out_z[other_pixel_index] ?
87 std::min((
int)out_z[other_pixel_index], (
int)z_pixels[z_pixel_index]) :
88 z_pixels[z_pixel_index];
92 template<
int N,
class GET_DEPTH>
95 auto in_other = (
const bytes<N> *)(other_pixels);
96 auto out_other = (
bytes<N> *)(other_aligned_to_depth);
97 align_images(depth_intrin, depth_to_other, other_intrin, get_depth,
98 [out_other, in_other](
int depth_pixel_index,
int other_pixel_index) { out_other[depth_pixel_index] = in_other[other_pixel_index]; });
101 template<
class GET_DEPTH>
104 switch (other_format)
107 align_other_to_depth_bytes<1>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
111 align_other_to_depth_bytes<2>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
115 align_other_to_depth_bytes<3>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
119 align_other_to_depth_bytes<4>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
128 byte* aligned_data =
reinterpret_cast<byte*
>(
const_cast<void*
>(aligned.
get_data()));
130 memset(aligned_data, 0, aligned_profile.height() * aligned_profile.width() * aligned.
get_bytes_per_pixel());
137 auto z_to_other = depth_profile.get_extrinsics_to(other_profile);
140 auto other_pixels =
reinterpret_cast<const byte*
>(other.
get_data());
142 align_other_to_depth(aligned_data, [z_pixels, z_scale](
int z_pixel_index) {
return z_scale * z_pixels[z_pixel_index]; },
143 z_intrin, z_to_other, other_intrin, other_pixels, other_profile.
format());
156 auto aligned_profile = std::make_shared<rs2::video_stream_profile>(original_profile.
clone(original_profile.
stream_type(), original_profile.
stream_index(), original_profile.
format()));
157 aligned_profile->get()->profile->set_framerate(original_profile.
fps());
158 if (
auto original_video_profile = As<video_stream_profile_interface>(original_profile.
get()->
profile))
160 if (
auto to_video_profile = As<video_stream_profile_interface>(to_profile.
get()->
profile))
162 if (
auto aligned_video_profile = As<video_stream_profile_interface>(aligned_profile->get()->profile))
164 aligned_video_profile->set_dims(to_video_profile->get_width(), to_video_profile->get_height());
165 auto aligned_intrinsics = to_video_profile->get_intrinsics();
166 aligned_intrinsics.width = to_video_profile->get_width();
167 aligned_intrinsics.height = to_video_profile->get_height();
168 aligned_video_profile->set_intrinsics([aligned_intrinsics]() {
return aligned_intrinsics; });
169 aligned_profile->register_extrinsics_to(to_profile, { { 1,0,0,0,1,0,0,0,1 },{ 0,0,0 } });
175 return aligned_profile;
193 bool has_tex =
false, has_depth =
false;
195 set.foreach_rs([&has_depth](
const rs2::frame& frame)
197 if (!has_tex || !has_depth)
224 from_bytes_per_pixel,
252 std::vector<rs2::frame> output_frames;
253 std::vector<rs2::frame> other_frames;
267 for (
auto from : other_frames)
271 output_frames.push_back(aligned_frame);
276 auto to = other_frames.front();
279 output_frames.push_back(aligned_frame);
283 return new_composite;
std::map< std::pair< stream_profile_interface *, stream_profile_interface * >, std::shared_ptr< rs2::video_stream_profile > > _align_stream_unique_ids
stream_profile clone(rs2_stream type, int index, rs2_format format, int width, int height, const rs2_intrinsics &intr) const
int get_bytes_per_pixel() const
GLsizei GLsizei GLchar * source
rs2_format format() const
virtual void align_other_to_z(rs2::video_frame &aligned, const rs2::video_frame &depth, const rs2::video_frame &other, float z_scale)
GLint GLint GLsizei GLsizei GLsizei depth
virtual void reset_cache(rs2_stream from, rs2_stream to)
frame allocate_video_frame(const stream_profile &profile, const frame &original, int new_bpp=0, int new_width=0, int new_height=0, int new_stride=0, rs2_extension frame_type=RS2_EXTENSION_VIDEO_FRAME) const
virtual void align_z_to_other(rs2::video_frame &aligned, const rs2::video_frame &depth, const rs2::video_stream_profile &other_profile, float z_scale)
#define assert(condition)
bool should_process(const rs2::frame &frame) override
GLint GLint GLsizei GLint GLenum format
void rs2_project_point_to_pixel(float pixel[2], const rs2_intrinsics *intrin, const float point[3])
void align_frames(rs2::video_frame &aligned, const rs2::video_frame &from, const rs2::video_frame &to)
virtual rs2_extension select_extension(const rs2::frame &input)
rs2_format
A stream's format identifies how binary data is encoded within a frame.
rs2::frame process_frame(const rs2::frame_source &source, const rs2::frame &f) override
rs2_stream
Streams are different types of data provided by RealSense devices.
const rs2_stream_profile * get() const
librealsense::stream_profile_interface * profile
GLboolean GLboolean GLboolean b
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
const void * get_data() const
void align_other_to_depth_bytes(byte *other_aligned_to_depth, GET_DEPTH get_depth, const rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, const byte *other_pixels)
rs2_stream _to_stream_type
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
stream_profile to_profile(const stream_profile_interface *sp)
std::shared_ptr< rs2::video_stream_profile > create_aligned_profile(rs2::video_stream_profile &original_profile, rs2::video_stream_profile &to_profile)
void align_images(const rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, GET_DEPTH get_depth, TRANSFER_PIXEL transfer_pixel)
typename ::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
void rs2_deproject_pixel_to_point(float point[3], const rs2_intrinsics *intrin, const float pixel[2], float depth)
void align_other_to_depth(byte *other_aligned_to_depth, GET_DEPTH get_depth, const rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, const byte *other_pixels, rs2_format other_format)
rs2_stream stream_type() const
align(rs2_stream to_stream)
rs2_intrinsics get_intrinsics() const
void rs2_transform_point_to_point(float to_point[3], const rs2_extrinsics *extrin, const float from_point[3])
stream_profile get_profile() const
frame allocate_composite_frame(std::vector< frame > frames) const
rs2::video_frame allocate_aligned_frame(const rs2::frame_source &source, const rs2::video_frame &from, const rs2::video_frame &to)