Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

remove deprecated L500 APIs #12354

Merged
merged 3 commits into from
Nov 5, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 0 additions & 18 deletions include/librealsense2/h/rs_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -635,24 +635,6 @@ void rs2_override_intrinsics( const rs2_sensor* sensor, const rs2_intrinsics* in
*/
void rs2_set_extrinsics(const rs2_sensor* from_sensor, const rs2_stream_profile* from_profile, rs2_sensor* to_sensor, const rs2_stream_profile* to_profile, const rs2_extrinsics* extrinsics, rs2_error** error);

/**
* Get the DSM parameters for a sensor
* \param[in] sensor Sensor that supports the CALIBRATED_SENSOR extension
* \param[out] p_params_out Pointer to the structure that will get the DSM parameters
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_get_dsm_params( rs2_sensor const * sensor, rs2_dsm_params * p_params_out, rs2_error** error );

/**
* Set the sensor DSM parameters
* This should ideally be done when the stream is NOT running. If it is, the
* parameters may not take effect immediately.
* \param[in] sensor Sensor that supports the CALIBRATED_SENSOR extension
* \param[out] p_params Pointer to the structure that contains the DSM parameters
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_override_dsm_params( rs2_sensor const * sensor, rs2_dsm_params const * p_params, rs2_error** error );

/**
* Reset the sensor DSM parameters
* This should ideally be done when the stream is NOT running. May not take effect immediately.
Expand Down
32 changes: 0 additions & 32 deletions include/librealsense2/h/rs_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,38 +67,6 @@ typedef struct rs2_intrinsics
float coeffs[5]; /**< Distortion coefficients. Order for Brown-Conrady: [k1, k2, p1, p2, k3]. Order for F-Theta Fish-eye: [k1, k2, k3, k4, 0]. Other models are subject to their own interpretations */
} rs2_intrinsics;

/** \brief Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params)
This is the block in MC that converts angles to dimensionless integers reported to MA (using "DSM coefficients").
*/
#pragma pack( push, 1 )
typedef struct rs2_dsm_params
{
unsigned long long timestamp; /**< system_clock::time_point::time_since_epoch().count() */
unsigned short version; /**< MAJOR<<12 | MINOR<<4 | PATCH */
unsigned char model; /**< rs2_dsm_correction_model */
unsigned char flags[5]; /**< TBD, now 0s */
float h_scale; /**< the scale factor to horizontal DSM scale thermal results */
float v_scale; /**< the scale factor to vertical DSM scale thermal results */
float h_offset; /**< the offset to horizontal DSM offset thermal results */
float v_offset; /**< the offset to vertical DSM offset thermal results */
float rtd_offset; /**< the offset to the Round-Trip-Distance delay thermal results */
unsigned char temp_x2; /**< the temperature recorded times 2 (ldd for depth; hum for rgb) */
float mc_h_scale; /**< the scale factor to horizontal LOS coefficients in MC */
float mc_v_scale; /**< the scale factor to vertical LOS coefficients in MC */
unsigned char weeks_since_calibration; /**< time (in weeks) since factory calibration */
unsigned char ac_weeks_since_calibaration; /**< time (in weeks) between factory calibration and last AC event */
unsigned char reserved[1];
} rs2_dsm_params;
#pragma pack( pop )

typedef enum rs2_dsm_correction_model
{
RS2_DSM_CORRECTION_NONE, /**< hFactor and hOffset are not used, and no artificial error is induced */
RS2_DSM_CORRECTION_AOT, /**< Aging-over-thermal (default); aging-induced error is uniform across temperature */
RS2_DSM_CORRECTION_TOA, /**< Thermal-over-aging; aging-induced error changes alongside temperature */
RS2_DSM_CORRECTION_COUNT
} rs2_dsm_correction_model;

