Skip to content

Commit

Permalink
Fix more errors discovered by izaakvc in issue IntelRealSense#2487
Browse files Browse the repository at this point in the history
  • Loading branch information
Lior Ramati committed Oct 24, 2018
1 parent 8267753 commit 2993136
Show file tree
Hide file tree
Showing 5 changed files with 21 additions and 10 deletions.
1 change: 1 addition & 0 deletions wrappers/matlab/disparity_transform.m
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
else
validateattributes(transform_to_disparity, {'logical', 'numeric'}, {'scalar', 'real'});
out = realsense.librealsense_mex('rs2::disparity_transform', 'new', logical(transform_to_disparity));
end
this = [email protected]_interface(out);
end

Expand Down
9 changes: 7 additions & 2 deletions wrappers/matlab/frameset.m
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,13 @@
ret = realsense.librealsense_mex('rs2::frameset', 'get_color_frame', this.objectHandle);
color_frame = realsense.video_frame(ret);
end
function infrared_frame = get_infrared_frame(this)
ret = realsense.librealsense_mex('rs2::frameset', 'get_infrared_frame', this.objectHandle);
function infrared_frame = get_infrared_frame(this, index)
if (nargin == 1)
ret = realsense.librealsense_mex('rs2::frameset', 'get_infrared_frame', this.objectHandle);
else
validateattributes(index, {'numeric'}, {'scalar', 'nonnegative', 'real', 'integer', '<=', 2}, '', 'index', 2);
ret = realsense.librealsense_mex('rs2::frameset', 'get_infrared_frame', this.objectHandle, int64_t(index));
end
infrared_frame = realsense.video_frame(ret);
end
function size = get_size(this)
Expand Down
17 changes: 11 additions & 6 deletions wrappers/matlab/librealsense_mex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,11 +451,16 @@ void make_factory(){
// try/catch moved to outer framework
outv[0] = MatlabParamParser::wrap(thiz.get_color_frame());
});
frameset_factory.record("get_infrared_frame", 1, 1, [](int outc, mxArray* outv[], int inc, const mxArray* inv[])
frameset_factory.record("get_infrared_frame", 1, 1, 2, [](int outc, mxArray* outv[], int inc, const mxArray* inv[])
{
auto thiz = MatlabParamParser::parse<rs2::frameset>(inv[0]);
// try/catch moved to outer framework
outv[0] = MatlabParamParser::wrap(thiz.get_infrared_frame());
if (inc == 1)
outv[0] = MatlabParamParser::wrap(thiz.get_infrared_frame());
else {
auto index = MatlabParamParser::parse<size_t>(inv[1]);
outv[0] = MatlabParamParser::wrap(thiz.get_infrared_frame(index));
}
});
frameset_factory.record("size", 1, 1, [](int outc, mxArray* outv[], int inc, const mxArray* inv[])
{
Expand Down Expand Up @@ -898,10 +903,10 @@ void make_factory(){
frame_queue_factory.record("wait_for_frame", 1, 1, 2, [](int outc, mxArray* outv[], int inc, const mxArray* inv[])
{
auto thiz = MatlabParamParser::parse<rs2::frame_queue>(inv[0]);
if (inc == 0) {
if (inc == 1) {
outv[0] = MatlabParamParser::wrap(thiz.wait_for_frame());
}
else if (inc == 1) {
else if (inc == 2) {
auto timeout_ms = MatlabParamParser::parse<unsigned int>(inv[1]);
outv[0] = MatlabParamParser::wrap(thiz.wait_for_frame(timeout_ms));
}
Expand Down Expand Up @@ -953,10 +958,10 @@ void make_factory(){
syncer_factory.record("wait_for_frames", 1, 1, 2, [](int outc, mxArray* outv[], int inc, const mxArray* inv[])
{
auto thiz = MatlabParamParser::parse<rs2::syncer>(inv[0]);
if (inc == 0) {
if (inc == 1) {
outv[0] = MatlabParamParser::wrap(thiz.wait_for_frames());
}
else if (inc == 1) {
else if (inc == 2) {
auto timeout_ms = MatlabParamParser::parse<unsigned int>(inv[1]);
outv[0] = MatlabParamParser::wrap(thiz.wait_for_frames(timeout_ms));
}
Expand Down
2 changes: 1 addition & 1 deletion wrappers/matlab/pipeline_profile.m
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ function delete(this)
narginchk(2, 3);
validateattributes(stream_type, {'realsense.stream', 'numeric'}, {'scalar', 'nonnegative', 'real', 'integer', '<=', realsense.stream.count}, '', 'stream_type', 2);
if nargin == 2
out = realsense.librealsense_mex('rs2::pipeline_profile', 'get_streams', this.objectHandle, int64(stream_type));
out = realsense.librealsense_mex('rs2::pipeline_profile', 'get_stream', this.objectHandle, int64(stream_type));
else
validateattributes(stream_index, {'numeric'}, {'scalar', 'nonnegative', 'real', 'integer'}, '', 'stream_index', 3);
out = realsense.librealsense_mex('rs2::pipeline_profile', 'get_stream', this.objectHandle, int64(stream_type), int64(stream_index));
Expand Down
2 changes: 1 addition & 1 deletion wrappers/matlab/stream_profile.m
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ function delete(this)
validateattributes(index, {'numeric'}, {'scalar', 'nonnegative', 'real', 'integer'}, '', 'index', 3);
validateattributes(fmt, {'realsense.format', 'numeric'}, {'scalar', 'nonnegative', 'real', 'integer', '<=', realsense.format.count}, '', 'fmt', 4);
out = realsense.librealsense_mex('rs2::stream_profile', 'clone', this.objectHandle, int64(type), int64(index), int64(fmt));
realsense.stream_profile(out{:});
profile = realsense.stream_profile(out{:});
end
function value = is(this, type)
narginchk(2, 2);
Expand Down

0 comments on commit 2993136

Please sign in to comment.