Skip to content
Merged
1 change: 1 addition & 0 deletions dpnp/backend/extensions/ufunc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ set(_elementwise_sources
${CMAKE_CURRENT_SOURCE_DIR}/elementwise_functions/ldexp.cpp
${CMAKE_CURRENT_SOURCE_DIR}/elementwise_functions/logaddexp2.cpp
${CMAKE_CURRENT_SOURCE_DIR}/elementwise_functions/radians.cpp
${CMAKE_CURRENT_SOURCE_DIR}/elementwise_functions/sinc.cpp
${CMAKE_CURRENT_SOURCE_DIR}/elementwise_functions/spacing.cpp
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include "ldexp.hpp"
#include "logaddexp2.hpp"
#include "radians.hpp"
#include "sinc.hpp"
#include "spacing.hpp"

namespace py = pybind11;
Expand All @@ -62,6 +63,7 @@ void init_elementwise_functions(py::module_ m)
init_ldexp(m);
init_logaddexp2(m);
init_radians(m);
init_sinc(m);
init_spacing(m);
}
} // namespace dpnp::extensions::ufunc
127 changes: 127 additions & 0 deletions dpnp/backend/extensions/ufunc/elementwise_functions/sinc.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
//*****************************************************************************
// Copyright (c) 2024, Intel Corporation
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// - Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// - Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF
// THE POSSIBILITY OF SUCH DAMAGE.
//*****************************************************************************

#include <sycl/sycl.hpp>

#include "dpctl4pybind11.hpp"

#include "kernels/elementwise_functions/sinc.hpp"
#include "populate.hpp"
#include "sinc.hpp"

// include a local copy of elementwise common header from dpctl tensor:
// dpctl/tensor/libtensor/source/elementwise_functions/elementwise_functions.hpp
// TODO: replace by including dpctl header once available
#include "../../elementwise_functions/elementwise_functions.hpp"

// dpctl tensor headers
#include "kernels/elementwise_functions/common.hpp"
#include "utils/type_dispatch.hpp"

namespace dpnp::extensions::ufunc
{
namespace py = pybind11;
namespace py_int = dpnp::extensions::py_internal;

namespace impl
{
namespace ew_cmn_ns = dpctl::tensor::kernels::elementwise_common;
namespace td_ns = dpctl::tensor::type_dispatch;

/**
* @brief A factory to define pairs of supported types for which
* sycl::sinc<T> function is available.
*
* @tparam T Type of input vector `a` and of result vector `y`.
*/
template <typename T>
struct OutputType
{
using value_type = typename std::disjunction<
td_ns::TypeMapResultEntry<T, sycl::half>,
td_ns::TypeMapResultEntry<T, float>,
td_ns::TypeMapResultEntry<T, double>,
td_ns::TypeMapResultEntry<T, std::complex<float>>,
td_ns::TypeMapResultEntry<T, std::complex<double>>,
td_ns::DefaultResultEntry<void>>::result_type;
};

using dpnp::kernels::sinc::SincFunctor;

template <typename argT,
typename resT = argT,
unsigned int vec_sz = 4,
unsigned int n_vecs = 2,
bool enable_sg_loadstore = true>
using ContigFunctor = ew_cmn_ns::UnaryContigFunctor<argT,
resT,
SincFunctor<argT, resT>,
vec_sz,
n_vecs,
enable_sg_loadstore>;

template <typename argTy, typename resTy, typename IndexerT>
using StridedFunctor = ew_cmn_ns::
UnaryStridedFunctor<argTy, resTy, IndexerT, SincFunctor<argTy, resTy>>;

using ew_cmn_ns::unary_contig_impl_fn_ptr_t;
using ew_cmn_ns::unary_strided_impl_fn_ptr_t;

static unary_contig_impl_fn_ptr_t sinc_contig_dispatch_vector[td_ns::num_types];
static int sinc_output_typeid_vector[td_ns::num_types];
static unary_strided_impl_fn_ptr_t
sinc_strided_dispatch_vector[td_ns::num_types];

MACRO_POPULATE_DISPATCH_VECTORS(sinc);
} // namespace impl

void init_sinc(py::module_ m)
{
using arrayT = dpctl::tensor::usm_ndarray;
using event_vecT = std::vector<sycl::event>;
{
impl::populate_sinc_dispatch_vectors();
using impl::sinc_contig_dispatch_vector;
using impl::sinc_output_typeid_vector;
using impl::sinc_strided_dispatch_vector;

auto sinc_pyapi = [&](const arrayT &src, const arrayT &dst,
sycl::queue &exec_q,
const event_vecT &depends = {}) {
return py_int::py_unary_ufunc(
src, dst, exec_q, depends, sinc_output_typeid_vector,
sinc_contig_dispatch_vector, sinc_strided_dispatch_vector);
};
m.def("_sinc", sinc_pyapi, "", py::arg("src"), py::arg("dst"),
py::arg("sycl_queue"), py::arg("depends") = py::list());

auto sinc_result_type_pyapi = [&](const py::dtype &dtype) {
return py_int::py_unary_ufunc_result_type(
dtype, sinc_output_typeid_vector);
};
m.def("_sinc_result_type", sinc_result_type_pyapi);
}
}
} // namespace dpnp::extensions::ufunc
35 changes: 35 additions & 0 deletions dpnp/backend/extensions/ufunc/elementwise_functions/sinc.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
//*****************************************************************************
// Copyright (c) 2024, Intel Corporation
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// - Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// - Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF
// THE POSSIBILITY OF SUCH DAMAGE.
//*****************************************************************************

