32 if (devices.
size() == 0)
34 std::cerr <<
"No device connected, please connect a RealSense device" << std::endl;
45 std::cout <<
"Found the following devices:\n" << std::endl;
59 if (selected_device_index >= devices.size())
61 throw std::out_of_range(
"Selected device index is out of range");
65 selected_device = devices[selected_device_index];
68 return selected_device;
76 std::cout <<
"Device information: " << std::endl;
97 std::string
name =
"Unknown Device";
102 std::string
sn =
"########";
106 return name +
" " +
sn;
115 return "Unknown Sensor";
128 std::cout <<
"Device consists of " << sensors.size() <<
" sensors:\n" << std::endl;
139 if (selected_sensor_index >= sensors.size())
141 throw std::out_of_range(
"Selected sensor index is out of range");
144 return sensors[selected_sensor_index];
152 std::cout <<
"Sensor supports the following options:\n" << std::endl;
171 std::cout <<
" Description : " << description << std::endl;
174 float current_value = sensor.
get_option(option_type);
175 std::cout <<
" Current Value : " << current_value << std::endl;
181 std::cout <<
" is not supported" << std::endl;
188 throw std::out_of_range(
"Selected option is out of range");
190 return static_cast<rs2_option>(selected_sensor_option);
201 float scale = dpt_sensor.get_depth_scale();
202 std::cout <<
"Scale factor for depth sensor is: " << scale << std::endl;
206 throw std::runtime_error(
"Given sensor is not a depth sensor");
222 auto principal_point = std::make_pair(intrinsics.
ppx, intrinsics.
ppy);
226 std::cout <<
"Principal Point : " << principal_point.first <<
", " << principal_point.second << std::endl;
228 std::cout <<
"Distortion Model : " << model << std::endl;
229 std::cout <<
"Distortion Coefficients : [" << intrinsics.
coeffs[0] <<
"," << intrinsics.
coeffs[1] <<
"," <<
230 intrinsics.
coeffs[2] <<
"," << intrinsics.
coeffs[3] <<
"," << intrinsics.
coeffs[4] <<
"]" << std::endl;
232 catch (
const std::exception&
e)
234 std::cerr <<
"Failed to get intrinsics for the given stream. " << e.what() << std::endl;
244 std::cout <<
" Scale X cross axis cross axis Bias X \n";
245 std::cout <<
" cross axis Scale Y cross axis Bias Y \n";
246 std::cout <<
" cross axis cross axis Scale Z Bias Z \n";
247 for (
int i = 0;
i < 3;
i++)
249 for (
int j = 0;
j < 4;
j++)
256 std::cout <<
"Variance of noise for X, Y, Z axis \n";
257 for (
int i = 0;
i < 3;
i++)
261 std::cout <<
"Variance of bias for X, Y, Z axis \n";
262 for (
int i = 0;
i < 3;
i++)
266 catch (
const std::exception&
e)
268 std::cerr <<
"Failed to get intrinsics for the given stream. " << e.what() << std::endl;
273 std::cerr <<
"Given stream profile has no intrinsics data" << std::endl;
290 catch (
const std::exception&
e)
292 std::cerr <<
"Failed to get extrinsics for the given streams. " << e.what() << std::endl;
306 std::cerr <<
"This option is not supported by this sensor" << std::endl;
313 std::cout <<
"Supported range for option " << option_type <<
":" << std::endl;
316 float default_value = range.
def;
317 float maximum_supported_value = range.
max;
318 float minimum_supported_value = range.
min;
319 float difference_to_next_value = range.
step;
320 std::cout <<
" Min Value : " << minimum_supported_value << std::endl;
321 std::cout <<
" Max Value : " << maximum_supported_value << std::endl;
322 std::cout <<
" Default Value : " << default_value << std::endl;
323 std::cout <<
" Step : " << difference_to_next_value << std::endl;
325 bool change_option =
false;
330 std::cout <<
"Enter the new value for this option: ";
331 float requested_value;
332 std::cin >> requested_value;
338 sensor.
set_option(option_type, requested_value);
344 std::cerr <<
"Failed to set option " << option_type <<
". (" << e.what() <<
")" << std::endl;
364 std::map<std::pair<rs2_stream, int>,
int> unique_streams;
365 for (
auto&& sp : stream_profiles)
367 unique_streams[std::make_pair(sp.stream_type(), sp.stream_index())]++;
369 std::cout <<
"Sensor consists of " << unique_streams.size() <<
" streams: " << std::endl;
370 for (
size_t i = 0;
i < unique_streams.size();
i++)
372 auto it = unique_streams.begin();
374 std::cout <<
" - " <<
it->first.first <<
" #" <<
it->first.second << std::endl;
378 std::cout <<
"Sensor provides the following stream profiles:" << std::endl;
387 rs2_stream stream_data_type = stream_profile.stream_type();
403 int stream_index = stream_profile.stream_index();
408 std::string stream_name = stream_profile.stream_name();
413 int unique_stream_id = stream_profile.unique_id();
414 std::cout << std::setw(3) << profile_num <<
": " << stream_data_type <<
" #" << stream_index;
426 std::cout <<
" (Video Stream: " << video_stream_profile.
format() <<
" " <<
427 video_stream_profile.
width() <<
"x" << video_stream_profile.
height() <<
"@ " << video_stream_profile.
fps() <<
"Hz)";
434 if (selected_profile_index >= stream_profiles.size())
436 throw std::out_of_range(
"Requested profile index is out of range");
439 return stream_profiles[selected_profile_index];
453 sensor.
open(stream_profile);
455 std::ostringstream oss;
456 oss <<
"Displaying profile " << stream_profile.
stream_name();
477 std::cout <<
"Streaming profile: " << stream_profile.
stream_name() <<
". Close display window to continue..." << std::endl;
bool prompt_yes_no(const std::string &prompt_msg)
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
GLuint const GLchar * name
std::vector< sensor > query_sensors() const
std::vector< stream_profile > get_stream_profiles() const
const char * get_info(rs2_camera_info info) const
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
rs2_format format() const
void start(T callback) const
static std::string get_sensor_name(const rs2::sensor &sensor)
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
std::string stream_name() const
static std::string get_device_name(const rs2::device &dev)
bool supports(rs2_camera_info info) const
const char * get_option_description(rs2_option option) const
device_list query_devices() const
static void start_streaming_a_profile(const rs2::sensor &sensor, const rs2::stream_profile &stream_profile)
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
device wait_for_device() const
float get_option(rs2_option option) const
static rs2::sensor get_a_sensor_from_a_device(const rs2::device &dev)
void open(const stream_profile &profile) const
static void print_device_information(const rs2::device &dev)
static rs2::stream_profile choose_a_streaming_profile(const rs2::sensor &sensor)
static void change_sensor_option(const rs2::sensor &sensor, rs2_option option_type)
rs2_stream
Streams are different types of data provided by RealSense devices.
uint32_t get_user_selection(const std::string &prompt_message)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
std::pair< std::string, std::string > get_device_name(const device &dev)
std::string get_sensor_name(rs2::video_stream_profile c, rs2::video_stream_profile d)
static void get_extrinsics(const rs2::stream_profile &from_stream, const rs2::stream_profile &to_stream)
static void get_field_of_view(const rs2::stream_profile &stream)
bool supports(rs2_camera_info info) const
static rs2_option get_sensor_option(const rs2::sensor &sensor)
option_range get_option_range(rs2_option option) const
void set_option(rs2_option option, float value) const
std::vector< std::shared_ptr< stream_profile_interface > > stream_profiles
Motion device intrinsics: scale, bias, and variances.
static rs2::device get_a_realsense_device()
const char * get_info(rs2_camera_info info) const
static float get_depth_units(const rs2::sensor &sensor)