/** \brief Motion device intrinsics: scale, bias, and variances. */
typedef struct rs2_motion_device_intrinsic
{
Expand Down
62 changes: 0 additions & 62 deletions include/librealsense2/hpp/rs_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -663,68 +663,6 @@ namespace rs2
explicit wheel_odometer(std::shared_ptr<rs2_sensor> dev) : wheel_odometer(sensor(dev)) {}
};

class calibrated_sensor : public sensor
{
public:
calibrated_sensor( sensor s )
: sensor( s.get() )
{
rs2_error* e = nullptr;
if( rs2_is_sensor_extendable_to( _sensor.get(), RS2_EXTENSION_CALIBRATED_SENSOR, &e ) == 0 && !e )
{
_sensor.reset();
}
error::handle( e );
}

operator bool() const { return _sensor.get() != nullptr; }

/** Override the intrinsics at the sensor level, as DEPTH_TO_RGB calibration does */
void override_intrinsics( rs2_intrinsics const& intr )
{
rs2_error* e = nullptr;
rs2_override_intrinsics( _sensor.get(), &intr, &e );
error::handle( e );
}

/** Override the intrinsics at the sensor level, as DEPTH_TO_RGB calibration does */
void override_extrinsics( rs2_extrinsics const& extr )
{
rs2_error* e = nullptr;
rs2_override_extrinsics( _sensor.get(), &extr, &e );
error::handle( e );
}

/** Override the intrinsics at the sensor level, as DEPTH_TO_RGB calibration does */
rs2_dsm_params get_dsm_params() const
{
rs2_error* e = nullptr;
rs2_dsm_params params;
rs2_get_dsm_params( _sensor.get(), &params, &e );
error::handle( e );
return params;
}

/** Set the sensor DSM parameters
* This should ideally be done when the stream is NOT running. If it is, the
* parameters may not take effect immediately. */
void override_dsm_params( rs2_dsm_params const & params )
{
rs2_error* e = nullptr;
rs2_override_dsm_params( _sensor.get(), &params, &e );
error::handle( e );
}

/** Reset the sensor DSM calibration
*/
void reset_calibration()
{
rs2_error* e = nullptr;
rs2_reset_sensor_calibration( _sensor.get(), &e );
error::handle( e );
}
};

