9 #ifndef LIBREALSENSE_TYPES_H 10 #define LIBREALSENSE_TYPES_H 12 #include "../include/librealsense/rs.h" 13 #include "../include/librealsense/rscore.hpp" 20 #include <condition_variable> 46 std::ostringstream
ss;
59 for (
unsigned int i = 0; i < sizeof(T); ++i) reinterpret_cast<char *>(&le_value)[i] = reinterpret_cast<const char *>(&be_value)[
sizeof(T) - i - 1];
76 #define LOG(SEVERITY, ...) do { if(static_cast<int>(SEVERITY) >= rsimpl::get_minimum_severity()) { std::ostringstream ss; ss << __VA_ARGS__; rsimpl::log(SEVERITY, ss.str()); } } while(false) 77 #define LOG_DEBUG(...) LOG(RS_LOG_SEVERITY_DEBUG, __VA_ARGS__) 78 #define LOG_INFO(...) LOG(RS_LOG_SEVERITY_INFO, __VA_ARGS__) 79 #define LOG_WARNING(...) LOG(RS_LOG_SEVERITY_WARN, __VA_ARGS__) 80 #define LOG_ERROR(...) LOG(RS_LOG_SEVERITY_ERROR, __VA_ARGS__) 81 #define LOG_FATAL(...) LOG(RS_LOG_SEVERITY_FATAL, __VA_ARGS__) 87 #define RS_ENUM_HELPERS(TYPE, PREFIX) const char * get_string(TYPE value); \ 88 inline bool is_valid(TYPE value) { return value >= 0 && value < RS_##PREFIX##_COUNT; } \ 89 inline std::ostream & operator << (std::ostream & out, TYPE value) { if(is_valid(value)) return out << get_string(value); else return out << (int)value; } 103 #undef RS_ENUM_HELPERS 110 struct float3 {
float x,
y,
z;
float & operator [] (
int i) {
return (&x)[i]; } };
133 std::vector<std::pair<rs_stream, rs_format>>
outputs;
136 rs_format
get_format(
rs_stream stream)
const {
for (
auto & o : outputs)
if (o.first == stream)
return o.second;
throw std::logic_error(
"missing output"); }
174 bool is_filled()
const;
207 static std::vector<std::string> split(
const std::string& str);
214 : m_major(major), m_minor(minor), m_patch(patch), m_build(build), is_any(is_any), string_representation(
to_string()) {}
222 : m_major(parse_part(name, 0)), m_minor(parse_part(name, 1)), m_patch(parse_part(name, 2)), m_build(parse_part(name, 3)), is_any(false), string_representation(
to_string()) {}
226 if (is_any || other.
is_any)
return true;
227 if (m_major > other.
m_major)
return false;
228 if ((m_major == other.
m_major) && (m_minor > other.
m_minor))
return false;
229 if ((m_major == other.
m_major) && (m_minor == other.
m_minor) && (m_patch > other.
m_patch))
return false;
238 bool operator> (
const firmware_version& other)
const {
return !(*
this < other) || is_any; }
245 return (from <= *
this) && (*
this <= until);
248 operator const char*()
const 250 return string_representation.c_str();
262 : capability(capability), from(from), until(until), firmware_type(firmware_type) {}
304 if ((
size_t)unpacker_index < mode.
pf.
unpackers.size())
306 throw std::runtime_error(
"failed to fetch an unpakcer, most likely because enable_stream was not called!");
308 const std::vector<std::pair<rs_stream, rs_format>> &
get_outputs()
const {
return get_unpacker().outputs; }
317 void set_output_buffer_format(
const rs_output_buffer_format in_output_format);
319 void unpack(byte *
const dest[],
const byte *
source)
const;
320 int get_unpacked_width()
const;
321 int get_unpacked_height()
const;
341 operator bool() {
return fptr !=
nullptr; }
345 try { fptr(dev, frame, user); }
catch (...)
347 LOG_ERROR(
"Received an execption from frame callback!");
363 operator bool() {
return fptr !=
nullptr; }
369 try { fptr(device, data, user); }
catch (...)
371 LOG_ERROR(
"Received an execption from motion events callback!");
388 operator bool() {
return fptr !=
nullptr; }
392 try { fptr(device, data, user); }
catch (...)
394 LOG_ERROR(
"Received an execption from timestamp events callback!");
409 operator bool() {
return fptr !=
nullptr; }
415 try { fptr(severity, message, user); }
418 LOG_ERROR(
"Received an execption from log callback!");
438 if (callback) callback->
release();
439 callback = other.callback;
440 other.callback =
nullptr;
464 bool all_requests_filled(
const stream_request(&original_requests)[RS_STREAM_NATIVE_COUNT])
const;
465 bool find_good_requests_combination(
stream_request(&output_requests)[RS_STREAM_NATIVE_COUNT], std::vector<stream_request> stream_requests[RS_STREAM_NATIVE_COUNT])
const;
466 bool fill_requests(
stream_request(&requests)[RS_STREAM_NATIVE_COUNT])
const;
467 void get_all_possible_requestes(std::vector<stream_request> (&stream_requests)[RS_STREAM_NATIVE_COUNT])
const;
468 std::vector<subdevice_mode_selection> select_modes(
const stream_request(&requests)[RS_STREAM_NATIVE_COUNT])
const;
470 bool validate_requests(
stream_request(&requests)[RS_STREAM_NATIVE_COUNT],
bool throw_exception =
false)
const;
479 return{ i.
width + pad_crop * 2, i.
height + pad_crop * 2, i.
ppx + pad_crop, i.
ppy + pad_crop, i.
fx, i.
fy, i.
model, {i.
coeffs[0], i.
coeffs[1], i.
coeffs[2], i.
coeffs[3], i.
coeffs[4]} };
484 const float sx = (float)width / i.
width, sy = (
float)height / i.
height;
485 return{
width,
height, i.
ppx*sx, i.
ppy*sy, i.
fx*sx, i.
fy*sy, i.
model, {i.
coeffs[0], i.
coeffs[1], i.
coeffs[2], i.
coeffs[3], i.
coeffs[4]} };
490 inline uint32_t
pack(uint8_t c0, uint8_t c1, uint8_t c2, uint8_t c3)
492 return (c0 << 24) | (c1 << 16) | (c2 << 8) | c3;
495 template<
class T,
int C>
501 bool keep_allocating =
true;
502 std::condition_variable
cv;
508 for (
auto i = 0; i < C; i++)
511 buffer[i] = std::move(T());
517 std::unique_lock<std::mutex> lock(mutex);
518 if (!keep_allocating)
return nullptr;
520 for (
auto i = 0; i < C; i++)
534 if (item < buffer || item >= buffer + C)
536 throw std::runtime_error(
"Trying to return item to a heap that didn't allocate it!");
539 buffer[i] = std::move(T());
542 std::unique_lock<std::mutex> lock(mutex);
557 std::unique_lock<std::mutex> lock(mutex);
558 keep_allocating =
false;
563 std::unique_lock<std::mutex> lock(mutex);
565 const auto ready = [
this]()
569 if (!ready() && !cv.wait_for(lock, std::chrono::hours(1000), ready))
571 throw std::runtime_error(
"Could not flush one of the user controlled objects!");
579 const void* protected_data =
nullptr;
586 explicit frame_continuation(std::function<
void()> continuation,
const void* protected_data) : continuation(continuation), protected_data(protected_data) {}
591 other.continuation = []() {};
592 other.protected_data =
nullptr;
598 continuation = []() {};
599 protected_data =
nullptr;
604 protected_data =
nullptr;
605 continuation = [](){};
608 const void*
get_data()
const {
return protected_data; }
613 protected_data = other.protected_data;
614 continuation = other.continuation;
615 other.continuation = []() {};
616 other.protected_data =
nullptr;
632 std::function<
bool(
rs_stream)> intrinsic_validator);
645 return std::find_if(data.begin(), data.end(), [](byte
b){
return b!=0; }) != data.end();
subdevice_mode_selection()
std::function< void()> continuation
to_string & operator<<(const T &val)
std::vector< rs_intrinsics > rect_modes
void timestamp_callback(rs_device *, rs_timestamp_data, void *)
bool operator<=(const firmware_version &other) const
std::unique_ptr< rs_motion_callback, void(*)(rs_motion_callback *)> motion_callback_ptr
int num_libuvc_transfer_buffers
void on_event(rs_log_severity severity, const char *message) override
bool operator==(const firmware_version &other) const
std::vector< rs_frame_metadata > supported_metadata_vector
rs_frame_callback * callback
frame_continuation(std::function< void()> continuation, const void *protected_data)
bool operator>=(const firmware_version &other) const
const int RS_USER_QUEUE_SIZE
GLint GLint GLsizei GLsizei height
rs_blob_type
Proprietary formats for direct communication with device firmware.
GLint GLint GLint GLint GLint GLint y
uint32_t pack(uint8_t c0, uint8_t c1, uint8_t c2, uint8_t c3)
void(* timestamp_callback_function_ptr)(rs_device *dev, rs_timestamp_data data, void *user)
rs_log_severity get_minimum_severity()
void motion_callback(rs_device *, rs_motion_data, void *)
float3 operator*(const float3 &a, float b)
std::vector< int > pad_crop_options
GLuint GLsizei const GLchar * message
GLsizei const GLchar *const * string
std::function< bool(rs_stream stream)> intrinsic_validator
bool provides_stream(rs_stream stream) const
const int RS_MAX_EVENT_QUEUE_SIZE
std::string string_representation
rs_intrinsics pad_crop_intrinsics(const rs_intrinsics &i, int pad_crop)
log_callback(log_callback_function_ptr fptr, void *user)
firmware_version(int major, int minor, int patch, int build, bool is_any=false)
void log_to_file(rs_log_severity min_severity, const char *file_path)
rs_option
Defines general configuration controls.
rs_output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
rs_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
bool is_between(const firmware_version &from, const firmware_version &until)
std::vector< subdevice_mode > subdevice_modes
void(* motion_callback_function_ptr)(rs_device *dev, rs_motion_data data, void *user)
rs_format get_format(rs_stream stream) const
device_config(const rsimpl::static_device_info &info)
const uint8_t RS_STREAM_NATIVE_COUNT
std::vector< supported_capability > capabilities_vector
timestamp_events_callback()
rs_intrinsics native_intrinsics
float nominal_depth_scale
frame_continuation(frame_continuation &&other)
std::string firmware_version
void log_to_console(rs_log_severity min_severity)
supported_capability(rs_capabilities capability)
float3 operator+(const float3 &a, const float3 &b)
GLuint GLuint GLsizei count
Motion data from gyroscope and accelerometer from the microcontroller.
void(* frame_callback_function_ptr)(rs_device *dev, rs_frame_ref *frame, void *user)
const void * get_data() const
frame_callback(rs_device *dev, frame_callback_function_ptr on_frame, void *user)
rs_camera_info
Read-only strings that can be queried from the device.
std::condition_variable cv
void on_event(rs_motion_data data) override
void log_to_callback(rs_log_severity min_severity, rs_log_callback *callback)
#define RS_ENUM_HELPERS(TYPE, PREFIX)
bool operator<(const firmware_version &other) const
void(* log_callback_function_ptr)(rs_log_severity severity, const char *message, void *user)
int stream_request::* field
bool check_not_all_zeros(std::vector< byte > data)
std::unique_ptr< rs_log_callback, void(*)(rs_log_callback *)> log_callback_ptr
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
void on_frame(rs_device *dev, rs_frame_ref *frame) override
supported_capability(rs_capabilities capability, firmware_version from, firmware_version until, rs_camera_info firmware_type=RS_CAMERA_INFO_CAMERA_FIRMWARE_VERSION)
std::map< rs_camera_info, std::string > camera_info
rs_format
Formats: defines how each stream can be encoded.
bool requires_processing() const
std::vector< supported_option > options
Timestamp data from the motion microcontroller.
GLboolean GLboolean GLboolean GLboolean a
bool operator!=(const firmware_version &other) const
const std::vector< std::pair< rs_stream, rs_format > > & get_outputs() const
const static_device_info info
rs_source
Source: allows you to choose between available hardware subdevices.
GLboolean GLboolean GLboolean b
typedef void(APIENTRYP PFNGLDRAWRANGEELEMENTSPROC)(GLenum mode
firmware_version(const std::string &name)
rs_preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
frame_callback_function_ptr fptr
timestamp_callback_function_ptr fptr
std::vector< subdevice_mode_selection > select_modes() const
std::unique_ptr< rs_timestamp_callback, void(*)(rs_timestamp_callback *)> timestamp_callback_ptr
pose inverse(const pose &a)
void log(rs_log_severity severity, const std::string &message)
rs_stream
Streams are different types of data provided by RealSense devices.
GLint GLint GLsizei width
GLuint const GLchar * name
std::function< bool(rs_stream from_stream, rs_stream to_stream)> extrinsic_validator
GLsizei GLsizei GLchar * source
static firmware_version any()
frame_callback_ptr(rs_frame_callback *callback)
int get_framerate() const
size_t get_image_size(int width, int height, rs_format format)
rs_log_severity
Severity of the librealsense logger.
const pixel_format_unpacker & get_unpacker() const
rs_capabilities
Specifies various capabilities of a RealSense device.
data_polling_request data_request
subdevice_mode_selection(const subdevice_mode &mode, int pad_crop, int unpacker_index)
std::vector< interstream_rule > interstream_rules
rs_output_buffer_format output_format
rs_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
float3x3 transpose(const float3x3 &a)
rs_frame_metadata
Types of value provided from the device with each frame.
rs_camera_info firmware_type
rs_intrinsics scale_intrinsics(const rs_intrinsics &i, int width, int height)
bool operator==(const float3 &a, const float3 &b)
rs_capabilities capability
rs_frame_callback * operator*()
motion_callback_function_ptr fptr
void on_event(rs_timestamp_data data) override
frame_continuation & operator=(frame_continuation &&other)
GLint GLint GLint GLint GLint x
rs_event_source
Source device that triggered a specific timestamp event from the motion module.
log_callback_function_ptr fptr
timestamp_events_callback(rs_device *dev, timestamp_callback_function_ptr fptr, void *user)
const int RS_MAX_EVENT_TIME_OUT
motion_events_callback(rs_device *dev, motion_callback_function_ptr fptr, void *user)