diff --git a/src/core/enum-helpers.h b/src/core/enum-helpers.h index ca9381b1b0..a3bf2446f8 100644 --- a/src/core/enum-helpers.h +++ b/src/core/enum-helpers.h @@ -48,6 +48,7 @@ std::ostream & operator<<( std::ostream & out, rs2_option option ); bool try_parse( const std::string & option_name, rs2_option & result ); RS2_ENUM_HELPERS( rs2_stream, STREAM ) +LRS_EXTENSION_API char const * get_abbr_string( rs2_stream ); RS2_ENUM_HELPERS( rs2_format, FORMAT ) RS2_ENUM_HELPERS( rs2_distortion, DISTORTION ) RS2_ENUM_HELPERS( rs2_camera_info, CAMERA_INFO ) diff --git a/src/frame.cpp b/src/frame.cpp index 07c2c46777..e963c13624 100644 --- a/src/frame.cpp +++ b/src/frame.cpp @@ -32,8 +32,8 @@ std::ostream & operator<<( std::ostream & s, const frame_interface & f ) } else { - s << "[" << f.get_stream()->get_stream_type(); - s << "/" << f.get_stream()->get_unique_id(); + s << "[" << get_abbr_string( f.get_stream()->get_stream_type() ); + s << f.get_stream()->get_unique_id(); s << " " << f.get_header(); s << "]"; } @@ -45,7 +45,7 @@ std::ostream & operator<<( std::ostream & s, const frame_interface & f ) std::ostream & operator<<( std::ostream & os, frame_header const & header ) { os << "#" << header.frame_number; - os << " @" << ( rsutils::string::from() << std::fixed << std::setprecision( 2 ) << (double)header.timestamp ).str(); + os << " @" << rsutils::string::from( header.timestamp ); if( header.timestamp_domain != RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK ) os << "/" << rs2_timestamp_domain_to_string( header.timestamp_domain ); return os; diff --git a/src/sync.cpp b/src/sync.cpp index 3f306905e1..562b046c25 100644 --- a/src/sync.cpp +++ b/src/sync.cpp @@ -82,8 +82,7 @@ namespace librealsense _streams_type = {stream_type}; std::ostringstream ss; - ss << rs2_stream_to_string( stream_type ); - ss << '/'; + ss << get_abbr_string( stream_type ); ss << stream; _name = ss.str(); } @@ -137,6 +136,17 @@ namespace librealsense _name = create_composite_name(matchers, name); } + composite_matcher::matcher_queue::matcher_queue() + : q( QUEUE_MAX_SIZE, + []( frame_holder const & fh ) + { + // If queues are overrun, we'll get here + LOG_DEBUG( "DROPPED frame " << fh ); + } ) + { + } + + void composite_matcher::dispatch(frame_holder f, const syncronization_environment& env) { clean_inactive_streams(f); @@ -172,13 +182,13 @@ namespace librealsense if( ! matcher->get_active() ) { matcher->set_active( true ); - _frames_queue[matcher.get()].start(); + _frames_queue[matcher.get()].q.start(); } return matcher; } } - LOG_DEBUG( "no matcher found for " << rs2_stream_to_string( stream_type ) << '/' - << stream_id << "; creating matcher from device..." ); + LOG_DEBUG( "no matcher found for " << get_abbr_string( stream_type ) << '.' << stream_id + << "; creating matcher from device..." ); auto sensor = frame.frame->get_sensor().get(); //TODO: Potential deadlock if get_sensor() gets a hold of the last reference of that sensor auto dev_exist = false; @@ -266,7 +276,7 @@ namespace librealsense // Stop all our queues to wake up anyone waiting on them for( auto & fq : _frames_queue ) - fq.second.stop(); + fq.second.q.stop(); // Trickle the stop down to any children for( auto m : _matchers ) @@ -289,7 +299,7 @@ namespace librealsense os << '['; for( auto m : matchers ) { - auto const & q = _frames_queue[m]; + auto const & q = _frames_queue[m].q; q.peek( [&os]( frame_holder const & fh ) { os << fh; } ); @@ -313,7 +323,7 @@ namespace librealsense // latest timestamp/frame-number/etc. that we can compare to. auto const last_arrived = f->get_header(); - if( ! _frames_queue[matcher.get()].enqueue( std::move( f ) ) ) + if( ! _frames_queue[matcher.get()].q.enqueue( std::move( f ) ) ) // If we get stopped, nothing to do! return; @@ -344,7 +354,7 @@ namespace librealsense for( auto s = _frames_queue.begin(); s != _frames_queue.end(); s++ ) { librealsense::matcher * const m = s->first; - if( ! s->second.peek( [&]( frame_holder & fh ) { + if( ! s->second.q.peek( [&]( frame_holder & fh ) { LOG_IF_ENABLE( "... have " << *fh.frame, env ); frames_arrived.push_back( &fh ); frames_arrived_matchers.push_back( m ); @@ -395,12 +405,13 @@ namespace librealsense // something missing, we can't release anything yet... for( auto i : missing_streams ) { - LOG_IF_ENABLE( "... missing " << i->get_name() << ", next expected " - << _next_expected[i], + LOG_IF_ENABLE( "... missing " << i->get_name() << ", next expected @" + << rsutils::string::from( _next_expected[i].value ) << " (from " + << rsutils::string::from( _next_expected[i].fps ) << " fps)", env ); if( skip_missing_stream( *curr_sync, i, last_arrived, env ) ) { - LOG_IF_ENABLE( "... ignoring it", env ); + LOG_IF_ENABLE( "... cannot be synced; not waiting for it", env ); continue; } @@ -425,7 +436,7 @@ namespace librealsense frame_holder frame; int const timeout_ms = 5000; librealsense::matcher * m = frames_arrived_matchers[index]; - _frames_queue[m].dequeue( &frame, timeout_ms ); + _frames_queue[m].q.dequeue( &frame, timeout_ms ); match.push_back( std::move( frame ) ); } } @@ -493,7 +504,7 @@ namespace librealsense for(auto id: inactive_matchers) { - _frames_queue[_matchers[id].get()].clear(); + _frames_queue[_matchers[id].get()].q.clear(); } } @@ -506,9 +517,10 @@ namespace librealsense if(!missing->get_active()) return true; - auto next_expected = _next_expected[missing]; + auto const & next_expected = _next_expected[missing]; - if(synced_frame->get_frame_number() - next_expected > 4 || synced_frame->get_frame_number() < next_expected) + if( synced_frame->get_frame_number() - next_expected.value > 4 + || synced_frame->get_frame_number() < next_expected.value ) { return true; } @@ -518,7 +530,7 @@ namespace librealsense void frame_number_composite_matcher::update_next_expected( std::shared_ptr< matcher > const & matcher, const frame_holder & f ) { - _next_expected[matcher.get()] = f.frame->get_frame_number()+1.; + _next_expected[matcher.get()].value = f.frame->get_frame_number()+1.; } std::pair extract_timestamps(frame_holder & a, frame_holder & b) @@ -573,12 +585,12 @@ namespace librealsense fps = fps_md / 1000.; if( fps ) { - //LOG_DEBUG( "fps " << fps << " from metadata" ); + //LOG_DEBUG( "fps " << rsutils::string::from( fps ) << " from metadata " << *f ); } else { fps = f->get_stream()->get_framerate(); - //LOG_DEBUG( "fps " << fps << " from stream framerate" ); + //LOG_DEBUG( "fps " << rsutils::string::from( fps ) << " from stream framerate " << *f ); } return fps; } @@ -592,9 +604,13 @@ namespace librealsense auto ts = f.frame->get_frame_timestamp(); auto ne = ts + gap; - //LOG_DEBUG( "... next_expected = {timestamp}" << ts << " + {gap}(1000/{fps}" << fps << ") = " << ne ); - _next_expected[matcher.get()] = ne; - _next_expected_domain[matcher.get()] = f.frame->get_frame_timestamp_domain(); + //LOG_DEBUG( "... next_expected = {timestamp}" << rsutils::string::from( ts ) << " + {gap}(1000/{fps}" + // << rsutils::string::from( fps ) + // << ") = " << rsutils::string::from( ne ) ); + auto & next_expected = _next_expected[matcher.get()]; + next_expected.value = ne; + next_expected.fps = fps; + next_expected.domain = f.frame->get_frame_timestamp_domain(); } void timestamp_composite_matcher::clean_inactive_streams(frame_holder& f) @@ -615,20 +631,16 @@ namespace librealsense //LOG_IF_ENABLE( "... matcher " << synced[0]->get_name(), env ); - auto next_expected = _next_expected[missing]; + auto const & next_expected = _next_expected[missing]; // LOG_IF_ENABLE( "... next " << std::fixed << next_expected, env ); - auto it = _next_expected_domain.find( missing ); - if( it != _next_expected_domain.end() ) + if( next_expected.domain != last_arrived.timestamp_domain ) { - if( it->second != last_arrived.timestamp_domain ) - { - // LOG_IF_ENABLE( "... not the same domain: frameset not ready!", env ); - // D457 dev - return false removed - // because IR has no md, so its ts domain is "system time" - // other streams have md, and their ts domain is "hardware clock" - //return false; - } + // LOG_IF_ENABLE( "... not the same domain: frameset not ready!", env ); + // D457 dev - return false removed + // because IR has no md, so its ts domain is "system time" + // other streams have md, and their ts domain is "hardware clock" + //return false; } // We want to calculate a cutout for inactive stream detection: if we wait too long past @@ -674,7 +686,7 @@ namespace librealsense auto const fps = get_fps( waiting_to_be_released ); rs2_time_t now = last_arrived.timestamp; - if( now > next_expected ) + if( now > next_expected.value ) { // Wait for the missing stream frame to arrive -- up to a cutout: anything more and we // let the frameset be ready without it... @@ -683,17 +695,21 @@ namespace librealsense // between the streams we're willing to live with. Each gap is a frame so we are limited // by the number of frames we're willing to keep (which is our queue limit) auto threshold = 7 * gap; // really 7+1 because NE is already 1 away - if( now - next_expected < threshold ) + if( now - next_expected.value < threshold ) { - //LOG_IF_ENABLE( "... still below cutout of {NE+7*gap}" << ( next_expected + threshold ), env ); + //LOG_IF_ENABLE( "... still below cutout of {NE+7*gap}" + // << rsutils::string::from( next_expected + threshold ), + // env ); return false; } - LOG_IF_ENABLE( "... exceeded cutout of {NE+7*gap}" << ( next_expected + threshold ) << "; deactivating matcher!", env ); + LOG_IF_ENABLE( "... exceeded cutout of {NE+7*gap}" + << rsutils::string::from( next_expected.value + threshold ) << "; deactivating matcher!", + env ); auto const q_it = _frames_queue.find( missing ); if( q_it != _frames_queue.end() ) { - if( q_it->second.empty() ) + if( q_it->second.q.empty() ) _frames_queue.erase( q_it ); } missing->set_active( false ); @@ -701,8 +717,8 @@ namespace librealsense } return ! are_equivalent( waiting_to_be_released->get_frame_timestamp(), - next_expected, - fps ); // should be min fps to match behavior elsewhere? + next_expected.value, + fps ); } bool timestamp_composite_matcher::are_equivalent( double a, double b, double fps ) @@ -710,11 +726,14 @@ namespace librealsense auto gap = 1000. / fps; if( abs( a - b ) < (gap / 2) ) { - //LOG_DEBUG( "... " << a << " == " << b << " {diff}" << abs( a - b ) << " < " << (gap / 2) << "{gap/2}" ); + //LOG_DEBUG( "... " << rsutils::string::from( a ) << " == " << rsutils::string::from( b ) << " {diff}" + // << abs( a - b ) << " < " << rsutils::string::from( gap / 2 ) << "{gap/2}" ); return true; } - //LOG_DEBUG( "... " << a << " != " << b << " {diff}" << abs( a - b ) << " >= " << ( gap / 2 ) << "{gap/2}" ); + //LOG_DEBUG( "... " << rsutils::string::from( a ) << " != " << rsutils::string::from( b ) << " {diff}" + // << rsutils::string::from( abs( a - b ) ) << " >= " << rsutils::string::from( gap / 2 ) + // << "{gap/2}" ); return false; } @@ -731,7 +750,7 @@ namespace librealsense if (!composite) { std::vector match; - std::stringstream frame_string_for_logging; + std::ostringstream frame_string_for_logging; frame_string_for_logging << f; // Saving frame holder string before moving frame match.push_back(std::move(f)); diff --git a/src/sync.h b/src/sync.h index 53893f1658..803e2c9655 100644 --- a/src/sync.h +++ b/src/sync.h @@ -5,6 +5,7 @@ #include "types.h" #include "archive.h" +#include "core/frame-holder.h" #include #include @@ -110,10 +111,22 @@ namespace librealsense const frame_holder & f ) = 0; - std::map> _frames_queue; + struct matcher_queue + { + single_consumer_frame_queue< frame_holder > q; + + matcher_queue(); + }; + + std::map< matcher *, matcher_queue > _frames_queue; std::map> _matchers; - std::map _next_expected; - std::map _next_expected_domain; + struct next_expected_t + { + double value; // timestamp/frame-number/etc. + double fps; + rs2_timestamp_domain domain; + }; + std::map< matcher *, next_expected_t > _next_expected; std::mutex _mutex; }; diff --git a/src/to-string.cpp b/src/to-string.cpp index 7515514621..32df5c8e50 100644 --- a/src/to-string.cpp +++ b/src/to-string.cpp @@ -66,6 +66,28 @@ const char * get_string( rs2_stream value ) #undef CASE } +char const * get_abbr_string( rs2_stream value) +{ + switch( value ) + { + case RS2_STREAM_ANY: return "Any"; + case RS2_STREAM_DEPTH: return "D"; + case RS2_STREAM_COLOR: return "C"; + case RS2_STREAM_INFRARED: return "IR"; + case RS2_STREAM_FISHEYE: return "FE"; + case RS2_STREAM_GYRO: return "G"; + case RS2_STREAM_ACCEL: return "A"; + case RS2_STREAM_GPIO: return "GPIO"; + case RS2_STREAM_POSE: return "P"; + case RS2_STREAM_CONFIDENCE: return "Conf"; + case RS2_STREAM_MOTION: return "M"; + default: + assert( !is_valid( value ) ); + return "?"; + } +} + + const char * get_string( rs2_sr300_visual_preset value ) { #define CASE( X ) STRCASE( SR300_VISUAL_PRESET, X ) diff --git a/third-party/rsutils/include/rsutils/string/from.h b/third-party/rsutils/include/rsutils/string/from.h index cf0c6dcd26..a1f91a9ced 100644 --- a/third-party/rsutils/include/rsutils/string/from.h +++ b/third-party/rsutils/include/rsutils/string/from.h @@ -28,6 +28,10 @@ struct from _ss << val; } + // Specialty conversion: like std::to_string; fixed, high-precision (6) + // Trims ending 0s and reverts to non-fixed notation if '0.' is the result... + explicit from( double val, int precision = 6 ); + template< class T > from & operator<<( const T & val ) { @@ -45,5 +49,12 @@ struct from }; +inline std::ostream & operator<<( std::ostream & os, from const & f ) +{ + // TODO c++20: use .rdbuf()->view() + return os << f.str(); +} + + } // namespace string } // namespace rsutils diff --git a/third-party/rsutils/py/pyrsutils.cpp b/third-party/rsutils/py/pyrsutils.cpp index 8e852fd3e3..709d174c2e 100644 --- a/third-party/rsutils/py/pyrsutils.cpp +++ b/third-party/rsutils/py/pyrsutils.cpp @@ -46,6 +46,8 @@ PYBIND11_MODULE(NAME, m) { m.def( "executable_path", &rsutils::os::executable_path ); m.def( "executable_name", &rsutils::os::executable_name, py::arg( "with_extension" ) = false ); + m.def( "string_from_double", []( double d ) { return rsutils::string::from( d ).str(); } ); + using rsutils::version; py::class_< version >( m, "version" ) .def( py::init<>() ) diff --git a/third-party/rsutils/src/string-from-datetime.cpp b/third-party/rsutils/src/from.cpp similarity index 72% rename from third-party/rsutils/src/string-from-datetime.cpp rename to third-party/rsutils/src/from.cpp index e1416316ee..86790fe2a0 100644 --- a/third-party/rsutils/src/string-from-datetime.cpp +++ b/third-party/rsutils/src/from.cpp @@ -9,6 +9,25 @@ namespace rsutils { namespace string { +from::from( double d, int precision ) +{ + char base[64]; + auto const len = std::snprintf( base, sizeof( base ), "%.*f", precision, d ); + if( len < 0 || len >= sizeof( base ) ) + _ss << d; + else + { + char const * end = base + len; + while( end > base && end[-1] == '0' ) + --end; + if( *base == '0' && base[1] == '.' && end == base + 2 ) + _ss << d; + else + _ss.write( base, end - base ); + } +} + + std::string from::datetime( tm const * time, char const * format ) { std::string buffer; diff --git a/unit-tests/syncer/sw.py b/unit-tests/syncer/sw.py index 1098a9d5c7..845bb93e4d 100644 --- a/unit-tests/syncer/sw.py +++ b/unit-tests/syncer/sw.py @@ -181,7 +181,7 @@ def reset(): syncer = None -def generate_depth_frame( frame_number, timestamp ): +def generate_depth_frame( frame_number, timestamp, next_expected=None ): """ """ global playback_status @@ -198,10 +198,15 @@ def generate_depth_frame( frame_number, timestamp ): depth_frame.domain = domain depth_frame.profile = depth_profile # - log.d( "-->", depth_frame ) + if next_expected is not None: + actual_fps = round( 1000000 / ( next_expected - timestamp ) ) + depth_sensor.set_metadata( rs.frame_metadata_value.actual_fps, actual_fps ) + log.d( "-->", depth_frame, "with actual FPS", actual_fps ) + else: + log.d( "-->", depth_frame ) depth_sensor.on_video_frame( depth_frame ) -def generate_color_frame( frame_number, timestamp ): +def generate_color_frame( frame_number, timestamp, next_expected=None ): """ """ global playback_status @@ -218,7 +223,12 @@ def generate_color_frame( frame_number, timestamp ): color_frame.domain = domain color_frame.profile = color_profile # - log.d( "-->", color_frame ) + if next_expected is not None: + actual_fps = round( 1000000 / ( next_expected - timestamp ) ) + color_sensor.set_metadata( rs.frame_metadata_value.actual_fps, actual_fps ) + log.d( "-->", color_frame, "with actual FPS", actual_fps ) + else: + log.d( "-->", color_frame ) color_sensor.on_video_frame( color_frame ) def generate_depth_and_color( frame_number, timestamp ): diff --git a/unit-tests/syncer/test-ts-desync-2.py b/unit-tests/syncer/test-ts-desync-2.py new file mode 100644 index 0000000000..4f9fd9942f --- /dev/null +++ b/unit-tests/syncer/test-ts-desync-2.py @@ -0,0 +1,101 @@ +# License: Apache 2.0. See LICENSE file in root directory. +# Copyright(c) 2023 Intel Corporation. All Rights Reserved. + +import pyrealsense2 as rs +from rspy import log, test +import sw + + +# +# This is a reproduction of a problem we saw with externally-synced cameras, where the master +# camera is OK but the slave cameras generate delayed color frames (Depth at time X arrives 4ms +# sooner than Color at time X-18ms) with exaggerated next-expected because of low-calculated-fps +# (29 versus the nominal 30 that's supposed to be seen). +# +# This should no longer happen as recorded because the captured FPS, and therefore estimated +# next-expected, is much more accurate: part of the problem was that ACTUAL_FPS was crudely +# misrepresented (29.98 became 29). Nonetheless, with the below capture times, this is the behavior +# we expect. +# +# See [RSDSO-19336] +# + + +sw.fps_d = 30 +sw.fps_c = 30 +sw.init() +sw.start() + +############################################################################################# +with test.closure( "Init" ): + # It can take a few frames for the syncer to actually produce a matched frameset (it doesn't + # know what to match to in the beginning) + + sw.generate_color_frame( frame_number=1730, timestamp=63198.01542, next_expected=63231.348758 ) + sw.expect( color_frame=1730 ) # syncer doesn't know about D yet, so releases right away + sw.generate_depth_frame( frame_number=1742, timestamp=63214.73 ) + sw.expect_nothing() # should be waiting for next color + +############################################################################################# +with test.closure( "Sync D1742 & C1731" ): + sw.generate_depth_frame( frame_number=1743, timestamp=63248.07 ) + sw.expect_nothing() # still waiting for next color with 1742 + sw.generate_color_frame( frame_number=1731, timestamp=63230.22, next_expected=63264.698758 ) + sw.expect( depth_frame=1742, color_frame=1731, nothing_else=True ) # no hope for a match: D1743 is already out, so it's released + +############################################################################################# +with test.closure( "Sync D1743 & C1732" ): + sw.generate_depth_frame( frame_number=1744, timestamp=63281.41 ) + sw.expect_nothing() # should be waiting for next color + sw.generate_color_frame( frame_number=1732, timestamp=63263.57, next_expected=63298.049758 ) + sw.expect( depth_frame=1743, color_frame=1732, nothing_else=True ) + +############################################################################################# +with test.closure( "Sync D1744 & C1733" ): + sw.generate_depth_frame( frame_number=1745, timestamp=63314.76 ) + sw.expect_nothing() # should be waiting for next color + sw.generate_color_frame( frame_number=1733, timestamp=63296.92, next_expected=63331.399758 ) + sw.expect( depth_frame=1744, color_frame=1733, nothing_else=True ) + +############################################################################################# +with test.closure( "Sync D1745 & C1734" ): + sw.generate_depth_frame( frame_number=1746, timestamp=63348.10 ) + sw.expect_nothing() # should be waiting for next color + sw.generate_color_frame( frame_number=1734, timestamp=63330.27, next_expected=63364.750758 ) + sw.expect( depth_frame=1745, color_frame=1734, nothing_else=True ) + +############################################################################################# +with test.closure( "Sync D1746 & C1735" ): + sw.generate_depth_frame( frame_number=1747, timestamp=63381.45 ) + sw.expect_nothing() # should be waiting for next color + sw.generate_color_frame( frame_number=1735, timestamp=63363.62, next_expected=63398.100758 ) + sw.expect( depth_frame=1746, color_frame=1735, nothing_else=True ) + +############################################################################################# +with test.closure( "Sync D1747 & C1736" ): + sw.generate_depth_frame( frame_number=1748, timestamp=63414.79 ) + sw.expect_nothing() # should be waiting for next color + sw.generate_color_frame( frame_number=1736, timestamp=63396.97, next_expected=63431.451758 ) + sw.expect( depth_frame=1747, color_frame=1736, nothing_else=True ) + +############################################################################################# +with test.closure( "Sync D1748 & C1737" ): + sw.generate_depth_frame( frame_number=1749, timestamp=63448.13 ) + sw.expect_nothing() # should be waiting for next color + sw.generate_color_frame( frame_number=1737, timestamp=63430.32, next_expected=63464.801758 ) + sw.expect( depth_frame=1748, color_frame=1737 ) + +############################################################################################# +with test.closure( "LONE D1749!" ): + sw.expect( depth_frame=1749, nothing_else=True ) + +############################################################################################# +with test.closure( "No sync on D1750 & C1738" ): + sw.generate_depth_frame( frame_number=1750, timestamp=63481.48 ) + sw.expect_nothing() # should be waiting for next color + sw.generate_color_frame( frame_number=1738, timestamp=63463.67, next_expected=63498.152758 ) + sw.expect( color_frame=1738 ) + sw.expect( depth_frame=1750 ) + +############################################################################################# +test.print_results_and_exit() diff --git a/unit-tests/syncer/test-ts-desync.py b/unit-tests/syncer/test-ts-desync.py index 6d81c3f59d..0b2d7fa29d 100644 --- a/unit-tests/syncer/test-ts-desync.py +++ b/unit-tests/syncer/test-ts-desync.py @@ -61,8 +61,8 @@ # 3 @7952 -> needs to be released BEFORE C2!! # # NOTE: the timestamp is the SAME AS BEFORE! Imagine that, instead of a Depth frame, this was -# an Infrared: the matcher would be (TS: (TS: Depth Infra Confidence) Color). But we have no -# Infra or Confidence mechanism (in sw) so we just generate another D -- it should have the +# an Infrared: the matcher would be (TS: (TS: Depth Infra Confidence) Color). But we have no +# Infra or Confidence mechanism (in sw) so we just generate another D -- it should have the # same effect: # # NOTE: this used to crash (see LRS-289)! diff --git a/unit-tests/syncer/test-ts-diff-fps.py b/unit-tests/syncer/test-ts-diff-fps.py index b518e2d46d..a36ec0cc83 100644 --- a/unit-tests/syncer/test-ts-diff-fps.py +++ b/unit-tests/syncer/test-ts-diff-fps.py @@ -102,7 +102,7 @@ sw.generate_depth_frame( 17, sw.gap_d * 17 ); sw.expect( depth_frame = 17 ) sw.generate_color_frame( 2, sw.gap_c * 2 ); sw.expect_nothing() -# We're waiting for D.NE @180, because it's comparable (using min fps of the two) +# We're waiting for D.NE @180, because it's comparable (using min fps of the two) sw.generate_depth_frame( 18, sw.gap_d * 18 ) # Now we get both back: diff --git a/wrappers/python/pyrs_frame.cpp b/wrappers/python/pyrs_frame.cpp index e7fd8362fd..4353b89400 100644 --- a/wrappers/python/pyrs_frame.cpp +++ b/wrappers/python/pyrs_frame.cpp @@ -4,8 +4,25 @@ Copyright(c) 2017 Intel Corporation. All Rights Reserved. */ #include "pyrealsense2.h" #include +#include #include // bad idea? for get_image_bpp + +namespace { + + + std::ostream & operator<<( std::ostream & ss, const rs2::frame & self ) + { + ss << rs2_format_to_string( self.get_profile().format() ); + ss << " #" << self.get_frame_number(); + ss << " @" << rsutils::string::from( self.get_timestamp() ); + return ss; + } + + +} + + void init_frame(py::module &m) { py::class_ BufData_py(m, "BufData", py::buffer_protocol()); BufData_py.def_buffer([](BufData& self) @@ -153,14 +170,12 @@ void init_frame(py::module &m) { { ss << "set"; for( auto sf : fs ) - ss << " " << rs2_format_to_string( sf.get_profile().format() ); + ss << " " << sf; } else { - ss << " " << rs2_format_to_string( self.get_profile().format() ); + ss << " " << self; } - ss << " #" << self.get_frame_number(); - ss << " @" << std::fixed << self.get_timestamp(); } ss << ">"; return ss.str();