#pragma once

#include <pybind11/pybind11.h>

namespace py = pybind11;

namespace dpnp::extensions::ufunc
{
void init_sinc(py::module_ m);
} // namespace dpnp::extensions::ufunc
200 changes: 200 additions & 0 deletions dpnp/backend/kernels/elementwise_functions/sinc.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,200 @@
//*****************************************************************************
// Copyright (c) 2024, Intel Corporation
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// - Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// - Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF
// THE POSSIBILITY OF SUCH DAMAGE.
//*****************************************************************************

#pragma once

#define SYCL_EXT_ONEAPI_COMPLEX
#if __has_include(<sycl/ext/oneapi/experimental/sycl_complex.hpp>)
#include <sycl/ext/oneapi/experimental/sycl_complex.hpp>
#else
#include <sycl/ext/oneapi/experimental/complex/complex.hpp>
#endif

#include <sycl/sycl.hpp>

// dpctl tensor headers
#include "utils/type_utils.hpp"

namespace dpnp::kernels::sinc
{
namespace tu_ns = dpctl::tensor::type_utils;

namespace impl
{
namespace exprm_ns = sycl::ext::oneapi::experimental;

template <typename Tp>
inline Tp sin(const Tp &in)
{
if constexpr (tu_ns::is_complex<Tp>::value) {
using realTp = typename Tp::value_type;

constexpr realTp q_nan = std::numeric_limits<realTp>::quiet_NaN();

realTp const &in_re = std::real(in);
realTp const &in_im = std::imag(in);

const bool in_re_finite = sycl::isfinite(in_re);
const bool in_im_finite = sycl::isfinite(in_im);
/*
* Handle the nearly-non-exceptional cases where
* real and imaginary parts of input are finite.
*/
if (in_re_finite && in_im_finite) {
Tp res = exprm_ns::sin(exprm_ns::complex<realTp>(in)); // sin(in);
if (in_re == realTp(0)) {
res.real(sycl::copysign(realTp(0), in_re));
}
return res;
}

/*
* since sin(in) = -I * sinh(I * in), for special cases,
* we calculate real and imaginary parts of z = sinh(I * in) and
* then return { imag(z) , -real(z) } which is sin(in).
*/
const realTp x = -in_im;
const realTp y = in_re;
const bool xfinite = in_im_finite;
const bool yfinite = in_re_finite;
/*
* sinh(+-0 +- I Inf) = sign(d(+-0, dNaN))0 + I dNaN.
* The sign of 0 in the result is unspecified. Choice = normally
* the same as dNaN.
*
* sinh(+-0 +- I NaN) = sign(d(+-0, NaN))0 + I d(NaN).
* The sign of 0 in the result is unspecified. Choice = normally
* the same as d(NaN).
*/
if (x == realTp(0) && !yfinite) {
const realTp sinh_im = q_nan;
const realTp sinh_re = sycl::copysign(realTp(0), x * sinh_im);
return Tp{sinh_im, -sinh_re};
}

/*
* sinh(+-Inf +- I 0) = +-Inf + I +-0.
*
* sinh(NaN +- I 0) = d(NaN) + I +-0.
*/
if (y == realTp(0) && !xfinite) {
if (std::isnan(x)) {
const realTp sinh_re = x;
const realTp sinh_im = y;
return Tp{sinh_im, -sinh_re};
}
const realTp sinh_re = x;
const realTp sinh_im = sycl::copysign(realTp(0), y);
return Tp{sinh_im, -sinh_re};
}

/*
* sinh(x +- I Inf) = dNaN + I dNaN.
*
* sinh(x + I NaN) = d(NaN) + I d(NaN).
*/
if (xfinite && !yfinite) {
const realTp sinh_re = q_nan;
const realTp sinh_im = x * sinh_re;
return Tp{sinh_im, -sinh_re};
}

/*
* sinh(+-Inf + I NaN) = +-Inf + I d(NaN).
* The sign of Inf in the result is unspecified. Choice = normally
* the same as d(NaN).
*
* sinh(+-Inf +- I Inf) = +Inf + I dNaN.
* The sign of Inf in the result is unspecified.
* Choice = always - here for sinh to have positive result for
* imaginary part of sin.
*
* sinh(+-Inf + I y) = +-Inf cos(y) + I Inf sin(y)
*/
if (std::isinf(x)) {
if (!yfinite) {
const realTp sinh_re = -x * x;
const realTp sinh_im = x * (y - y);
return Tp{sinh_im, -sinh_re};
}
const realTp sinh_re = x * sycl::cos(y);
const realTp sinh_im =
std::numeric_limits<realTp>::infinity() * sycl::sin(y);
return Tp{sinh_im, -sinh_re};
}

/*
* sinh(NaN + I NaN) = d(NaN) + I d(NaN).
*
* sinh(NaN +- I Inf) = d(NaN) + I d(NaN).
*
* sinh(NaN + I y) = d(NaN) + I d(NaN).
*/
const realTp y_m_y = (y - y);
const realTp sinh_re = (x * x) * y_m_y;
const realTp sinh_im = (x + x) * y_m_y;
return Tp{sinh_im, -sinh_re};
}
else {
if (in == Tp(0)) {
return in;
}
return sycl::sin(in);
}
}
} // namespace impl

template <typename argT, typename Tp>
struct SincFunctor
{
// is function constant for given argT
using is_constant = typename std::false_type;
// constant value, if constant
// constexpr Tp constant_value = Tp{};
// is function defined for sycl::vec
using supports_vec = typename std::false_type;
// do both argT and Tp support subgroup store/load operation
using supports_sg_loadstore = typename std::negation<
std::disjunction<tu_ns::is_complex<Tp>, tu_ns::is_complex<argT>>>;

Tp operator()(const argT &x) const
{
constexpr argT pi =
static_cast<argT>(3.1415926535897932384626433832795029L);
const argT y = pi * x;

if (y == argT(0)) {
return Tp(1);
}

if constexpr (tu_ns::is_complex<argT>::value) {
return impl::sin(y) / y;
}
else {
return sycl::sinpi(x) / y;
}
}
};
} // namespace dpnp::kernels::sinc
Loading
Loading