5 #include "../include/librealsense2/rs.h" 12 std::replace(
begin(str),
end(str),
' ',
'_');
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.")
47 py::class_<rs2_intrinsics>
intrinsics(m,
"intrinsics",
"Video stream intrinsics.");
48 intrinsics.def(py::init<>())
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")
58 std::ostringstream ss;
63 py::class_<rs2_dsm_params> dsm_params( m,
"dsm_params",
"Video stream DSM parameters" );
64 dsm_params.def( py::init<>() )
74 .def_property_readonly(
"temp",
76 return float(
self.temp_x2 ) / 2;
78 "temperature (LDD for depth; HUM for color)" )
83 std::ostringstream ss;
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<>())
96 ss <<
"noise_variances: " <<
array_to_string(
self.noise_variances) <<
", ";
104 py::class_<rs2_vector> vector(m,
"vector",
"3D vector in Euclidean coordinate space.");
105 vector.def(py::init<>())
110 std::stringstream ss;
111 ss <<
"x: " <<
self.x <<
", ";
112 ss <<
"y: " <<
self.y <<
", ";
113 ss <<
"z: " <<
self.z;
117 py::class_<rs2_quaternion> quaternion(m,
"quaternion",
"Quaternion used to represent rotation.");
118 quaternion.def(py::init<>())
124 std::stringstream ss;
125 ss <<
"x: " <<
self.x <<
", ";
126 ss <<
"y: " <<
self.y <<
", ";
127 ss <<
"z: " <<
self.z <<
", ";
128 ss <<
"w: " <<
self.w;
132 py::class_<rs2_pose>
pose(m,
"pose");
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)")
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<>())
150 std::stringstream ss;
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
#define BIND_ENUM_CUSTOM(module, rs2_enum_type, FIRST, LAST, docstring)
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
rs2_vector angular_acceleration
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
std::string matrix_to_string(const T(&arr)[N][M])
unsigned int tracker_confidence
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
std::string array_to_string(const T(&arr)[N])
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
rs2_calib_target_type
Calibration target type.
#define BIND_ENUM(module, rs2_enum_type, RS2_ENUM_COUNT, docstring)
unsigned long long timestamp
rs2_vector angular_velocity
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
unsigned int mapper_confidence
Quaternion used to represent rotation.
unsigned char reserved[1]
rs2_matchers
Specifies types of different matchers.
rs2_format
A stream's format identifies how binary data is encoded within a frame.
#define BIND_RAW_2D_ARRAY_PROPERTY(T, member, valueT, NROWS, NCOLS)
rs2_stream
Streams are different types of data provided by RealSense devices.
float3 transform(const rs2_extrinsics *extrin, const float3 &point)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
#define BIND_RAW_ARRAY_PROPERTY(T, member, valueT, SIZE)
3D vector in Euclidean coordinate space
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
rs2_notification_category
Category of the librealsense notification.
Motion device intrinsics: scale, bias, and variances.
void init_c_files(py::module &m)
std::string make_pythonic_str(std::string str)
rs2_log_severity
Severity of the librealsense logger.
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
rs2_l500_visual_preset
For L500 devices: provides optimized settings (presets) for specific types of usage.
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.