Skip to content

Commit

Permalink
remove L500-specific calibrated-sensor
Browse files Browse the repository at this point in the history
  • Loading branch information
maloel committed Oct 14, 2023
1 parent 4dfbed5 commit c42e6e8
Show file tree
Hide file tree
Showing 7 changed files with 7 additions and 162 deletions.
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
32 changes: 6 additions & 26 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 @@ -1199,40 +1198,25 @@ 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();
throw not_implemented_exception( "deprecated" );
}
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 );
throw not_implemented_exception( "deprecated" );
}
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 @@ -1442,7 +1426,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 @@ -2759,11 +2743,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
25 changes: 0 additions & 25 deletions wrappers/python/c_files.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,31 +87,6 @@ void init_c_files(py::module &m) {
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();
} );

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<>())
.def_property(BIND_RAW_2D_ARRAY_PROPERTY(rs2_motion_device_intrinsic, data, float, 3, 4), "3x4 matrix with 3x3 scale and cross axis and 3x1 biases")
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

0 comments on commit c42e6e8

Please sign in to comment.