Skip to content

Commit

Permalink
PR #11375 from maloel: C++latest, step 1
Browse files Browse the repository at this point in the history
  • Loading branch information
Nir-Az committed Jan 30, 2023
2 parents b7e4936 + ba3d2b0 commit 400db66
Show file tree
Hide file tree
Showing 59 changed files with 160 additions and 153 deletions.
6 changes: 3 additions & 3 deletions src/ds/ds5/ds5-auto-calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -461,7 +461,7 @@ namespace librealsense
if (host_assistance != host_assistance_type::no_assistance)
if (count < 20) progress_callback->on_update_progress(static_cast<float>(80 + count++));
else
progress_callback->on_update_progress(count++ * (2.f * speed)); //curently this number does not reflect the actual progress
progress_callback->on_update_progress(count++ * (2.f * static_cast<int>(speed))); //curently this number does not reflect the actual progress
}
}, false);
// Handle errors from firmware
Expand Down Expand Up @@ -550,7 +550,7 @@ namespace librealsense
if (host_assistance != host_assistance_type::no_assistance)
if (count < 20) progress_callback->on_update_progress(static_cast<float>(80 + count++));
else
progress_callback->on_update_progress(count++ * (2.f * speed)); //curently this number does not reflect the actual progress
progress_callback->on_update_progress(count++ * (2.f * static_cast<int>(speed))); //curently this number does not reflect the actual progress
}
});
std::this_thread::sleep_for(std::chrono::milliseconds(100));
Expand Down Expand Up @@ -778,7 +778,7 @@ namespace librealsense
if (host_assistance != host_assistance_type::no_assistance)
if (count < 20) progress_callback->on_update_progress(static_cast<float>(80 + count++));
else
progress_callback->on_update_progress(count++* (2.f * speed)); //curently this number does not reflect the actual progress
progress_callback->on_update_progress(count++* (2.f * static_cast<int>(speed))); //curently this number does not reflect the actual progress
}

now = std::chrono::high_resolution_clock::now();
Expand Down
6 changes: 3 additions & 3 deletions src/l500/l500-color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ namespace librealsense

auto host_perf = get_option(RS2_OPTION_HOST_PERFORMANCE).query();

if (host_perf == RS2_HOST_PERF_LOW || host_perf == RS2_HOST_PERF_HIGH)
if (static_cast<int>(host_perf) == RS2_HOST_PERF_LOW || static_cast<int>(host_perf) == RS2_HOST_PERF_HIGH)
{
// TPROC USB Granularity and TRB threshold settings for improved performance and stability
// on hosts with weak cpu and system performance
Expand All @@ -393,7 +393,7 @@ namespace librealsense
// and improve performance
int usb_trb = 7; // 7 KB

if (host_perf == RS2_HOST_PERF_LOW)
if (static_cast<int>(host_perf) == RS2_HOST_PERF_LOW)
{
usb_trb = 32; // 32 KB
}
Expand All @@ -414,7 +414,7 @@ namespace librealsense
LOG_WARNING("Failed to update color usb tproc granularity and TRB threshold. performance and stability maybe impacted on certain platforms.");
}
}
else if (host_perf == RS2_HOST_PERF_DEFAULT)
else if (static_cast<int>(host_perf) == RS2_HOST_PERF_DEFAULT)
{
LOG_DEBUG("Default host performance mode, color usb tproc granularity and TRB threshold not changed");
}
Expand Down
6 changes: 3 additions & 3 deletions src/l500/l500-depth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -417,7 +417,7 @@ namespace librealsense

auto host_perf = get_option(RS2_OPTION_HOST_PERFORMANCE).query();

