Intel® RealSense™ Cross Platform API
Intel Realsense Cross-platform API
Public Member Functions | List of all members
rs2::pose_sensor Class Reference

#include <rs_sensor.hpp>

Inheritance diagram for rs2::pose_sensor:
rs2::sensor rs2::options

Public Member Functions

 pose_sensor (sensor s)
 
bool import_localization_map (const std::vector< uint8_t > &lmap_buf) const
 
std::vector< uint8_t > export_localization_map () const
 
bool set_static_node (const std::string &guid, const rs2_vector &pos, const rs2_quaternion &orient) const
 
bool get_static_node (const std::string &guid, rs2_vector &pos, rs2_quaternion &orient) const
 
bool remove_static_node (const std::string &guid) const
 
 operator bool () const
 
 pose_sensor (std::shared_ptr< rs2_sensor > dev)
 
- Public Member Functions inherited from rs2::sensor
void open (const stream_profile &profile) const
 
bool supports (rs2_camera_info info) const
 
const char * get_info (rs2_camera_info info) const
 
void open (const std::vector< stream_profile > &profiles) const
 
void close () const
 
template<class T >
void start (T callback) const
 
void stop () const
 
template<class T >
void set_notifications_callback (T callback) const
 
std::vector< stream_profileget_stream_profiles () const
 
std::vector< stream_profileget_active_streams () const
 
std::vector< filterget_recommended_filters () const
 
sensoroperator= (const std::shared_ptr< rs2_sensor > other)
 
sensoroperator= (const sensor &other)
 
 sensor ()
 
 operator bool () const
 
const std::shared_ptr< rs2_sensor > & get () const
 
template<class T >
bool is () const
 
template<class T >
as () const
 
 sensor (std::shared_ptr< rs2_sensor > dev)
 
 operator std::shared_ptr< rs2_sensor > ()
 
bool supports (rs2_option option) const
 
- Public Member Functions inherited from rs2::options
bool supports (rs2_option option) const
 
const char * get_option_description (rs2_option option) const
 
const char * get_option_name (rs2_option option) const
 
const char * get_option_value_description (rs2_option option, float val) const
 
float get_option (rs2_option option) const
 
option_value get_option_value (rs2_option option_id) const
 
option_range get_option_range (rs2_option option) const
 
void set_option (rs2_option option, float value) const
 
void set_option_value (option_value const &value) const
 
bool is_option_read_only (rs2_option option) const
 
void on_options_changed (std::function< void(const options_list &) > callback) const
 
std::vector< rs2_optionget_supported_options ()
 
options_list get_supported_option_values ()
 
optionsoperator= (const options &other)
 
 options (const options &other)
 
virtual ~options ()=default
 

Additional Inherited Members

- Protected Member Functions inherited from rs2::options
 options (rs2_options *o=nullptr)
 
template<class T >
optionsoperator= (const T &dev)
 
- Protected Attributes inherited from rs2::sensor
friend context
 
friend device_list
 
friend device
 
friend device_base
 
friend roi_sensor
 
std::shared_ptr< rs2_sensor_sensor
 

Constructor & Destructor Documentation

◆ pose_sensor() [1/2]

rs2::pose_sensor::pose_sensor ( sensor  s)
inline

◆ pose_sensor() [2/2]

rs2::pose_sensor::pose_sensor ( std::shared_ptr< rs2_sensor dev)
inlineexplicit

Member Function Documentation

◆ export_localization_map()

std::vector<uint8_t> rs2::pose_sensor::export_localization_map ( ) const
inline

Get relocalization map that is currently on device, created and updated during most recent tracking session. Can be called before or after stop().

Returns
map data as a binary blob

◆ get_static_node()

bool rs2::pose_sensor::get_static_node ( const std::string &  guid,
rs2_vector pos,
rs2_quaternion orient 
) const
inline

Gets the current pose of a static node that was created in the current map or in an imported map. Static nodes of imported maps are available after relocalizing the imported map. The static node's pose is returned relative to the current origin of coordinates of device poses. Thus, poses of static nodes of an imported map are consistent with current device poses after relocalization. This function fails if the current tracker confidence is below 3 (high confidence).

Parameters
[in]guidunique name of the static node (limited to 127 chars).
[out]posposition of the static node in the 3D space.
[out]orient_quatorientation of the static node in the 3D space, represented by a unit quaternion.
Returns
true if success.

◆ import_localization_map()

bool rs2::pose_sensor::import_localization_map ( const std::vector< uint8_t > &  lmap_buf) const
inline

Load relocalization map onto device. Only one relocalization map can be imported at a time; any previously existing map will be overwritten. The imported map exists simultaneously with the map created during the most recent tracking session after start(), and they are merged after the imported map is relocalized. This operation must be done before start().

Parameters
[in]lmap_bufmap data as a binary blob
Returns
true if success

◆ operator bool()

rs2::pose_sensor::operator bool ( ) const
inline

◆ remove_static_node()

bool rs2::pose_sensor::remove_static_node ( const std::string &  guid) const
inline

Removes a static node from the current map.

Parameters
[in]guidunique name of the static node (limited to 127 chars).

◆ set_static_node()

bool rs2::pose_sensor::set_static_node ( const std::string &  guid,
const rs2_vector pos,
const rs2_quaternion orient 
) const
inline

Creates a named virtual landmark in the current map, known as static node. The static node's pose is provided relative to the origin of current coordinate system of device poses. This function fails if the current tracker confidence is below 3 (high confidence).

Parameters
[in]guidunique name of the static node (limited to 127 chars). If a static node with the same name already exists in the current map or the imported map, the static node is overwritten.
[in]posposition of the static node in the 3D space.
[in]orient_quatorientation of the static node in the 3D space, represented by a unit quaternion.
Returns
true if success.

The documentation for this class was generated from the following file: