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 "python.hpp"
5 #include "../include/librealsense2/rs.h"
6 #include <iomanip>
7 #include "types.h"
8 
9 std::string make_pythonic_str(std::string str)
10 {
11  std::transform(begin(str), end(str), begin(str), ::tolower); //Make lower case
12  std::replace(begin(str), end(str), ' ', '_'); //replace spaces with underscore
13  if (str == "6dof") //Currently this is the only enum that starts with a digit
14  {
15  return "six_dof";
16  }
17  return str;
18 }
19 
20 
21 void init_c_files(py::module &m) {
23  BIND_ENUM(m, rs2_notification_category, RS2_NOTIFICATION_CATEGORY_COUNT, "Category of the librealsense notification.")
24  // rs2_exception_type
25  BIND_ENUM(m, rs2_distortion, RS2_DISTORTION_COUNT, "Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.")
26  BIND_ENUM(m, rs2_log_severity, RS2_LOG_SEVERITY_COUNT, "Severity of the librealsense logger.")
27  BIND_ENUM(m, rs2_extension, RS2_EXTENSION_COUNT, "Specifies advanced interfaces (capabilities) objects may implement.")
28  BIND_ENUM(m, rs2_matchers, RS2_MATCHER_COUNT, "Specifies types of different matchers.")
29  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.")
30  BIND_ENUM(m, rs2_stream, RS2_STREAM_COUNT, "Streams are different types of data provided by RealSense devices.")
31  BIND_ENUM(m, rs2_format, RS2_FORMAT_COUNT, "A stream's format identifies how binary data is encoded within a frame.")
32  BIND_ENUM(m, rs2_timestamp_domain, RS2_TIMESTAMP_DOMAIN_COUNT, "Specifies the clock in relation to which the frame timestamp was measured.")
33  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.")
34  BIND_ENUM(m, rs2_calib_target_type, RS2_CALIB_TARGET_COUNT, "Calibration target type.")
35 
36  BIND_ENUM(m, rs2_option, RS2_OPTION_COUNT, "Defines general configuration controls. These can generally be mapped to camera UVC controls, and can be set / queried at any time unless stated otherwise.")
37  // Force binding of deprecated (renamed) options that we still want to expose for backwards compatibility
38  py_rs2_option.value("ambient_light", RS2_OPTION_AMBIENT_LIGHT);
39  py_rs2_option.value( "lld_temperature", RS2_OPTION_LLD_TEMPERATURE );
40 
41  BIND_ENUM(m, rs2_l500_visual_preset, RS2_L500_VISUAL_PRESET_COUNT, "For L500 devices: provides optimized settings (presets) for specific types of usage.")
42  BIND_ENUM(m, rs2_playback_status, RS2_PLAYBACK_STATUS_COUNT, "") // No docstring in C++
43  BIND_ENUM(m, rs2_calibration_type, RS2_CALIBRATION_TYPE_COUNT, "Calibration type for use in device_calibration")
44  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")
45 
46 
47  py::class_<rs2_intrinsics> intrinsics(m, "intrinsics", "Video stream intrinsics.");
48  intrinsics.def(py::init<>())
49  .def_readwrite("width", &rs2_intrinsics::width, "Width of the image in pixels")
50  .def_readwrite("height", &rs2_intrinsics::height, "Height of the image in pixels")
51  .def_readwrite("ppx", &rs2_intrinsics::ppx, "Horizontal coordinate of the principal point of the image, as a pixel offset from the left edge")
52  .def_readwrite("ppy", &rs2_intrinsics::ppy, "Vertical coordinate of the principal point of the image, as a pixel offset from the top edge")
53  .def_readwrite("fx", &rs2_intrinsics::fx, "Focal length of the image plane, as a multiple of pixel width")
54  .def_readwrite("fy", &rs2_intrinsics::fy, "Focal length of the image plane, as a multiple of pixel height")
55  .def_readwrite("model", &rs2_intrinsics::model, "Distortion model of the image")
56  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_intrinsics, coeffs, float, 5), "Distortion coefficients")
57  .def("__repr__", [](const rs2_intrinsics& self) {
58  std::ostringstream ss;
59  ss << self;
60  return ss.str();
61  });
62 
63  py::class_<rs2_dsm_params> dsm_params( m, "dsm_params", "Video stream DSM parameters" );
64  dsm_params.def( py::init<>() )
65  .def_readonly( "timestamp", &rs2_dsm_params::timestamp, "seconds since epoch" )
66  .def_readonly( "version", &rs2_dsm_params::version, "major<<12 | minor<<4 | patch" )
67  .def_readwrite( "model", &rs2_dsm_params::model, "correction model (0/1/2 none/AOT/TOA)" )
68  .def_property( BIND_RAW_ARRAY_PROPERTY( rs2_dsm_params, flags, uint8_t, sizeof( rs2_dsm_params::flags )), "flags" )
69  .def_readwrite( "h_scale", &rs2_dsm_params::h_scale, "horizontal DSM scale" )
70  .def_readwrite( "v_scale", &rs2_dsm_params::v_scale, "vertical DSM scale" )
71  .def_readwrite( "h_offset", &rs2_dsm_params::h_offset, "horizontal DSM offset" )
72  .def_readwrite( "v_offset", &rs2_dsm_params::v_offset, "vertical DSM offset" )
73  .def_readwrite( "rtd_offset", &rs2_dsm_params::rtd_offset, "the Round-Trip-Distance delay" )
74  .def_property_readonly( "temp",
75  []( rs2_dsm_params const & self ) -> float {
76  return float( self.temp_x2 ) / 2;
77  },
78  "temperature (LDD for depth; HUM for color)" )
79  .def_property( BIND_RAW_ARRAY_PROPERTY( rs2_dsm_params, reserved, uint8_t, sizeof( rs2_dsm_params::reserved )), "reserved" )
80  .def( "__repr__",
81  []( const rs2_dsm_params & self )
82  {
83  std::ostringstream ss;
84  ss << self;
85  return ss.str();
86  } );
87 
88  py::class_<rs2_motion_device_intrinsic> motion_device_intrinsic(m, "motion_device_intrinsic", "Motion device intrinsics: scale, bias, and variances.");
89  motion_device_intrinsic.def(py::init<>())
90  .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")
91  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_motion_device_intrinsic, noise_variances, float, 3), "Variance of noise for X, Y, and Z axis")
92  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_motion_device_intrinsic, bias_variances, float, 3), "Variance of bias for X, Y, and Z axis")
93  .def("__repr__", [](const rs2_motion_device_intrinsic& self) {
94  std::stringstream ss;
95  ss << "data: " << matrix_to_string(self.data) << ", ";
96  ss << "noise_variances: " << array_to_string(self.noise_variances) << ", ";
97  ss << "bias_variances: " << array_to_string(self.bias_variances);
98  return ss.str();
99  });
100 
101  // rs2_vertex
102  // rs2_pixel
103 
104  py::class_<rs2_vector> vector(m, "vector", "3D vector in Euclidean coordinate space.");
105  vector.def(py::init<>())
106  .def_readwrite("x", &rs2_vector::x)
107  .def_readwrite("y", &rs2_vector::y)
108  .def_readwrite("z", &rs2_vector::z)
109  .def("__repr__", [](const rs2_vector& self) {
110  std::stringstream ss;
111  ss << "x: " << self.x << ", ";
112  ss << "y: " << self.y << ", ";
113  ss << "z: " << self.z;
114  return ss.str();
115  });
116 
117  py::class_<rs2_quaternion> quaternion(m, "quaternion", "Quaternion used to represent rotation.");
118  quaternion.def(py::init<>())
119  .def_readwrite("x", &rs2_quaternion::x)
120  .def_readwrite("y", &rs2_quaternion::y)
121  .def_readwrite("z", &rs2_quaternion::z)
122  .def_readwrite("w", &rs2_quaternion::w)
123  .def("__repr__", [](const rs2_quaternion& self) {
124  std::stringstream ss;
125  ss << "x: " << self.x << ", ";
126  ss << "y: " << self.y << ", ";
127  ss << "z: " << self.z << ", ";
128  ss << "w: " << self.w;
129  return ss.str();
130  });
131 
132  py::class_<rs2_pose> pose(m, "pose"); // No docstring in C++
133  pose.def(py::init<>())
134  .def_readwrite("translation", &rs2_pose::translation, "X, Y, Z values of translation, in meters (relative to initial position)")
135  .def_readwrite("velocity", &rs2_pose::velocity, "X, Y, Z values of velocity, in meters/sec")
136  .def_readwrite("acceleration", &rs2_pose::acceleration, "X, Y, Z values of acceleration, in meters/sec^2")
137  .def_readwrite("rotation", &rs2_pose::rotation, "Qi, Qj, Qk, Qr components of rotation as represented in quaternion rotation (relative to initial position)")
138  .def_readwrite("angular_velocity", &rs2_pose::angular_velocity, "X, Y, Z values of angular velocity, in radians/sec")
139  .def_readwrite("angular_acceleration", &rs2_pose::angular_acceleration, "X, Y, Z values of angular acceleration, in radians/sec^2")
140  .def_readwrite("tracker_confidence", &rs2_pose::tracker_confidence, "Pose confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High")
141  .def_readwrite("mapper_confidence", &rs2_pose::mapper_confidence, "Pose map confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High");
145  py::class_<rs2_extrinsics> extrinsics(m, "extrinsics", "Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.");
146  extrinsics.def(py::init<>())
147  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_extrinsics, rotation, float, 9), "Column - major 3x3 rotation matrix")
148  .def_property(BIND_RAW_ARRAY_PROPERTY(rs2_extrinsics, translation, float, 3), "Three-element translation vector, in meters")
149  .def("__repr__", [](const rs2_extrinsics &e) {
150  std::stringstream ss;
151  ss << "rotation: " << array_to_string(e.rotation);
152  ss << "\ntranslation: " << array_to_string(e.translation);
153  return ss.str();
154  });
156 }
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
float rtd_offset
Definition: rs_types.h:84
GLuint GLuint end
#define BIND_ENUM_CUSTOM(module, rs2_enum_type, FIRST, LAST, docstring)
Definition: python.hpp:39
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
Definition: extrinsics.h:59
float v_offset
Definition: rs_types.h:83
rs2_vector angular_acceleration
Definition: rs_types.h:147
rs2_calibration_type
Definition: rs_device.h:396
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
std::string matrix_to_string(const T(&arr)[N][M])
Definition: python.hpp:90
float z
Definition: rs_types.h:131
unsigned int tracker_confidence
Definition: rs_types.h:148
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
Definition: rs_types.h:45
std::string array_to_string(const T(&arr)[N])
Definition: python.hpp:75
float translation[3]
Definition: rs_sensor.h:101
std::mutex m
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
Definition: rs_types.h:74
float v_scale
Definition: rs_types.h:81
float h_scale
Definition: rs_types.h:80
rs2_vector translation
Definition: rs_types.h:142
rs2_calib_target_type
Calibration target type.
Definition: rs_frame.h:84
#define BIND_ENUM(module, rs2_enum_type, RS2_ENUM_COUNT, docstring)
Definition: python.hpp:38
unsigned long long timestamp
Definition: rs_types.h:76
unsigned char model
Definition: rs_types.h:78
unsigned char uint8_t
Definition: stdint.h:78
rs2_vector angular_velocity
Definition: rs_types.h:146
e
Definition: rmse.py:177
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
Definition: pose.h:88
float rotation[9]
Definition: rs_sensor.h:100
unsigned int mapper_confidence
Definition: rs_types.h:149
Quaternion used to represent rotation.
Definition: rs_types.h:135
not_this_one begin(...)
float y
Definition: rs_types.h:131
unsigned char reserved[1]
Definition: rs_types.h:90
unsigned short version
Definition: rs_types.h:77
rs2_vector velocity
Definition: rs_types.h:143
unsigned char flags[5]
Definition: rs_types.h:79
rs2_calibration_status
Definition: rs_device.h:408
rs2_matchers
Specifies types of different matchers.
Definition: rs_types.h:230
rs2_playback_status
rs2_quaternion rotation
Definition: rs_types.h:145
GLbitfield flags
rs2_format
A stream&#39;s format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
float x
Definition: rs_types.h:131
#define BIND_RAW_2D_ARRAY_PROPERTY(T, member, valueT, NROWS, NCOLS)
Definition: python.hpp:118
dictionary intrinsics
Definition: t265_stereo.py:142
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
float h_offset
Definition: rs_types.h:82
float3 transform(const rs2_extrinsics *extrin, const float3 &point)
Definition: pointcloud.cpp:47
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:98
#define BIND_RAW_ARRAY_PROPERTY(T, member, valueT, SIZE)
Definition: python.hpp:117
3D vector in Euclidean coordinate space
Definition: rs_types.h:129
rs2_distortion model
Definition: rs_types.h:66
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
Definition: rs_types.h:166
rs2_notification_category
Category of the librealsense notification.
Definition: rs_types.h:17
Video stream intrinsics.
Definition: rs_types.h:58
Motion device intrinsics: scale, bias, and variances.
Definition: rs_types.h:103
void init_c_files(py::module &m)
Definition: c_files.cpp:21
rs2_vector acceleration
Definition: rs_types.h:144
std::string make_pythonic_str(std::string str)
Definition: c_files.cpp:9
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:153
Definition: parser.hpp:153
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
rs2_l500_visual_preset
For L500 devices: provides optimized settings (presets) for specific types of usage.
Definition: rs_option.h:158
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
Definition: rs_frame.h:19


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Thu Dec 22 2022 03:41:42