class max_usable_range_sensor : public sensor
{
public:
Expand Down
1 change: 0 additions & 1 deletion src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,6 @@ target_sources(${LRS_TARGET}
"${CMAKE_CURRENT_LIST_DIR}/platform/command-transfer.h"
"${CMAKE_CURRENT_LIST_DIR}/auto-calibrated-device.h"
"${CMAKE_CURRENT_LIST_DIR}/device-calibration.h"
"${CMAKE_CURRENT_LIST_DIR}/calibrated-sensor.h"
"${CMAKE_CURRENT_LIST_DIR}/serializable-interface.h"
"${CMAKE_CURRENT_LIST_DIR}/max-usable-range-sensor.h"
"${CMAKE_CURRENT_LIST_DIR}/debug-stream-sensor.h"
Expand Down
24 changes: 0 additions & 24 deletions src/calibrated-sensor.h

This file was deleted.

2 changes: 1 addition & 1 deletion src/max-usable-range-sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#pragma once

#include "types.h"
#include "core/extension.h"

namespace librealsense
{
Expand Down
2 changes: 0 additions & 2 deletions src/realsense.def
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,6 @@ EXPORTS
rs2_override_extrinsics
rs2_get_motion_intrinsics
rs2_override_intrinsics
rs2_get_dsm_params
rs2_override_dsm_params
rs2_reset_sensor_calibration

rs2_get_stream_profiles
Expand Down
40 changes: 4 additions & 36 deletions src/rs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,6 @@
#include "terminal-parser.h"
#include "firmware_logger_device.h"
#include "device-calibration.h"
#include "calibrated-sensor.h"
#include <librealsense2/h/rs_internal.h>
#include "debug-stream-sensor.h"
#include "max-usable-range-sensor.h"
Expand Down Expand Up @@ -1226,40 +1225,13 @@ HANDLE_EXCEPTIONS_AND_RETURN(, from, to, extrin)

void rs2_override_extrinsics( const rs2_sensor* sensor, const rs2_extrinsics* extrinsics, rs2_error** error ) BEGIN_API_CALL
{
VALIDATE_NOT_NULL( sensor );
VALIDATE_NOT_NULL( extrinsics );

auto ois = VALIDATE_INTERFACE( sensor->sensor, librealsense::calibrated_sensor );
ois->override_extrinsics( *extrinsics );
throw not_implemented_exception( "deprecated" );
}
HANDLE_EXCEPTIONS_AND_RETURN( , sensor, extrinsics )

void rs2_get_dsm_params( const rs2_sensor * sensor, rs2_dsm_params * p_params_out, rs2_error** error ) BEGIN_API_CALL
{
VALIDATE_NOT_NULL( sensor );
VALIDATE_NOT_NULL( p_params_out );

auto cs = VALIDATE_INTERFACE( sensor->sensor, librealsense::calibrated_sensor );
*p_params_out = cs->get_dsm_params();
}
HANDLE_EXCEPTIONS_AND_RETURN( , sensor, p_params_out )

void rs2_override_dsm_params( const rs2_sensor * sensor, rs2_dsm_params const * p_params, rs2_error** error ) BEGIN_API_CALL
{
VALIDATE_NOT_NULL( sensor );
VALIDATE_NOT_NULL( p_params );

auto cs = VALIDATE_INTERFACE( sensor->sensor, librealsense::calibrated_sensor );
cs->override_dsm_params( *p_params );
}
HANDLE_EXCEPTIONS_AND_RETURN( , sensor, p_params )

void rs2_reset_sensor_calibration( rs2_sensor const * sensor, rs2_error** error ) BEGIN_API_CALL
{
VALIDATE_NOT_NULL( sensor );

auto cs = VALIDATE_INTERFACE( sensor->sensor, librealsense::calibrated_sensor );
cs->reset_calibration();
throw not_implemented_exception( "deprecated" );
}
HANDLE_EXCEPTIONS_AND_RETURN( , sensor )

Expand Down Expand Up @@ -1469,7 +1441,7 @@ int rs2_is_sensor_extendable_to(const rs2_sensor* sensor, rs2_extension extensio
case RS2_EXTENSION_COLOR_SENSOR : return VALIDATE_INTERFACE_NO_THROW(sensor->sensor, librealsense::color_sensor) != nullptr;
case RS2_EXTENSION_MOTION_SENSOR : return VALIDATE_INTERFACE_NO_THROW(sensor->sensor, librealsense::motion_sensor) != nullptr;
case RS2_EXTENSION_FISHEYE_SENSOR : return VALIDATE_INTERFACE_NO_THROW(sensor->sensor, librealsense::fisheye_sensor) != nullptr;
case RS2_EXTENSION_CALIBRATED_SENSOR : return VALIDATE_INTERFACE_NO_THROW(sensor->sensor, librealsense::calibrated_sensor) != nullptr;
case RS2_EXTENSION_CALIBRATED_SENSOR : return false;
case RS2_EXTENSION_MAX_USABLE_RANGE_SENSOR : return VALIDATE_INTERFACE_NO_THROW(sensor->sensor, librealsense::max_usable_range_sensor)!= nullptr;
case RS2_EXTENSION_DEBUG_STREAM_SENSOR : return VALIDATE_INTERFACE_NO_THROW(sensor->sensor, librealsense::debug_stream_sensor ) != nullptr;

Expand Down Expand Up @@ -2786,11 +2758,7 @@ HANDLE_EXCEPTIONS_AND_RETURN(, sensor, profile, intrinsics)

void rs2_override_intrinsics( const rs2_sensor* sensor, const rs2_intrinsics* intrinsics, rs2_error** error ) BEGIN_API_CALL
{
VALIDATE_NOT_NULL( sensor );
VALIDATE_NOT_NULL( intrinsics );

auto ois = VALIDATE_INTERFACE( sensor->sensor, librealsense::calibrated_sensor );
ois->override_intrinsics( *intrinsics );
throw not_implemented_exception( "deprecated" );
}
HANDLE_EXCEPTIONS_AND_RETURN( , sensor, intrinsics )

Expand Down
37 changes: 0 additions & 37 deletions src/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -871,43 +871,6 @@ inline std::ostream& operator<<( std::ostream& out, rs2_intrinsics const & i )
<< "] ]";
}

inline std::ostream& operator<<( std::ostream& s, rs2_dsm_params const & self )
{
s << "[ ";
if( self.timestamp )
{
time_t t = self.timestamp;
auto ptm = localtime( &t );
char buf[256];
strftime( buf, sizeof( buf ), "%F.%T ", ptm );
s << buf;

unsigned patch = self.version & 0xF;
unsigned minor = (self.version >> 4) & 0xFF;
unsigned major = (self.version >> 12);
s << major << '.' << minor << '.' << patch << ' ';
}
else
{
s << "new: ";
}
switch( self.model )
{
case RS2_DSM_CORRECTION_NONE: break;
case RS2_DSM_CORRECTION_AOT: s << "AoT "; break;
case RS2_DSM_CORRECTION_TOA: s << "ToA "; break;
}
s << "x[" << self.h_scale << " " << self.v_scale << "] ";
s << "+[" << self.h_offset << " " << self.v_offset;
if( self.rtd_offset )
s << " rtd " << self.rtd_offset;
s << "]";
if( self.temp_x2 )
s << " @" << float( self.temp_x2 ) / 2 << "degC";
s << " ]";
return s;
}

template<typename T>
uint32_t rs_fourcc(const T a, const T b, const T c, const T d)
{
Expand Down
40 changes: 10 additions & 30 deletions wrappers/python/c_files.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@ Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
#include "pyrealsense2.h"
#include <librealsense2/rs.h>
#include <iomanip>
#include <src/types.h>

std::string make_pythonic_str(std::string str)
{
Expand Down Expand Up @@ -76,36 +75,17 @@ void init_c_files(py::module &m) {
.def_readwrite("fy", &rs2_intrinsics::fy, "Focal length of the image plane, as a multiple of pixel height")
.def_readwrite("model", &rs2_intrinsics::model, "Distortion model of the image")
.def_property(BIND_RAW_ARRAY_PROPERTY(rs2_intrinsics, coeffs, float, 5), "Distortion coefficients")
.def("__repr__", [](const rs2_intrinsics& self) {
std::ostringstream ss;
ss << self;
return ss.str();
});

py::class_<rs2_dsm_params> dsm_params( m, "dsm_params", "Video stream DSM parameters" );
dsm_params.def( py::init<>() )
.def_readonly( "timestamp", &rs2_dsm_params::timestamp, "seconds since epoch" )
.def_readonly( "version", &rs2_dsm_params::version, "major<<12 | minor<<4 | patch" )
.def_readwrite( "model", &rs2_dsm_params::model, "correction model (0/1/2 none/AOT/TOA)" )
.def_property( BIND_RAW_ARRAY_PROPERTY( rs2_dsm_params, flags, uint8_t, sizeof( rs2_dsm_params::flags )), "flags" )
.def_readwrite( "h_scale", &rs2_dsm_params::h_scale, "horizontal DSM scale" )
.def_readwrite( "v_scale", &rs2_dsm_params::v_scale, "vertical DSM scale" )
.def_readwrite( "h_offset", &rs2_dsm_params::h_offset, "horizontal DSM offset" )
.def_readwrite( "v_offset", &rs2_dsm_params::v_offset, "vertical DSM offset" )
.def_readwrite( "rtd_offset", &rs2_dsm_params::rtd_offset, "the Round-Trip-Distance delay" )
.def_property_readonly( "temp",
[]( rs2_dsm_params const & self ) -> float {
return float( self.temp_x2 ) / 2;
},
"temperature (LDD for depth; HUM for color)" )
.def_property( BIND_RAW_ARRAY_PROPERTY( rs2_dsm_params, reserved, uint8_t, sizeof( rs2_dsm_params::reserved )), "reserved" )
.def( "__repr__",
[]( const rs2_dsm_params & self )
{
std::ostringstream ss;
ss << self;
return ss.str();
} );
[]( const rs2_intrinsics & i )
{
std::ostringstream ss;
ss << "[ " << i.width << "x" << i.height
<< " p[" << i.ppx << " " << i.ppy << "]"
<< " f[" << i.fx << " " << i.fy << "]"
<< " " << rs2_distortion_to_string( i.model ) << " [" << i.coeffs[0] << " " << i.coeffs[1] << " "
<< i.coeffs[2] << " " << i.coeffs[3] << " " << i.coeffs[4] << "] ]";
return ss.str();
} );

py::class_<rs2_motion_device_intrinsic> motion_device_intrinsic(m, "motion_device_intrinsic", "Motion device intrinsics: scale, bias, and variances.");
motion_device_intrinsic.def(py::init<>())
Expand Down
23 changes: 0 additions & 23 deletions wrappers/python/pyrs_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@ Copyright(c) 2017 Intel Corporation. All Rights Reserved. */

#include "pyrealsense2.h"
#include <librealsense2/hpp/rs_sensor.hpp>
#include "calibrated-sensor.h"
#include "max-usable-range-sensor.h"

void init_sensor(py::module &m) {
Expand Down Expand Up @@ -75,7 +74,6 @@ void init_sensor(py::module &m) {
.def(BIND_DOWNCAST(sensor, motion_sensor))
.def(BIND_DOWNCAST(sensor, fisheye_sensor))
.def(BIND_DOWNCAST(sensor, pose_sensor))
.def(BIND_DOWNCAST(sensor, calibrated_sensor))
.def(BIND_DOWNCAST(sensor, wheel_odometer))
.def(BIND_DOWNCAST(sensor, max_usable_range_sensor))
.def(BIND_DOWNCAST(sensor, debug_stream_sensor))
Expand Down Expand Up @@ -116,27 +114,6 @@ void init_sensor(py::module &m) {
py::class_<rs2::fisheye_sensor, rs2::sensor> fisheye_sensor(m, "fisheye_sensor"); // No docstring in C++
fisheye_sensor.def(py::init<rs2::sensor>(), "sensor"_a);

py::class_<rs2::calibrated_sensor, rs2::sensor> cal_sensor( m, "calibrated_sensor" );
cal_sensor.def(py::init<rs2::sensor>(), "sensor"_a)
.def("override_intrinsics",
&rs2::calibrated_sensor::override_intrinsics,
"intrinsics"_a,
py::call_guard< py::gil_scoped_release >())
.def("override_extrinsics",
&rs2::calibrated_sensor::override_extrinsics,
"extrinsics"_a,
py::call_guard< py::gil_scoped_release >())
.def("get_dsm_params",
&rs2::calibrated_sensor::get_dsm_params,
py::call_guard< py::gil_scoped_release >())
.def("override_dsm_params",
&rs2::calibrated_sensor::override_dsm_params,
"dsm_params"_a,
py::call_guard< py::gil_scoped_release >())
.def("reset_calibration",
&rs2::calibrated_sensor::reset_calibration,
py::call_guard< py::gil_scoped_release >());

py::class_<rs2::max_usable_range_sensor, rs2::sensor> mur_sensor(m, "max_usable_range_sensor");
mur_sensor.def(py::init<rs2::sensor>(), "sensor"_a)
.def("get_max_usable_depth_range",
Expand Down