if (host_perf == RS2_HOST_PERF_LOW || host_perf == RS2_HOST_PERF_HIGH)
if (static_cast<int>(host_perf) == RS2_HOST_PERF_LOW || static_cast<int>(host_perf) == RS2_HOST_PERF_HIGH)
{
// TPROC USB Granularity and TRB threshold settings for improved performance and stability
// on hosts with weak cpu and system performance
Expand All @@ -429,7 +429,7 @@ namespace librealsense
int ep3_usb_trb = 3; // 3 KB
int ep4_usb_trb = 3; // 3 KB

if (host_perf == RS2_HOST_PERF_LOW)
if (static_cast<int>(host_perf) == RS2_HOST_PERF_LOW)
{
ep2_usb_trb = 16; // 16 KB
ep3_usb_trb = 12; // 12 KB
Expand Down Expand Up @@ -466,7 +466,7 @@ namespace librealsense
LOG_WARNING("FAILED TO UPDATE depth usb tproc granularity and TRB threshold. performance and stability maybe impacted on certain platforms.");
}
}
else if (host_perf == RS2_HOST_PERF_DEFAULT)
else if (static_cast<int>(host_perf) == RS2_HOST_PERF_DEFAULT)
{
LOG_DEBUG("Default host performance mode, Depth/IR/Confidence usb tproc granularity and TRB threshold not changed");
}
Expand Down
10 changes: 5 additions & 5 deletions src/l500/l500-options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -547,7 +547,7 @@ namespace librealsense
== 1.0f ) )
{
if( ( RS2_OPTION_VISUAL_PRESET == opt )
&& ( value == RS2_L500_VISUAL_PRESET_MAX_RANGE ) )
&& (static_cast<int>(value) == RS2_L500_VISUAL_PRESET_MAX_RANGE ) )
return;

throw wrong_api_call_sequence_exception(
Expand Down Expand Up @@ -757,7 +757,7 @@ namespace librealsense
{
auto &sensor_mode_option = ds.get_option(RS2_OPTION_SENSOR_MODE);
auto sensor_mode = sensor_mode_option.query();
bool sensor_mode_is_vga = (sensor_mode == rs2_sensor_mode::RS2_SENSOR_MODE_VGA);
bool sensor_mode_is_vga = (static_cast<int>(sensor_mode) == rs2_sensor_mode::RS2_SENSOR_MODE_VGA);

bool visual_preset_is_max_range = ds.is_max_range_preset();

Expand Down Expand Up @@ -806,15 +806,15 @@ namespace librealsense

if( ds.supports_option( RS2_OPTION_ENABLE_IR_REFLECTIVITY )
&& ds.get_option( RS2_OPTION_ENABLE_IR_REFLECTIVITY ).query() == 1.0f
&& ( value != rs2_sensor_mode::RS2_SENSOR_MODE_VGA ) )
&& (static_cast<int>(value) != rs2_sensor_mode::RS2_SENSOR_MODE_VGA ) )
{
ds.get_option( RS2_OPTION_ENABLE_IR_REFLECTIVITY ).set( 0.0f );
LOG_INFO( "IR Reflectivity was on - turning it off" );
}

if( ds.supports_option( RS2_OPTION_ENABLE_MAX_USABLE_RANGE )
&& ( ds.get_option( RS2_OPTION_ENABLE_MAX_USABLE_RANGE ).query() == 1.0f )
&& ( value != rs2_sensor_mode::RS2_SENSOR_MODE_VGA ) )
&& (static_cast<int>(value) != rs2_sensor_mode::RS2_SENSOR_MODE_VGA ) )
{
ds.get_option( RS2_OPTION_ENABLE_MAX_USABLE_RANGE ).set( 0.0f );
LOG_INFO( "Max Usable Range was on - turning it off" );
Expand Down Expand Up @@ -852,7 +852,7 @@ namespace librealsense

auto &sensor_mode_option = ds.get_option(RS2_OPTION_SENSOR_MODE);
auto sensor_mode = sensor_mode_option.query();
bool sensor_mode_is_vga = (sensor_mode == rs2_sensor_mode::RS2_SENSOR_MODE_VGA);
bool sensor_mode_is_vga = (static_cast<int>(sensor_mode) == rs2_sensor_mode::RS2_SENSOR_MODE_VGA);

bool visual_preset_is_max_range = ds.is_max_range_preset();

Expand Down
2 changes: 1 addition & 1 deletion src/media/record/record_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,7 +215,7 @@ void record_sensor::unregister_before_start_callback(int token)
}

