rs_options.hpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2019 Intel Corporation. All Rights Reserved.
3 
4 #ifndef LIBREALSENSE_RS2_OPTIONS_HPP
5 #define LIBREALSENSE_RS2_OPTIONS_HPP
6 
7 #include "rs_types.hpp"
8 
9 namespace rs2
10 {
11  class options
12  {
13  public:
20  {
21  rs2_error* e = nullptr;
22  auto res = rs2_supports_option(_options, option, &e);
23  error::handle(e);
24  return res > 0;
25  }
26 
33  {
34  rs2_error* e = nullptr;
35  auto res = rs2_get_option_description(_options, option, &e);
36  error::handle(e);
37  return res;
38  }
39 
45  const char* get_option_name(rs2_option option) const
46  {
47  rs2_error* e = nullptr;
48  auto res = rs2_get_option_name(_options, option, &e);
49  error::handle(e);
50  return res;
51  }
52 
60  {
61  rs2_error* e = nullptr;
62  auto res = rs2_get_option_value_description(_options, option, val, &e);
63  error::handle(e);
64  return res;
65  }
66 
73  {
74  rs2_error* e = nullptr;
75  auto res = rs2_get_option(_options, option, &e);
76  error::handle(e);
77  return res;
78  }
79 
85  {
87  rs2_error* e = nullptr;
89  &result.min, &result.max, &result.step, &result.def, &e);
90  error::handle(e);
91  return result;
92  }
93 
99  void set_option(rs2_option option, float value) const
100  {
101  rs2_error* e = nullptr;
102  rs2_set_option(_options, option, value, &e);
103  error::handle(e);
104  }
105 
112  {
113  rs2_error* e = nullptr;
114  auto res = rs2_is_option_read_only(_options, option, &e);
115  error::handle(e);
116  return res > 0;
117  }
118 
119  std::vector<rs2_option> get_supported_options()
120  {
121  std::vector<rs2_option> res;
122  rs2_error* e = nullptr;
123  std::shared_ptr<rs2_options_list> options_list(
126 
127  for (auto opt = 0; opt < rs2_get_options_list_size(options_list.get(), &e);opt++)
128  {
129  res.push_back(rs2_get_option_from_list(options_list.get(), opt, &e));
130  }
131  return res;
132  };
133 
134  options& operator=(const options& other)
135  {
136  _options = other._options;
137  return *this;
138  }
139  // if operator= is ok, this should be ok too
140  options(const options& other) : _options(other._options) {}
141 
142  virtual ~options() = default;
143  protected:
144  explicit options(rs2_options* o = nullptr) : _options(o)
145  {
146  }
147 
148  template<class T>
150  {
151  _options = (rs2_options*)(dev.get());
152  return *this;
153  }
154 
155  private:
157  };
158 }
159 #endif // LIBREALSENSE_RS2_OIPTIONS_HPP
float rs2_get_option(const rs2_options *options, rs2_option option, rs2_error **error)
Definition: rs.cpp:628
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
virtual ~options()=default
GLfloat value
options & operator=(const T &dev)
Definition: rs_options.hpp:149
Definition: cah-model.h:10
e
Definition: rmse.py:177
options(const options &other)
Definition: rs_options.hpp:140
GLuint GLfloat * val
std::vector< rs2_option > get_supported_options()
Definition: rs_options.hpp:119
int rs2_supports_option(const rs2_options *options, rs2_option option, rs2_error **error)
Definition: rs.cpp:679
Definition: getopt.h:41
const char * rs2_get_option_name(const rs2_options *options, rs2_option option, rs2_error **error)
Definition: rs.cpp:651
const char * rs2_get_option_value_description(const rs2_options *options, rs2_option option, float value, rs2_error **error)
Definition: rs.cpp:1022
const char * get_option_description(rs2_option option) const
Definition: rs_options.hpp:32
const char * get_option_name(rs2_option option) const
Definition: rs_options.hpp:45
bool is_option_read_only(rs2_option option) const
Definition: rs_options.hpp:111
void rs2_get_option_range(const rs2_options *sensor, rs2_option option, float *min, float *max, float *step, float *def, rs2_error **error)
Definition: rs.cpp:686
rs2_options_list * rs2_get_options_list(const rs2_options *options, rs2_error **error)
Definition: rs.cpp:644
bool supports(rs2_option option) const
Definition: rs_options.hpp:19
static void handle(rs2_error *e)
Definition: rs_types.hpp:144
options(rs2_options *o=nullptr)
Definition: rs_options.hpp:144
const char * rs2_get_option_description(const rs2_options *options, rs2_option option, rs2_error **error)
Definition: rs.cpp:1007
options & operator=(const options &other)
Definition: rs_options.hpp:134
int rs2_is_option_read_only(const rs2_options *options, rs2_option option, rs2_error **error)
Definition: rs.cpp:621
GLuint res
Definition: glext.h:8856
option_range get_option_range(rs2_option option) const
Definition: rs_options.hpp:84
rs2_options * _options
Definition: rs_options.hpp:156
void rs2_set_option(const rs2_options *options, rs2_option option, float value, rs2_error **error)
Definition: rs.cpp:636
void rs2_delete_options_list(rs2_options_list *list)
Definition: rs.cpp:672
void set_option(rs2_option option, float value) const
Definition: rs_options.hpp:99
GLuint64EXT * result
Definition: glext.h:10921
float get_option(rs2_option option) const
Definition: rs_options.hpp:72
rs2_option rs2_get_option_from_list(const rs2_options_list *options, int i, rs2_error **error)
Definition: rs.cpp:665
const char * get_option_value_description(rs2_option option, float val) const
Definition: rs_options.hpp:59
int rs2_get_options_list_size(const rs2_options_list *options, rs2_error **error)
Definition: rs.cpp:658


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:40