Skip to content

Commit

Permalink
Update sdk to v1.10.16
Browse files Browse the repository at this point in the history
  • Loading branch information
jian-dong committed Dec 10, 2024
1 parent dfa26a9 commit 98a1caf
Show file tree
Hide file tree
Showing 11 changed files with 215 additions and 33 deletions.
83 changes: 82 additions & 1 deletion orbbec_camera/SDK/include/libobsensor/h/Filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -248,12 +248,93 @@ ob_spatial_advanced_filter_params ob_spatial_advanced_filter_get_filter_params(o
/**
* @brief Set the spatial advanced filter params.
*
* @param[in] filter A temporal_filter object.
* @param[in] filter A spatial advanced filter object.
* @param[in] params ob_spatial_advanced_filter_params.
* @param[out] error Log error messages.
*/
void ob_spatial_advanced_filter_set_filter_params(ob_filter *filter, ob_spatial_advanced_filter_params params, ob_error **error);

/**
* @brief Create a spatial fast filter.
* @param[out] error Log error messages.
* @return A depth_filter object.
*/
ob_filter *ob_create_spatial_fast_filter(ob_error **error);

/**
* @brief Get the spatial fast filter window size range.
*
* @param[in] filter A spatial fast filter object.
* @param[out] error Log error messages.
* @return ob_uint8_property_range the filter window size value of property range.
*/
ob_uint8_property_range ob_spatial_fast_filter_get_size_range(ob_filter *filter, ob_error **error);

/**
* @brief Set the spatial fast filter params.
*
* @param[in] filter A spatial fast filter object.
* @param[in] params ob_spatial_fast_filter_params.
* @param[out] error Log error messages.
*/
void ob_spatial_fast_filter_set_filter_params(ob_filter *filter, ob_spatial_fast_filter_params params, ob_error **error);

/**
* @brief Get the spatial fast filter params.
*
* @param[in] filter A spatial fast filter object.
* @param[out] error Log error messages.
* @return ob_spatial_fast_filter_params.
*/
ob_spatial_fast_filter_params ob_spatial_fast_filter_get_filter_params(ob_filter *filter, ob_error **error);

/**
* @brief Create a spatial moderate filter.
* @param[out] error Log error messages.
* @return A depth_filter object.
*/
ob_filter *ob_create_spatial_moderate_filter(ob_error **error);
/**
* @brief Get the spatial moderate filter disp diff range.
*
* @param[in] filter A spatial moderate filter object.
* @param[out] error Log error messages.
* @return ob_uint16_property_range the dispdiff value of property range.
*/
ob_uint16_property_range ob_spatial_moderate_filter_get_disp_diff_range(ob_filter *filter, ob_error **error);
/**
* @brief Get the spatial moderate filter magnitude range.
*
* @param[in] filter A spatial moderate filter object.
* @param[out] error Log error messages.
* @return ob_uint8_property_range the magnitude value of property range.
*/
ob_uint8_property_range ob_spatial_moderate_filter_get_magnitude_range(ob_filter *filter, ob_error **error);
/**
* @brief Get the spatial moderate filter window size range.
*
* @param[in] filter A spatial moderate filter object.
* @param[out] error Log error messages.
* @return ob_uint8_property_range the filter window size value of property range.
*/
ob_uint8_property_range ob_spatial_moderate_filter_get_size_range(ob_filter *filter, ob_error **error);
/**
* @brief Get the spatial moderate filter params.
*
* @param[in] filter A spatial moderate filter object.
* @param[out] error Log error messages.
* @return ob_spatial_moderate_filter_params.
*/
ob_spatial_moderate_filter_params ob_spatial_moderate_filter_get_filter_params(ob_filter *filter, ob_error **error);
/**
* @brief Set the spatial moderate filter params.
*
* @param[in] filter A spatial moderate filter object.
* @param[in] params ob_spatial_moderate_filter_params.
* @param[out] error Log error messages.
*/
void ob_spatial_moderate_filter_set_filter_params(ob_filter *filter, ob_spatial_moderate_filter_params params, ob_error **error);

/**
* @brief Create a noise removal filter.
* @param[out] error Log error messages.
Expand Down
12 changes: 12 additions & 0 deletions orbbec_camera/SDK/include/libobsensor/h/ObTypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -974,6 +974,18 @@ typedef struct {
uint16_t radius; // hole_fill
} OBSpatialAdvancedFilterParams, ob_spatial_advanced_filter_params;


typedef struct {
uint8_t size; //median filter window size
} OBSpatialFastFilterParams, ob_spatial_fast_filter_params;


typedef struct {
uint8_t size ;
uint8_t magnitude ; // magnitude
uint16_t disp_diff ;
} OBSpatialModerateFilterParams, ob_spatial_moderate_filter_params;

typedef enum OB_EDGE_NOISE_REMOVAL_TYPE {
OB_MG_FILTER = 0,
OB_MGH_FILTER = 1, // horizontal MG
Expand Down
84 changes: 80 additions & 4 deletions orbbec_camera/SDK/include/libobsensor/hpp/Filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@ class OB_EXTENSION_API TemporalFilter : public Filter {
};

/**
* @brief Spatial advanced filte smooths the image by calculating frame with alpha and delta settings
* @brief Spatial advanced filter smooths the image by calculating frame with alpha and delta settings
* alpha defines the weight of the current pixel for smoothing,
* delta defines the depth gradient below which the smoothing will occur as number of depth levels.
*/
Expand All @@ -276,21 +276,21 @@ class OB_EXTENSION_API SpatialAdvancedFilter : public Filter {
/**
* @brief Get the spatial advanced filter dispdiff range.
*
* @return OBFloatPropertyRange the dispdiff value of property range.
* @return OBUint16PropertyRange the dispdiff value of property range.
*/
OBUint16PropertyRange getDispDiffRange();

/**
* @brief Get the spatial advanced filter radius range.
*
* @return OBFloatPropertyRange the radius value of property range.
* @return OBUint16PropertyRange the radius value of property range.
*/
OBUint16PropertyRange getRadiusRange();

/**
* @brief Get the spatial advanced filter magnitude range.
*
* @return OBFloatPropertyRange the magnitude value of property range.
* @return OBIntPropertyRange the magnitude value of property range.
*/
OBIntPropertyRange getMagnitudeRange();

Expand All @@ -310,6 +310,73 @@ class OB_EXTENSION_API SpatialAdvancedFilter : public Filter {
};

/**
* @brief Spatial fast filter smooths the image by calculating frame with filter window size settings
*/
class OB_EXTENSION_API SpatialFastFilter : public Filter {
public:
SpatialFastFilter();
/**
* @brief Get the spatial fast filter window size range
*
* @return OBUint8PropertyRange the windows size value of property range.
*/
OBUint8PropertyRange getSizeRange();

/**
* @brief Get the spatial fast filter params.
*
* @return OBSpatialFastFilterParams
*/
OBSpatialFastFilterParams getFilterParams();
/**
* @brief Set the spatial fast filter params.
*
* @param params OBSpatialFastFilterParams.
*/
void setFilterParams(OBSpatialFastFilterParams params);
};

/**
* @brief Spatial moderate filter smooths the image by calculating frame with filter window size,magnitude and disp diff settings
*/
class OB_EXTENSION_API SpatialModerateFilter : public Filter {
public:
SpatialModerateFilter();
/**
* @brief Get the spatial moderate filter window size range
*
* @return OBUint8PropertyRange the windows size value of property range.
*/
OBUint8PropertyRange getSizeRange();

/**
* @brief Get the spatial moderate filter magnitude range.
*
* @return OBUint8PropertyRange the magnitude value of property range.
*/
OBUint8PropertyRange getMagnitudeRange();
/**
* @brief Get the spatial moderate filter dispdiff range.
*
* @return OBUint16PropertyRange the dispdiff value of property range.
*/
OBUint16PropertyRange getDispDiffRange();

/**
* @brief Get the spatial moderate filter params.
*
* @return OBSpatialModerateFilterParams
*/
OBSpatialModerateFilterParams getFilterParams();
/**
* @brief Set the spatial moderate filter params.
*
* @param params OBSpatialModerateFilterParams.
*/
void setFilterParams(OBSpatialModerateFilterParams params);
};

/**
* @brief Depth to disparity or disparity to depth
*/
class OB_EXTENSION_API DisparityTransform : public Filter {
Expand Down Expand Up @@ -542,6 +609,15 @@ template <typename T> bool Filter::is() {
if(name == "SpatialAdvancedFilter") {
return typeid(T) == typeid(SpatialAdvancedFilter);
}

if(name == "SpatialFastFilter") {
return typeid(T) == typeid(SpatialFastFilter);
}

if(name == "SpatialModerateFilter") {
return typeid(T) == typeid(SpatialModerateFilter);
}

if(name == "TemporalFilter") {
return typeid(T) == typeid(TemporalFilter);
}
Expand Down
2 changes: 1 addition & 1 deletion orbbec_camera/SDK/lib/arm32/libOrbbecSDK.so.1.10
Binary file removed orbbec_camera/SDK/lib/arm32/libOrbbecSDK.so.1.10.14
Binary file not shown.
Binary file not shown.
2 changes: 1 addition & 1 deletion orbbec_camera/SDK/lib/arm64/libOrbbecSDK.so.1.10
Binary file not shown.
2 changes: 1 addition & 1 deletion orbbec_camera/SDK/lib/x64/libOrbbecSDK.so.1.10
Binary file not shown.
63 changes: 38 additions & 25 deletions orbbec_camera/src/ob_camera_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -322,30 +322,6 @@ void OBCameraNode::setupDevices() {
}
}

for (const auto &stream_index : IMAGE_STREAMS) {
if (enable_stream_[stream_index]) {
OBPropertyID mirrorPropertyID = OB_PROP_DEPTH_MIRROR_BOOL;
if (stream_index == COLOR) {
mirrorPropertyID = OB_PROP_COLOR_MIRROR_BOOL;
} else if (stream_index == DEPTH) {
mirrorPropertyID = OB_PROP_DEPTH_MIRROR_BOOL;
} else if (stream_index == INFRA0) {
mirrorPropertyID = OB_PROP_IR_MIRROR_BOOL;

} else if (stream_index == INFRA1) {
mirrorPropertyID = OB_PROP_IR_MIRROR_BOOL;
} else if (stream_index == INFRA2) {
mirrorPropertyID = OB_PROP_IR_RIGHT_MIRROR_BOOL;
}

if (device_->isPropertySupported(mirrorPropertyID, OB_PERMISSION_WRITE)) {
RCLCPP_INFO_STREAM(logger_, "Setting " << stream_name_[stream_index] << " mirror to "
<< (flip_stream_[stream_index] ? "ON" : "OFF"));
TRY_TO_SET_PROPERTY(setBoolProperty, mirrorPropertyID, flip_stream_[stream_index]);
}
}
}

if (!depth_filter_config_.empty() && enable_depth_filter_) {
RCLCPP_INFO_STREAM(logger_, "Load depth filter config: " << depth_filter_config_);
TRY_EXECUTE_BLOCK(device_->loadDepthFilterConfig(depth_filter_config_.c_str()));
Expand Down Expand Up @@ -1779,7 +1755,7 @@ void OBCameraNode::onNewFrameSetCallback(std::shared_ptr<ob::FrameSet> frame_set
if (enable_stream_[COLOR] && color_frame) {
std::unique_lock<std::mutex> lock(color_frame_queue_lock_);
if (!enable_3d_reconstruction_mode_ || depth_laser_status) {
if(color_frame_queue_.size() > 2) {
if (color_frame_queue_.size() > 2) {
color_frame_queue_.pop();
}
color_frame_queue_.push(frame_set);
Expand Down Expand Up @@ -2072,6 +2048,39 @@ void OBCameraNode::onNewFrameCallback(const std::shared_ptr<ob::Frame> &frame,
camera_info.p.at(7) = -fy * ex.trans[1] / 1000.0 + 0.0;
}
CHECK(camera_info_publishers_.count(stream_index) > 0);
if (flip_stream_[stream_index]) {
// We are performing a horizontal flip (left-right mirror) of the image.
//
// After flipping the image, the camera's principal point (cx) in the
// camera_info must be adjusted so that it still refers to the correct point
// in the flipped image.

// Intrinsic matrix K:
// K = [ fx 0 cx
// 0 fy cy
// 0 0 1 ]
double &cx = camera_info.k[2]; // K[0,2]

// Store the original principal point cx
double old_cx = cx;

// For a horizontal flip, the new cx = (width - 1) - old_cx
// This effectively mirrors the cx value about the center of the image.
cx = (width - 1) - old_cx;

// Update the projection matrix P:
// P = [ fx 0 cx Tx
// 0 fy cy Ty
// 0 0 1 0 ]
double &p_cx = camera_info.p[2];

double old_p_cx = p_cx;
p_cx = (width - 1) - old_p_cx;

// fx, fy, cy remain the same for a simple horizontal flip.
// The only changes are cx and p_cx.
}

camera_info_publishers_[stream_index]->publish(camera_info);
if (isGemini335PID(pid)) {
publishMetadata(frame, stream_index, camera_info.header);
Expand All @@ -2097,6 +2106,10 @@ void OBCameraNode::onNewFrameCallback(const std::shared_ptr<ob::Frame> &frame,
auto depth_scale = video_frame->as<ob::DepthFrame>()->getValueScale();
image = image * depth_scale;
}
if (flip_stream_[stream_index]) {
// flip image
cv::flip(image, image, 1);
}
sensor_msgs::msg::Image::UniquePtr image_msg(new sensor_msgs::msg::Image());

cv_bridge::CvImage(std_msgs::msg::Header(), encoding_[stream_index], image)
Expand Down

0 comments on commit 98a1caf

Please sign in to comment.