template <typename T>
void librealsense::record_sensor::record_snapshot(rs2_extension extension_type, const recordable<T>& ext)
void librealsense::record_sensor::record_snapshot(rs2_extension extension_type, const librealsense::recordable<T>& ext)
{
std::shared_ptr<T> snapshot;
ext.create_snapshot(snapshot);
Expand Down
2 changes: 1 addition & 1 deletion src/media/record/record_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace librealsense
virtual processing_blocks get_recommended_processing_blocks() const override;

private /*methods*/:
template <typename T> void record_snapshot(rs2_extension extension_type, const recordable<T>& snapshot);
template <typename T> void record_snapshot(rs2_extension extension_type, const librealsense::recordable<T>& snapshot);
template <rs2_extension E, typename P> bool extend_to_aux(P* p, void** ext);
void record_frame(frame_holder holder);
void enable_sensor_hooks();
Expand Down
20 changes: 13 additions & 7 deletions src/mf/mf-hid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -387,10 +387,18 @@ namespace librealsense
if (SUCCEEDED(pSensorCollection->GetAt(i, &pSensor.p)))
{
/* Retrieve SENSOR_PROPERTY_FRIENDLY_NAME which is the sensor name that is intended to be seen by the user */
BSTR fName{};
LOG_HR(res = pSensor->GetFriendlyName(&fName));
if (FAILED(res))
fName= L"Unidentified HID sensor";
std::string sensor_id;
{
BSTR fName;
LOG_HR( res = pSensor->GetFriendlyName( &fName ) );
if( FAILED( res ) )
sensor_id = "Unidentified HID sensor";
else
{
sensor_id = rsutils::string::windows::win_to_utf( fName );
SysFreeString( fName );
}
}

/* Retrieve SENSOR_PROPERTY_PERSISTENT_UNIQUE_ID which is a GUID that uniquely identifies the sensor on the current computer */
SENSOR_ID id{};
Expand Down Expand Up @@ -425,7 +433,7 @@ namespace librealsense
if (IsEqualPropertyKey(propertyKey, SENSOR_PROPERTY_DEVICE_PATH))
{
info.device_path = rsutils::string::windows::win_to_utf( propertyValue.pwszVal );
info.id = rsutils::string::windows::win_to_utf( fName );
info.id = sensor_id;

uint16_t vid, pid, mi;
std::string uid, guid;
Expand Down Expand Up @@ -472,8 +480,6 @@ namespace librealsense
}

action(info, pSensor);

SysFreeString(fName);
}
//Releasing resources
safe_release(pSensor);
Expand Down
17 changes: 9 additions & 8 deletions src/mf/mf-hid.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,16 +18,17 @@ namespace librealsense
wmf_hid_sensor(const hid_device_info& device_info, CComPtr<ISensor> pISensor) :
_hid_device_info(device_info), _pISensor(pISensor)
{
BSTR fName{};

auto res = pISensor->GetFriendlyName(&fName);
if (FAILED(res))
BSTR fName;
auto res = pISensor->GetFriendlyName( &fName );
if( FAILED( res ) )
{
fName = L"Unidentified HID Sensor";
_name = CW2A( L"Unidentified HID Sensor" );
}
else
{
_name = CW2A( fName );
SysFreeString( fName );
}

_name = CW2A(fName);
SysFreeString(fName);
};

const std::string& get_sensor_name() const { return _name; }
Expand Down
8 changes: 4 additions & 4 deletions src/mf/mf-uvc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1132,10 +1132,10 @@ namespace librealsense

check_connection();

auto& elem = std::find_if(_streams.begin(), _streams.end(),
[&](const profile_and_callback& pac) {
return (pac.profile == profile && (pac.callback));
});
auto elem = std::find_if( _streams.begin(),
_streams.end(),
[&]( const profile_and_callback & pac )
{ return ( pac.profile == profile && ( pac.callback ) ); } );

if (elem == _streams.end() && _frame_callbacks.empty())
throw std::runtime_error("Camera is not streaming!");
Expand Down
2 changes: 1 addition & 1 deletion src/win/win-helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -757,7 +757,7 @@ namespace librealsense

PSECURITY_DESCRIPTOR make_allow_all_security_descriptor(void)
{
WCHAR *pszStringSecurityDescriptor;
WCHAR const *pszStringSecurityDescriptor;
pszStringSecurityDescriptor = L"D:(A;;GA;;;WD)(A;;GA;;;AN)S:(ML;;NW;;;ME)";
PSECURITY_DESCRIPTOR pSecDesc;
if (!ConvertStringSecurityDescriptorToSecurityDescriptor(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ struct KeyValue_



typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _key_type;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _key_type;
_key_type key;

typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _value_type;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _value_type;
_value_type value;


Expand Down Expand Up @@ -183,9 +183,9 @@ struct Printer< ::diagnostic_msgs::KeyValue_<ContainerAllocator> >
template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::diagnostic_msgs::KeyValue_<ContainerAllocator>& v)
{
s << indent << "key: ";
Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.key);
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.key);
s << indent << "value: ";
Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.value);
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.value);
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ struct Polygon_



