10 #define MIN_DISTANCE 1e-6 20 if (archive)
return archive->get_sensor();
39 const int w = ptr->get_width(),
h = ptr->get_height();
40 int x =
std::min(std::max(
int(u*w + .5
f), 0), w - 1);
42 int idx = x * ptr->get_bpp() / 8 + y * ptr->get_stride();
43 const auto texture_data =
reinterpret_cast<const uint8_t*
>(ptr->get_frame_data());
44 return std::make_tuple(texture_data[idx], texture_data[idx + 1], texture_data[idx + 2]);
54 const auto vertices = get_vertices();
55 const auto texcoords = get_texture_coordinates();
56 std::vector<float3> new_vertices;
57 std::vector<std::tuple<uint8_t, uint8_t, uint8_t>> new_tex;
58 std::map<int, int> index2reducedIndex;
60 new_vertices.reserve(get_vertex_count());
61 new_tex.reserve(get_vertex_count());
62 assert(get_vertex_count());
63 for (
int i = 0;
i < get_vertex_count(); ++
i)
67 index2reducedIndex[
i] = (int)new_vertices.size();
72 new_tex.push_back(
color);
78 std::vector<std::tuple<int, int, int>> faces;
83 auto a = y * width +
x,
b = y * width + x + 1,
c = (y + 1)*width + x,
d = (y + 1)*width + x + 1;
88 if (index2reducedIndex.count(
a) == 0 || index2reducedIndex.count(b) == 0 || index2reducedIndex.count(c) == 0 ||
89 index2reducedIndex.count(
d) == 0)
92 faces.emplace_back(index2reducedIndex[
a], index2reducedIndex[
d], index2reducedIndex[b]);
93 faces.emplace_back(index2reducedIndex[d], index2reducedIndex[a], index2reducedIndex[c]);
98 std::ofstream
out(fname);
100 out <<
"format binary_little_endian 1.0\n";
101 out <<
"comment pointcloud saved from Realsense Viewer\n";
102 out <<
"element vertex " << new_vertices.size() <<
"\n";
103 out <<
"property float" <<
sizeof(float) * 8 <<
" x\n";
104 out <<
"property float" <<
sizeof(float) * 8 <<
" y\n";
105 out <<
"property float" <<
sizeof(float) * 8 <<
" z\n";
108 out <<
"property uchar red\n";
109 out <<
"property uchar green\n";
110 out <<
"property uchar blue\n";
112 out <<
"element face " << faces.size() <<
"\n";
113 out <<
"property list uchar int vertex_indices\n";
114 out <<
"end_header\n";
118 for (
int i = 0;
i < new_vertices.size(); ++
i)
121 out.write(reinterpret_cast<const char*>(&(new_vertices[
i].x)),
sizeof(
float));
122 out.write(reinterpret_cast<const char*>(&(new_vertices[
i].y)),
sizeof(
float));
123 out.write(reinterpret_cast<const char*>(&(new_vertices[
i].z)),
sizeof(
float));
128 std::tie(x, y, z) = new_tex[
i];
129 out.write(reinterpret_cast<const char*>(&x),
sizeof(
uint8_t));
130 out.write(reinterpret_cast<const char*>(&y),
sizeof(
uint8_t));
131 out.write(reinterpret_cast<const char*>(&z),
sizeof(
uint8_t));
134 auto size = faces.size();
135 for (
int i = 0;
i <
size; ++
i) {
137 out.write(reinterpret_cast<const char*>(&three),
sizeof(
uint8_t));
138 out.write(reinterpret_cast<const char*>(&(std::get<0>(faces[
i]))),
sizeof(
int));
139 out.write(reinterpret_cast<const char*>(&(std::get<1>(faces[i]))),
sizeof(
int));
140 out.write(reinterpret_cast<const char*>(&(std::get<2>(faces[i]))),
sizeof(
int));
153 auto ijs = (
float2*)(
xyz + get_vertex_count());
159 std::atomic<uint32_t>* in_max_frame_queue_size,
160 std::shared_ptr<platform::time_service> ts,
161 std::shared_ptr<metadata_parser_map> parsers)
166 return std::make_shared<frame_archive<video_frame>>(in_max_frame_queue_size, ts, parsers);
169 return std::make_shared<frame_archive<composite_frame>>(in_max_frame_queue_size, ts, parsers);
172 return std::make_shared<frame_archive<motion_frame>>(in_max_frame_queue_size, ts, parsers);
175 return std::make_shared<frame_archive<points>>(in_max_frame_queue_size, ts, parsers);
178 return std::make_shared<frame_archive<depth_frame>>(in_max_frame_queue_size, ts, parsers);
181 return std::make_shared<frame_archive<pose_frame>>(in_max_frame_queue_size, ts, parsers);
184 return std::make_shared<frame_archive<disparity_frame>>(in_max_frame_queue_size, ts, parsers);
187 throw std::runtime_error(
"Requested frame type is not supported!");
197 owner->unpublish_frame(
this);
203 if (!
_kept.exchange(
true))
205 owner->keep_frame(
this);
213 return owner->publish_frame(
this);
225 <<
" attribute is not applicable for " 229 bool value_retrieved =
false;
231 for (
auto it = parsers.first;
it != parsers.second; ++
it)
235 result =
it->second->get(*
this);
236 value_retrieved =
true;
244 if (!value_retrieved)
261 for (
auto it = found.first;
it != found.second; ++
it)
262 if (
it->second->supports(*
this))
273 return (
int)
data.size();
326 auto callback_warning_duration = 1000.f / (
get_stream()->get_framerate() + 1);
330 << std::dec <<
get_frame_number() <<
",DispatchedAt," << std::fixed << timestamp);
332 if (callback_duration > callback_warning_duration)
336 <<
"overdue. (Duration: " << callback_duration
337 <<
"ms, FPS: " <<
get_stream()->get_framerate() <<
", Max Duration: " << callback_warning_duration <<
"ms)");
std::shared_ptr< stream_profile_interface > get_stream() const override
bool supports_frame_metadata(const rs2_frame_metadata_value &frame_metadata) const override
GLboolean GLboolean GLboolean b
const char * get_string(rs2_rs400_visual_preset value)
std::atomic< int > ref_count
float2 * get_texture_coordinates()
std::shared_ptr< archive_interface > make_archive(rs2_extension type, std::atomic< uint32_t > *in_max_frame_queue_size, std::shared_ptr< platform::time_service > ts, std::shared_ptr< metadata_parser_map > parsers)
const void * get_data() const
uint32_t get_height() const override
rs2_time_t frame_callback_started
unsigned long long get_frame_number() const override
std::shared_ptr< archive_interface > owner
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
void export_to_ply(const std::string &fname, const frame_holder &texture)
void unpublish() override
archive_interface * get_owner() const override
void log_callback_end(rs2_time_t timestamp) const override
GLfloat GLfloat GLfloat GLfloat h
frame_additional_data additional_data
GLboolean GLboolean GLboolean GLboolean a
rs2_timestamp_domain get_frame_timestamp_domain() const override
int get_frame_data_size() const override
unsigned long long frame_number
rs2_time_t get_frame_callback_start_time_point() const override
uint32_t get_width() const override
void set_sensor(std::shared_ptr< sensor_interface > s) override
size_t get_vertex_count() const
std::shared_ptr< metadata_parser_map > metadata_parsers
frame_continuation on_release
LOG_INFO("Log message using LOG_INFO()")
void log_callback_start(rs2_time_t timestamp) override
std::weak_ptr< sensor_interface > sensor
frame_interface * publish(std::shared_ptr< archive_interface > new_owner) override
static const struct @18 vertices[3]
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
void update_frame_callback_start_ts(rs2_time_t ts) override
long long rs2_metadata_type
const char * what() const noexceptoverride
rs2_timestamp_domain timestamp_domain
const GLuint GLenum const void * binary
std::shared_ptr< sensor_interface > get_sensor() const override
const byte * get_frame_data() const override
rs2_time_t get_frame_system_time() const override
std::tuple< uint8_t, uint8_t, uint8_t > get_texcolor(const frame_holder &texture, float u, float v)
rs2_time_t get_frame_timestamp() const override
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
rs2_metadata_type get_frame_metadata(const rs2_frame_metadata_value &frame_metadata) const override
std::string to_string(T value)
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.