Skip to content

Commit

Permalink
Merge pull request #3318 from dorodnic/bug_fixes
Browse files Browse the repository at this point in the history
Bug fixes
  • Loading branch information
dorodnic committed Mar 4, 2019
2 parents 3dae1c4 + 7e91ffc commit 43e30dd
Show file tree
Hide file tree
Showing 27 changed files with 373 additions and 110 deletions.
37 changes: 22 additions & 15 deletions common/model-views.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6261,9 +6261,9 @@ namespace rs2
}
}
}
catch (...)
catch (const std::exception& ex)
{
ImGui::TextColored(redish, "Couldn't fetch Advanced Mode settings");
error_message = ex.what();
}

ImGui::TreePop();
Expand Down Expand Up @@ -6659,22 +6659,29 @@ namespace rs2
{
assert(it.value().is_string());
std::string formatstr = it.value();
if (formatstr == "R8L8")
{
requested_streams[std::make_pair(RS2_STREAM_INFRARED, 1)].format = RS2_FORMAT_Y8;
requested_streams[std::make_pair(RS2_STREAM_INFRARED, 2)].format = RS2_FORMAT_Y8;
}
else if (formatstr == "Y8")
{
requested_streams[std::make_pair(RS2_STREAM_INFRARED, 1)].format = RS2_FORMAT_Y8;
}
else if (formatstr == "UYVY")

bool found = false;
for (int i = 0; i < RS2_FORMAT_COUNT; i++)
{
requested_streams[std::make_pair(RS2_STREAM_INFRARED, 1)].format = RS2_FORMAT_UYVY;
auto format = (rs2_format)i;
if (ends_with(rs2_format_to_string(format), formatstr))
{
requested_streams[std::make_pair(RS2_STREAM_INFRARED, 1)].format = format;
found = true;
}
}
else

if (!found)
{
throw std::runtime_error(to_string() << "Unsupported stream-ir-format: " << formatstr);
if (formatstr == "R8L8")
{
requested_streams[std::make_pair(RS2_STREAM_INFRARED, 1)].format = RS2_FORMAT_Y8;
requested_streams[std::make_pair(RS2_STREAM_INFRARED, 2)].format = RS2_FORMAT_Y8;
}
else
{
throw std::runtime_error(to_string() << "Unsupported stream-ir-format: " << formatstr);
}
}

// Disable infrared stream on all sub devices
Expand Down
132 changes: 108 additions & 24 deletions common/realsense-ui-advanced-mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,12 +100,6 @@ inline void slider_int(std::string& error_message, const char* id, T* val, S T::
{
error_message = "Invalid numeric input!";
}
else if (new_value < min || new_value > max)
{
error_message = rs2::to_string() << new_value
<< " is out of bounds [" << min << ", "
<< max << "]";
}
else
{
val->*field = static_cast<S>(new_value);
Expand Down Expand Up @@ -162,12 +156,6 @@ inline void slider_float(std::string& error_message, const char* id, T* val, S T
{
error_message = "Invalid numeric input!";
}
else if (new_value < min || new_value > max)
{
error_message = rs2::to_string() << new_value
<< " is out of bounds [" << min << ", "
<< max << "]";
}
else
{
val->*field = static_cast<S>(new_value);
Expand Down Expand Up @@ -258,7 +246,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_depth_control(amc.depth_controls.vals[0]);
try
{
advanced.set_depth_control(amc.depth_controls.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -280,7 +276,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_rsm(amc.rsm.vals[0]);
try
{
advanced.set_rsm(amc.rsm.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -307,7 +311,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_rau_support_vector_control(amc.rsvc.vals[0]);
try
{
advanced.set_rau_support_vector_control(amc.rsvc.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -330,7 +342,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_color_control(amc.color_control.vals[0]);
try
{
advanced.set_color_control(amc.color_control.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -351,7 +371,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_rau_thresholds_control(amc.rctc.vals[0]);
try
{
advanced.set_rau_thresholds_control(amc.rctc.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -372,7 +400,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_slo_color_thresholds_control(amc.sctc.vals[0]);
try
{
advanced.set_slo_color_thresholds_control(amc.sctc.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -396,7 +432,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_slo_penalty_control(amc.spc.vals[0]);
try
{
advanced.set_slo_penalty_control(amc.spc.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -419,7 +463,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_hdad(amc.hdad.vals[0]);
try
{
advanced.set_hdad(amc.hdad.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand Down Expand Up @@ -449,7 +501,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_color_correction(amc.cc.vals[0]);
try
{
advanced.set_color_correction(amc.cc.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -472,7 +532,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_depth_table(amc.depth_table.vals[0]);
try
{
advanced.set_depth_table(amc.depth_table.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -491,7 +559,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_ae_control(amc.ae.vals[0]);
try
{
advanced.set_ae_control(amc.ae.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand All @@ -511,7 +587,15 @@ inline void draw_advanced_mode_controls(rs400::advanced_mode& advanced,

if (to_set)
{
advanced.set_census(amc.census.vals[0]);
try
{
advanced.set_census(amc.census.vals[0]);
}
catch (...)
{
ImGui::TreePop();
throw;
}
was_set = true;
}

Expand Down
2 changes: 2 additions & 0 deletions common/rendering.h
Original file line number Diff line number Diff line change
Expand Up @@ -1225,6 +1225,8 @@ namespace rs2
if (auto colorized_frame = yuy2rgb->process(frame).as<video_frame>())
{
rendered_frame = colorized_frame;
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, width, height, 0, GL_RGB,
GL_UNSIGNED_BYTE, colorized_frame.get_data());
}
}
else
Expand Down
2 changes: 2 additions & 0 deletions examples/example.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@

#pragma once

#include <librealsense2/rs.hpp>

#define GLFW_INCLUDE_GLU
#include <GLFW/glfw3.h>

Expand Down
10 changes: 5 additions & 5 deletions examples/pointcloud/rs-pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,6 @@ int main(int argc, char * argv[]) try
// Wait for the next set of frames from the camera
auto frames = pipe.wait_for_frames();

auto depth = frames.get_depth_frame();

// Generate the pointcloud and texture mappings
points = pc.calculate(depth);

auto color = frames.get_color_frame();

// For cameras that don't have RGB sensor, we'll map the pointcloud to infrared instead of color
Expand All @@ -47,6 +42,11 @@ int main(int argc, char * argv[]) try
// Tell pointcloud object to map to this color frame
pc.map_to(color);

auto depth = frames.get_depth_frame();

// Generate the pointcloud and texture mappings
points = pc.calculate(depth);

// Upload the color frame to OpenGL
app_state.tex.upload(color);

Expand Down
2 changes: 0 additions & 2 deletions examples/software-device/rs-software-device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
#include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
#include <librealsense2/hpp/rs_internal.hpp>
#include "example.hpp"
#include "example.hpp" // Include short list of convenience functions for rendering


#define STB_IMAGE_WRITE_IMPLEMENTATION
#include <stb_image_write.h>
Expand Down
8 changes: 8 additions & 0 deletions include/librealsense2/h/rs_context.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,14 @@ void rs2_set_devices_changed_callback(const rs2_context* context, rs2_devices_ch
* @return A pointer to a device that plays data from the file, or null in case of failure
*/
rs2_device* rs2_context_add_device(rs2_context* ctx, const char* file, rs2_error** error);

/**
* Add an instance of software device to the context
* \param ctx The context to which the new device will be added
* \param dev Instance of software device to register into the context
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_context_add_software_device(rs2_context* ctx, rs2_device* dev, rs2_error** error);

/**
* Removes a playback device from the context, if exists
Expand Down
9 changes: 8 additions & 1 deletion include/librealsense2/h/rs_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -155,12 +155,19 @@ int rs2_is_sensor_extendable_to(const rs2_sensor* sensor, rs2_extension extensio
float rs2_get_depth_scale(rs2_sensor* sensor, rs2_error** error);

/**
* Retrieve the stereoscopic baseline value. Applicable to stereo-based depth modules
* Retrieve the stereoscopic baseline value from frame. Applicable to stereo-based depth modules
* \param[out] float Stereoscopic baseline in millimeters
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
float rs2_depth_stereo_frame_get_baseline(const rs2_frame* frame_ref, rs2_error** error);

/**
* Retrieve the stereoscopic baseline value from sensor. Applicable to stereo-based depth modules
* \param[out] float Stereoscopic baseline in millimeters
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
float rs2_get_stereo_baseline(rs2_sensor* sensor, rs2_error** error);

/**
* \brief sets the active region of interest to be used by auto-exposure algorithm
* \param[in] sensor the RealSense sensor
Expand Down
4 changes: 3 additions & 1 deletion include/librealsense2/hpp/rs_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ namespace rs2

class pipeline;
class device_hub;
class software_device;

/**
* default librealsense context class
Expand Down Expand Up @@ -202,9 +203,10 @@ namespace rs2
: _context(ctx)
{}
explicit operator std::shared_ptr<rs2_context>() { return _context; };
protected:
protected:
friend class rs2::pipeline;
friend class rs2::device_hub;
friend class rs2::software_device;

std::shared_ptr<rs2_context> _context;
};
Expand Down
Loading

0 comments on commit 43e30dd

Please sign in to comment.