typedef std::vector< ::geometry_msgs::Point32_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point32_<ContainerAllocator> >::other > _points_type;
typedef std::vector< ::geometry_msgs::Point32_<ContainerAllocator> , typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< ::geometry_msgs::Point32_<ContainerAllocator> > > _points_type;
_points_type points;


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ struct PoseArray_
typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
_header_type header;

typedef std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > _poses_type;
typedef std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< ::geometry_msgs::Pose_<ContainerAllocator> > > _poses_type;
_poses_type poses;


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ struct TransformStamped_
typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
_header_type header;

typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _child_frame_id_type;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _child_frame_id_type;
_child_frame_id_type child_frame_id;

typedef ::geometry_msgs::Transform_<ContainerAllocator> _transform_type;
Expand Down Expand Up @@ -248,7 +248,7 @@ struct Printer< ::geometry_msgs::TransformStamped_<ContainerAllocator> >
s << std::endl;
Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
s << indent << "child_frame_id: ";
Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.child_frame_id);
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.child_frame_id);
s << indent << "transform: ";
s << std::endl;
Printer< ::geometry_msgs::Transform_<ContainerAllocator> >::stream(s, indent + " ", v.transform);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ struct compressed_frame_info_
typedef uint64_t _system_time_type;
_system_time_type system_time;

typedef std::vector< ::realsense_legacy_msgs::metadata_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::realsense_legacy_msgs::metadata_<ContainerAllocator> >::other > _frame_metadata_type;
typedef std::vector< ::realsense_legacy_msgs::metadata_<ContainerAllocator> , typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< ::realsense_legacy_msgs::metadata_<ContainerAllocator> > > _frame_metadata_type;
_frame_metadata_type frame_metadata;

typedef uint32_t _time_stamp_domain_type;
Expand All @@ -61,7 +61,7 @@ struct compressed_frame_info_
typedef uint32_t _height_type;
_height_type height;

typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _encoding_type;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _encoding_type;
_encoding_type encoding;

typedef uint32_t _step_type;
Expand Down Expand Up @@ -240,7 +240,7 @@ struct Printer< ::realsense_legacy_msgs::compressed_frame_info_<ContainerAllocat
s << indent << "height: ";
Printer<uint32_t>::stream(s, indent + " ", v.height);
s << indent << "encoding: ";
Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.encoding);
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.encoding);
s << indent << "step: ";
Printer<uint32_t>::stream(s, indent + " ", v.step);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ struct frame_info_
typedef uint64_t _system_time_type;
_system_time_type system_time;

typedef std::vector< ::realsense_legacy_msgs::metadata_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::realsense_legacy_msgs::metadata_<ContainerAllocator> >::other > _frame_metadata_type;
typedef std::vector< ::realsense_legacy_msgs::metadata_<ContainerAllocator> , typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< ::realsense_legacy_msgs::metadata_<ContainerAllocator> > > _frame_metadata_type;
_frame_metadata_type frame_metadata;

typedef uint32_t _time_stamp_domain_type;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ struct metadata_
typedef uint32_t _type_type;
_type_type type;

typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _data_type;
typedef std::vector<uint8_t, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< uint8_t > > _data_type;
_data_type data;


Expand Down
Loading

0 comments on commit 400db66

Please sign in to comment.