c_files.cpp
Go to the documentation of this file.
1 /* License: Apache 2.0. See LICENSE file in root directory.
2 Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
3 
4 #include "pyrealsense2.h"
5 #include <librealsense2/rs.h>
6 #include <iomanip>
7 
9 {
10  std::transform(begin(str), end(str), begin(str), ::tolower); //Make lower case
11  std::replace(begin(str), end(str), ' ', '_'); //replace spaces with underscore
12  if (str == "6dof") //Currently this is the only enum that starts with a digit
13  {
14  return "six_dof";
15  }
16  return str;
17 }
18 
19 
20 void init_c_files(py::module &m) {
22  BIND_ENUM(m, rs2_notification_category, RS2_NOTIFICATION_CATEGORY_COUNT, "Category of the librealsense notification.")
23  // rs2_exception_type
24  BIND_ENUM(m, rs2_distortion, RS2_DISTORTION_COUNT, "Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.")
25  BIND_ENUM(m, rs2_log_severity, RS2_LOG_SEVERITY_COUNT, "Severity of the librealsense logger.")
26  BIND_ENUM(m, rs2_extension, RS2_EXTENSION_COUNT, "Specifies advanced interfaces (capabilities) objects may implement.")
27  BIND_ENUM(m, rs2_matchers, RS2_MATCHER_COUNT, "Specifies types of different matchers.")
28  BIND_ENUM(m, rs2_camera_info, RS2_CAMERA_INFO_COUNT, "This information is mainly available for camera debug and troubleshooting and should not be used in applications.")
29  BIND_ENUM(m, rs2_stream, RS2_STREAM_COUNT, "Streams are different types of data provided by RealSense devices.")
30  BIND_ENUM(m, rs2_format, RS2_FORMAT_COUNT, "A stream's format identifies how binary data is encoded within a frame.")
31  BIND_ENUM(m, rs2_timestamp_domain, RS2_TIMESTAMP_DOMAIN_COUNT, "Specifies the clock in relation to which the frame timestamp was measured.")
32  BIND_ENUM(m, rs2_frame_metadata_value, RS2_FRAME_METADATA_COUNT, "Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame.")
33  BIND_ENUM(m, rs2_calib_target_type, RS2_CALIB_TARGET_COUNT, "Calibration target type.")
34 
35  BIND_ENUM(m, rs2_option, RS2_OPTION_COUNT+1, "Defines general configuration controls. These can generally be mapped to camera UVC controls, and can be set / queried at any time unless stated otherwise.")
36  // Without __repr__ and __str__, we get the default 'enum_base' showing '???'
37  py_rs2_option.attr( "__repr__" ) = py::cpp_function(
38  []( const py::object & arg ) -> py::str
39  {
40  auto type = py::type::handle_of( arg );
41  py::object type_name = type.attr( "__name__" );
42  py::int_ arg_int( arg );
43  py::str enum_name( rs2_option_to_string( rs2_option( (int) arg_int ) ) );
44  return py::str( "<{} {} '{}'>" ).format( std::move( type_name ), arg_int, enum_name );
45  },
46  py::name( "__repr__" ),
47  py::is_method( py_rs2_option ) );
48  py_rs2_option.attr( "__str__" ) = py::cpp_function(
49  []( const py::object & arg ) -> py::str {
50  py::int_ arg_int( arg );
51  return rs2_option_to_string( rs2_option( (int) arg_int ) );
52  },
53  py::name( "name" ),
54  py::is_method( py_rs2_option ) );
55  // Force binding of deprecated (renamed) options that we still want to expose for backwards compatibility
56  py_rs2_option.value("ambient_light", RS2_OPTION_AMBIENT_LIGHT);
57  py_rs2_option.value( "lld_temperature", RS2_OPTION_LLD_TEMPERATURE );
58 
59  m.def( "option_from_string", &rs2_option_from_string );
60 
61  BIND_ENUM(m, rs2_option_type, RS2_OPTION_TYPE_COUNT, "The different types option values can take on")
62  BIND_ENUM(m, rs2_l500_visual_preset, RS2_L500_VISUAL_PRESET_COUNT, "For L500 devices: provides optimized settings (presets) for specific types of usage.")
63  BIND_ENUM(m, rs2_rs400_visual_preset, RS2_RS400_VISUAL_PRESET_COUNT, "For D400 devices: provides optimized settings (presets) for specific types of usage.")
64  BIND_ENUM(m, rs2_playback_status, RS2_PLAYBACK_STATUS_COUNT, "") // No docsDtring in C++
65  BIND_ENUM(m, rs2_calibration_type, RS2_CALIBRATION_TYPE_COUNT, "Calibration type for use in device_calibration")
66  BIND_ENUM_CUSTOM(m, rs2_calibration_status, RS2_CALIBRATION_STATUS_FIRST, RS2_CALIBRATION_STATUS_LAST, "Calibration callback status for use in device_calibration.trigger_device_calibration")
67 
68 
69  py::class_<rs2_intrinsics> intrinsics(m, "intrinsics", "Video stream intrinsics.");
70  intrinsics.def(py::init<>())
71  .def_readwrite("width", &rs2_intrinsics::width, "Width of the image in pixels")
72  .def_readwrite("height", &rs2_intrinsics::height, "Height of the image in pixels")
73  .def_readwrite("ppx", &rs2_intrinsics::ppx, "Horizontal coordinate of the principal point of the image, as a pixel offset from the left edge")
74  .def_readwrite("ppy", &rs2_intrinsics::ppy, "Vertical coordinate of the principal point of the image, as a pixel offset from the top edge")
75  .def_readwrite("fx", &rs2_intrinsics::fx, "Focal length of the image plane, as a multiple of pixel width")
76  .def_readwrite("fy", &rs2_intrinsics::fy, "Focal length of the image plane, as a multiple of pixel height")
77  .def_readwrite("model", &rs2_intrinsics::model, "Distortion model of the image")
78  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_intrinsics, coeffs, float, 5), "Distortion coefficients")
79  .def( "__repr__",
80  []( const rs2_intrinsics & i )
81  {
82  std::ostringstream ss;
83  ss << "[ " << i.width << "x" << i.height
84  << " p[" << i.ppx << " " << i.ppy << "]"
85  << " f[" << i.fx << " " << i.fy << "]"
86  << " " << rs2_distortion_to_string( i.model ) << " [" << i.coeffs[0] << " " << i.coeffs[1] << " "
87  << i.coeffs[2] << " " << i.coeffs[3] << " " << i.coeffs[4] << "] ]";
88  return ss.str();
89  } );
90 
91  py::class_<rs2_motion_device_intrinsic> motion_device_intrinsic(m, "motion_device_intrinsic", "Motion device intrinsics: scale, bias, and variances.");
92  motion_device_intrinsic.def(py::init<>())
93  .def_property(BIND_RAW_2D_ARRAY_PROPERTY(rs2_motion_device_intrinsic, data, float, 3, 4), "3x4 matrix with 3x3 scale and cross axis and 3x1 biases")
94  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_motion_device_intrinsic, noise_variances, float, 3), "Variance of noise for X, Y, and Z axis")
95  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_motion_device_intrinsic, bias_variances, float, 3), "Variance of bias for X, Y, and Z axis")
96  .def("__repr__", [](const rs2_motion_device_intrinsic& self) {
97  std::stringstream ss;
98  ss << "data: " << matrix_to_string(self.data) << ", ";
99  ss << "noise_variances: " << array_to_string(self.noise_variances) << ", ";
100  ss << "bias_variances: " << array_to_string(self.bias_variances);
101  return ss.str();
102  });
103 
104  // rs2_vertex
105  // rs2_pixel
106 
107  py::class_<rs2_vector> vector(m, "vector", "3D vector in Euclidean coordinate space.");
108  vector.def(py::init<>())
109  .def_readwrite("x", &rs2_vector::x)
110  .def_readwrite("y", &rs2_vector::y)
111  .def_readwrite("z", &rs2_vector::z)
112  .def("__repr__", [](const rs2_vector& self) {
113  std::stringstream ss;
114  ss << "x: " << self.x << ", ";
115  ss << "y: " << self.y << ", ";
116  ss << "z: " << self.z;
117  return ss.str();
118  });
119 
120  py::class_<rs2_quaternion> quaternion(m, "quaternion", "Quaternion used to represent rotation.");
121  quaternion.def(py::init<>())
122  .def_readwrite("x", &rs2_quaternion::x)
123  .def_readwrite("y", &rs2_quaternion::y)
124  .def_readwrite("z", &rs2_quaternion::z)
125  .def_readwrite("w", &rs2_quaternion::w)
126  .def("__repr__", [](const rs2_quaternion& self) {
127  std::stringstream ss;
128  ss << "x: " << self.x << ", ";
129  ss << "y: " << self.y << ", ";
130  ss << "z: " << self.z << ", ";
131  ss << "w: " << self.w;
132  return ss.str();
133  });
134 
135  py::class_<rs2_pose> pose(m, "pose"); // No docstring in C++
136  pose.def(py::init<>())
137  .def_readwrite("translation", &rs2_pose::translation, "X, Y, Z values of translation, in meters (relative to initial position)")
138  .def_readwrite("velocity", &rs2_pose::velocity, "X, Y, Z values of velocity, in meters/sec")
139  .def_readwrite("acceleration", &rs2_pose::acceleration, "X, Y, Z values of acceleration, in meters/sec^2")
140  .def_readwrite("rotation", &rs2_pose::rotation, "Qi, Qj, Qk, Qr components of rotation as represented in quaternion rotation (relative to initial position)")
141  .def_readwrite("angular_velocity", &rs2_pose::angular_velocity, "X, Y, Z values of angular velocity, in radians/sec")
142  .def_readwrite("angular_acceleration", &rs2_pose::angular_acceleration, "X, Y, Z values of angular acceleration, in radians/sec^2")
143  .def_readwrite("tracker_confidence", &rs2_pose::tracker_confidence, "Pose confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High")
144  .def_readwrite("mapper_confidence", &rs2_pose::mapper_confidence, "Pose map confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High");
148  py::class_<rs2_extrinsics> extrinsics(m, "extrinsics", "Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.");
149  extrinsics.def(py::init<>())
150  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_extrinsics, rotation, float, 9), "Column - major 3x3 rotation matrix")
151  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_extrinsics, translation, float, 3), "Three-element translation vector, in meters")
152  .def("__repr__", [](const rs2_extrinsics &e) {
153  std::stringstream ss;
154  ss << "rotation: " << array_to_string(e.rotation);
155  ss << "\ntranslation: " << array_to_string(e.translation);
156  return ss.str();
157  });
159 }
rs2_playback_status
rs2_playback_status
Definition: rs_record_playback.h:19
librealsense::transform
float3 transform(const rs2_extrinsics *extrin, const float3 &point)
Definition: pointcloud.cpp:50
rs2_vector
3D vector in Euclidean coordinate space
Definition: rs_types.h:97
RS2_OPTION_AMBIENT_LIGHT
@ RS2_OPTION_AMBIENT_LIGHT
Definition: rs_option.h:97
BIND_ENUM
#define BIND_ENUM(module, rs2_enum_type, RS2_ENUM_COUNT, docstring)
Definition: pyrealsense2.h:20
matrix_to_string
std::string matrix_to_string(const T(&arr)[N][M])
Definition: pyrealsense2.h:72
RS2_NOTIFICATION_CATEGORY_COUNT
@ RS2_NOTIFICATION_CATEGORY_COUNT
Definition: rs_types.h:25
rs2_quaternion
Quaternion used to represent rotation
Definition: rs_types.h:103
rs2_extrinsics
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.
Definition: rs_sensor.h:102
rs2_pose::angular_velocity
rs2_vector angular_velocity
Definition: rs_types.h:114
rs2_matchers
rs2_matchers
Specifies types of different matchers.
Definition: rs_types.h:198
rs2_extension
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
Definition: rs_types.h:134
rs2_intrinsics
Video stream intrinsics.
Definition: rs_types.h:58
realsense_legacy_msgs::pose
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
Definition: third-party/realsense-file/rosbag/msgs/realsense_legacy_msgs/pose.h:88
string
GLsizei const GLchar *const * string
Definition: glad/glad/glad.h:2861
rs2_intrinsics::ppx
float ppx
Definition: rs_types.h:62
rs2_option_to_string
const char * rs2_option_to_string(rs2_option option)
Definition: to-string.cpp:770
realsense_legacy_msgs::extrinsics
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
Definition: extrinsics.h:59
rs2_intrinsics::height
int height
Definition: rs_types.h:61
BIND_ENUM_CUSTOM
#define BIND_ENUM_CUSTOM(module, rs2_enum_type, FIRST, LAST, docstring)
Definition: pyrealsense2.h:21
RS2_DISTORTION_COUNT
@ RS2_DISTORTION_COUNT
Definition: rs_types.h:53
opencv_pointcloud_viewer.rotation
rotation
Definition: opencv_pointcloud_viewer.py:320
rs2_log_severity
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:121
rs2_pose::rotation
rs2_quaternion rotation
Definition: rs_types.h:113
RS2_STREAM_COUNT
@ RS2_STREAM_COUNT
Definition: rs_sensor.h:56
test-unit-transform.coeffs
coeffs
Definition: test-unit-transform.py:28
rs2_vector::z
float z
Definition: rs_types.h:99
read_bag_example.str
str
Definition: read_bag_example.py:21
RS2_L500_VISUAL_PRESET_COUNT
@ RS2_L500_VISUAL_PRESET_COUNT
Definition: rs_option.h:219
type
GLenum type
Definition: glad/glad/glad.h:135
m
std::mutex m
Definition: test-waiting-on.cpp:126
rs2_l500_visual_preset
rs2_l500_visual_preset
For L500 devices: provides optimized settings (presets) for specific types of usage.
Definition: rs_option.h:210
rs2_format
rs2_format
A stream's format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:61
data
GLboolean * data
Definition: glad/glad/glad.h:1481
RS2_RS400_VISUAL_PRESET_COUNT
@ RS2_RS400_VISUAL_PRESET_COUNT
Definition: rs_option.h:205
rs2_motion_device_intrinsic
Motion device intrinsics: scale, bias, and variances.
Definition: rs_types.h:71
rs2_quaternion::y
float y
Definition: rs_types.h:105
RS2_EXTENSION_COUNT
@ RS2_EXTENSION_COUNT
Definition: rs_types.h:192
rs2_intrinsics::fx
float fx
Definition: rs_types.h:64
rs2_intrinsics::model
rs2_distortion model
Definition: rs_types.h:66
i
int i
Definition: rs-pcl-color.cpp:54
rs2_option_type
rs2_option_type
Defines known option value types.
Definition: rs_option.h:146
RS2_TIMESTAMP_DOMAIN_COUNT
@ RS2_TIMESTAMP_DOMAIN_COUNT
Definition: rs_frame.h:24
rs2_intrinsics::ppy
float ppy
Definition: rs_types.h:63
test-motion.bias_variances
bias_variances
Definition: sw-dev/test-motion.py:16
rs2_calib_target_type
rs2_calib_target_type
Calibration target type.
Definition: rs_frame.h:84
init_c_files
void init_c_files(py::module &m)
Definition: c_files.cpp:20
test-shorten-json.ss
string ss
Definition: test-shorten-json.py:119
rs2_option
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls,...
Definition: rs_option.h:26
rs2_vector::y
float y
Definition: rs_types.h:99
rs2_pose::velocity
rs2_vector velocity
Definition: rs_types.h:111
name
GLuint const GLchar * name
Definition: glad/glad/glad.h:2777
rs2_intrinsics::fy
float fy
Definition: rs_types.h:65
RS2_FRAME_METADATA_COUNT
@ RS2_FRAME_METADATA_COUNT
Definition: rs_frame.h:78
rs2_vector::x
float x
Definition: rs_types.h:99
RS2_MATCHER_COUNT
@ RS2_MATCHER_COUNT
Definition: rs_types.h:220
rs2_pose::angular_acceleration
rs2_vector angular_acceleration
Definition: rs_types.h:115
rs2_pose::mapper_confidence
unsigned int mapper_confidence
Definition: rs_types.h:117
RS2_CALIBRATION_TYPE_COUNT
@ RS2_CALIBRATION_TYPE_COUNT
Definition: rs_device.h:407
rs2_pose::translation
rs2_vector translation
Definition: rs_types.h:110
rs2_camera_info
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
Definition: rs_sensor.h:22
rs2_calibration_type
rs2_calibration_type
Definition: rs_device.h:402
RS2_FORMAT_COUNT
@ RS2_FORMAT_COUNT
Definition: rs_sensor.h:97
rs2_quaternion::w
float w
Definition: rs_types.h:105
rs2_rs400_visual_preset
rs2_rs400_visual_preset
For RS400 devices: provides optimized settings (presets) for specific types of usage.
Definition: rs_option.h:196
rs2_intrinsics::width
int width
Definition: rs_types.h:60
RS2_CALIB_TARGET_COUNT
@ RS2_CALIB_TARGET_COUNT
Definition: rs_frame.h:89
RS2_CALIBRATION_STATUS_FIRST
@ RS2_CALIBRATION_STATUS_FIRST
Definition: rs_device.h:429
rs2_pose::tracker_confidence
unsigned int tracker_confidence
Definition: rs_types.h:116
RS2_CAMERA_INFO_COUNT
@ RS2_CAMERA_INFO_COUNT
Definition: rs_sensor.h:38
rs2_option_from_string
rs2_option rs2_option_from_string(const char *option_name)
Definition: to-string.cpp:775
array_to_string
std::string array_to_string(const T(&arr)[N])
Definition: pyrealsense2.h:57
BIND_RAW_ARRAY_PROPERTY
#define BIND_RAW_ARRAY_PROPERTY(T, member, valueT, SIZE)
Definition: pyrealsense2.h:99
RS2_OPTION_COUNT
@ RS2_OPTION_COUNT
Definition: rs_option.h:127
realdds::topics::notification::stream_options::key::intrinsics
const std::string intrinsics
Definition: test-unit-transform.py:20
rs.h
Exposes librealsense functionality for C compilers.
rs2_pose::acceleration
rs2_vector acceleration
Definition: rs_types.h:112
rs2_quaternion::z
float z
Definition: rs_types.h:105
rs2_distortion
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
Definition: rs_types.h:45
rmse.e
e
Definition: rmse.py:177
rs2_calibration_status
rs2_calibration_status
Definition: rs_device.h:414
RS2_OPTION_TYPE_COUNT
@ RS2_OPTION_TYPE_COUNT
Definition: rs_option.h:153
rs2_timestamp_domain
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
Definition: rs_frame.h:19
end
GLuint GLuint end
Definition: glad/glad/glad.h:2395
rs2_frame_metadata_value
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
Definition: rs_frame.h:29
BIND_RAW_2D_ARRAY_PROPERTY
#define BIND_RAW_2D_ARRAY_PROPERTY(T, member, valueT, NROWS, NCOLS)
Definition: pyrealsense2.h:100
rs2_quaternion::x
float x
Definition: rs_types.h:105
RS2_LOG_SEVERITY_COUNT
@ RS2_LOG_SEVERITY_COUNT
Definition: rs_types.h:128
rs2_stream
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:43
test-motion.noise_variances
noise_variances
Definition: sw-dev/test-motion.py:15
RS2_CALIBRATION_STATUS_LAST
@ RS2_CALIBRATION_STATUS_LAST
Definition: rs_device.h:430
RS2_PLAYBACK_STATUS_COUNT
@ RS2_PLAYBACK_STATUS_COUNT
Definition: rs_record_playback.h:25
rs2_distortion_to_string
const char * rs2_distortion_to_string(rs2_distortion distortion)
Definition: to-string.cpp:768
pyrealsense2.h
RS2_OPTION_LLD_TEMPERATURE
@ RS2_OPTION_LLD_TEMPERATURE
Definition: rs_option.h:77
rs2_notification_category
rs2_notification_category
Category of the librealsense notification.
Definition: rs_types.h:17
make_pythonic_str
std::string make_pythonic_str(std::string str)
Definition: c_files.cpp:8


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Mon Apr 22 2024 02:12:55