Go to the documentation of this file.
11 std::replace(begin(
str),
end(
str),
' ',
'_');
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.")
37 py_rs2_option.attr(
"__repr__" ) = py::cpp_function(
38 [](
const py::object & arg ) ->
py::str
40 auto type = py::type::handle_of( arg );
41 py::object type_name =
type.attr(
"__name__" );
42 py::int_ arg_int( arg );
44 return py::str(
"<{} {} '{}'>" ).format( std::move( type_name ), arg_int, enum_name );
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 );
54 py::is_method( py_rs2_option ) );
69 py::class_<rs2_intrinsics>
intrinsics(
m,
"intrinsics",
"Video stream intrinsics.");
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")
82 std::ostringstream
ss;
83 ss <<
"[ " <<
i.width <<
"x" <<
i.height
84 <<
" p[" <<
i.ppx <<
" " <<
i.ppy <<
"]"
85 <<
" f[" <<
i.fx <<
" " <<
i.fy <<
"]"
87 <<
i.coeffs[2] <<
" " <<
i.coeffs[3] <<
" " <<
i.coeffs[4] <<
"] ]";
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<>())
107 py::class_<rs2_vector> vector(
m,
"vector",
"3D vector in Euclidean coordinate space.");
108 vector.def(py::init<>())
113 std::stringstream
ss;
114 ss <<
"x: " <<
self.x <<
", ";
115 ss <<
"y: " <<
self.y <<
", ";
116 ss <<
"z: " <<
self.z;
120 py::class_<rs2_quaternion> quaternion(
m,
"quaternion",
"Quaternion used to represent rotation.");
121 quaternion.def(py::init<>())
127 std::stringstream
ss;
128 ss <<
"x: " <<
self.x <<
", ";
129 ss <<
"y: " <<
self.y <<
", ";
130 ss <<
"z: " <<
self.z <<
", ";
131 ss <<
"w: " <<
self.w;
135 py::class_<rs2_pose>
pose(
m,
"pose");
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)")
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.");
153 std::stringstream
ss;
float3 transform(const rs2_extrinsics *extrin, const float3 &point)
3D vector in Euclidean coordinate space
@ RS2_OPTION_AMBIENT_LIGHT
#define BIND_ENUM(module, rs2_enum_type, RS2_ENUM_COUNT, docstring)
std::string matrix_to_string(const T(&arr)[N][M])
@ RS2_NOTIFICATION_CATEGORY_COUNT
Quaternion used to represent rotation
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.
rs2_vector angular_velocity
rs2_matchers
Specifies types of different matchers.
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
GLsizei const GLchar *const * string
const char * rs2_option_to_string(rs2_option option)
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
#define BIND_ENUM_CUSTOM(module, rs2_enum_type, FIRST, LAST, docstring)
rs2_log_severity
Severity of the librealsense logger.
@ RS2_L500_VISUAL_PRESET_COUNT
rs2_l500_visual_preset
For L500 devices: provides optimized settings (presets) for specific types of usage.
rs2_format
A stream's format identifies how binary data is encoded within a frame.
@ RS2_RS400_VISUAL_PRESET_COUNT
Motion device intrinsics: scale, bias, and variances.
rs2_option_type
Defines known option value types.
@ RS2_TIMESTAMP_DOMAIN_COUNT
rs2_calib_target_type
Calibration target type.
void init_c_files(py::module &m)
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls,...
GLuint const GLchar * name
@ RS2_FRAME_METADATA_COUNT
rs2_vector angular_acceleration
unsigned int mapper_confidence
@ RS2_CALIBRATION_TYPE_COUNT
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
rs2_rs400_visual_preset
For RS400 devices: provides optimized settings (presets) for specific types of usage.
@ RS2_CALIBRATION_STATUS_FIRST
unsigned int tracker_confidence
rs2_option rs2_option_from_string(const char *option_name)
std::string array_to_string(const T(&arr)[N])
#define BIND_RAW_ARRAY_PROPERTY(T, member, valueT, SIZE)
const std::string intrinsics
Exposes librealsense functionality for C compilers.
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
#define BIND_RAW_2D_ARRAY_PROPERTY(T, member, valueT, NROWS, NCOLS)
rs2_stream
Streams are different types of data provided by RealSense devices.
@ RS2_CALIBRATION_STATUS_LAST
@ RS2_PLAYBACK_STATUS_COUNT
const char * rs2_distortion_to_string(rs2_distortion distortion)
@ RS2_OPTION_LLD_TEMPERATURE
rs2_notification_category
Category of the librealsense notification.
std::string make_pythonic_str(std::string str)
librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Fri Aug 2 2024 08:30:01