Merge remote-tracking branch 'upstream/develop' into pydocstrings-documentation
commit
a964c81ba0
File diff suppressed because it is too large
Load Diff
|
@ -110,7 +110,7 @@ class Experiment {
|
|||
gttic_(SmootherUpdate);
|
||||
clock_t beforeUpdate = clock();
|
||||
auto linearized = newFactors_.linearize(initial_);
|
||||
smoother_.update(*linearized, maxNrHypotheses);
|
||||
smoother_.update(*linearized, initial_);
|
||||
allFactors_.push_back(newFactors_);
|
||||
newFactors_.resize(0);
|
||||
clock_t afterUpdate = clock();
|
||||
|
@ -313,4 +313,4 @@ int main(int argc, char* argv[]) {
|
|||
experiment.run();
|
||||
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -45,7 +45,7 @@ public:
|
|||
typedef typename traits<G>::group_flavor flavor_tag;
|
||||
//typedef typename traits<G>::identity::value_type identity_value_type;
|
||||
|
||||
BOOST_CONCEPT_USAGE(IsGroup) {
|
||||
GTSAM_CONCEPT_USAGE(IsGroup) {
|
||||
static_assert(
|
||||
(std::is_base_of<group_tag, structure_category_tag>::value),
|
||||
"This type's structure_category trait does not assert it as a group (or derived)");
|
||||
|
|
|
@ -282,7 +282,7 @@ public:
|
|||
typedef typename traits<T>::TangentVector TangentVector;
|
||||
typedef typename traits<T>::ChartJacobian ChartJacobian;
|
||||
|
||||
BOOST_CONCEPT_USAGE(IsLieGroup) {
|
||||
GTSAM_CONCEPT_USAGE(IsLieGroup) {
|
||||
static_assert(
|
||||
(std::is_base_of<lie_group_tag, structure_category_tag>::value),
|
||||
"This type's trait does not assert it is a Lie group (or derived)");
|
||||
|
@ -313,7 +313,7 @@ public:
|
|||
typedef typename traits<T>::LieAlgebra LieAlgebra;
|
||||
typedef typename traits<T>::TangentVector TangentVector;
|
||||
|
||||
BOOST_CONCEPT_USAGE(IsMatrixLieGroup) {
|
||||
GTSAM_CONCEPT_USAGE(IsMatrixLieGroup) {
|
||||
// hat and vee
|
||||
X = traits<T>::Hat(xi);
|
||||
xi = traits<T>::Vee(X);
|
||||
|
|
|
@ -61,7 +61,7 @@ struct HasManifoldPrereqs {
|
|||
Eigen::Matrix<double, dim, 1> v;
|
||||
OptionalJacobian<dim, dim> Hp, Hq, Hv;
|
||||
|
||||
BOOST_CONCEPT_USAGE(HasManifoldPrereqs) {
|
||||
GTSAM_CONCEPT_USAGE(HasManifoldPrereqs) {
|
||||
v = p.localCoordinates(q);
|
||||
q = p.retract(v);
|
||||
}
|
||||
|
@ -139,7 +139,7 @@ public:
|
|||
typedef typename traits<T>::ManifoldType ManifoldType;
|
||||
typedef typename traits<T>::TangentVector TangentVector;
|
||||
|
||||
BOOST_CONCEPT_USAGE(IsManifold) {
|
||||
GTSAM_CONCEPT_USAGE(IsManifold) {
|
||||
static_assert(
|
||||
(std::is_base_of<manifold_tag, structure_category_tag>::value),
|
||||
"This type's structure_category trait does not assert it as a manifold (or derived)");
|
||||
|
|
|
@ -61,7 +61,7 @@ namespace gtsam {
|
|||
bool r1,r2;
|
||||
public:
|
||||
|
||||
BOOST_CONCEPT_USAGE(IsTestable) {
|
||||
GTSAM_CONCEPT_USAGE(IsTestable) {
|
||||
// check print function, with optional string
|
||||
traits<T>::Print(t, std::string());
|
||||
traits<T>::Print(t);
|
||||
|
@ -134,7 +134,7 @@ namespace gtsam {
|
|||
template<typename T>
|
||||
struct HasTestablePrereqs {
|
||||
|
||||
BOOST_CONCEPT_USAGE(HasTestablePrereqs) {
|
||||
GTSAM_CONCEPT_USAGE(HasTestablePrereqs) {
|
||||
t->print(str);
|
||||
b = t->equals(*s,tol);
|
||||
}
|
||||
|
|
|
@ -177,7 +177,7 @@ struct HasVectorSpacePrereqs {
|
|||
Class p, q;
|
||||
Vector v;
|
||||
|
||||
BOOST_CONCEPT_USAGE(HasVectorSpacePrereqs) {
|
||||
GTSAM_CONCEPT_USAGE(HasVectorSpacePrereqs) {
|
||||
p = Class::Identity(); // identity
|
||||
q = p + p; // addition
|
||||
q = p - p; // subtraction
|
||||
|
@ -492,7 +492,7 @@ public:
|
|||
|
||||
typedef typename traits<T>::structure_category structure_category_tag;
|
||||
|
||||
BOOST_CONCEPT_USAGE(IsVectorSpace) {
|
||||
GTSAM_CONCEPT_USAGE(IsVectorSpace) {
|
||||
static_assert(
|
||||
(std::is_base_of<vector_space_tag, structure_category_tag>::value),
|
||||
"This type's trait does not assert it as a vector space (or derived)");
|
||||
|
|
|
@ -17,9 +17,10 @@
|
|||
#include <boost/concept_check.hpp>
|
||||
#define GTSAM_CONCEPT_ASSERT(concept) BOOST_CONCEPT_ASSERT((concept))
|
||||
#define GTSAM_CONCEPT_REQUIRES(concept, return_type) BOOST_CONCEPT_REQUIRES(((concept)), (return_type))
|
||||
#define GTSAM_CONCEPT_USAGE BOOST_CONCEPT_USAGE
|
||||
#else
|
||||
// This does something sensible:
|
||||
#define BOOST_CONCEPT_USAGE(concept) void check##concept()
|
||||
#define GTSAM_CONCEPT_USAGE(concept) void check##concept()
|
||||
// These just ignore the concept checking for now:
|
||||
#define GTSAM_CONCEPT_ASSERT(concept) static_assert(true, "")
|
||||
#define GTSAM_CONCEPT_REQUIRES(concept, return_type) return_type
|
||||
|
|
|
@ -17,37 +17,117 @@
|
|||
*/
|
||||
|
||||
#include <gtsam/basis/Chebyshev2.h>
|
||||
|
||||
#include <Eigen/Dense>
|
||||
|
||||
#include <cassert>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
double Chebyshev2::Point(size_t N, int j, double a, double b) {
|
||||
double Chebyshev2::Point(size_t N, int j) {
|
||||
if (N == 1) return 0.0;
|
||||
assert(j >= 0 && size_t(j) < N);
|
||||
const double dtheta = M_PI / (N > 1 ? (N - 1) : 1);
|
||||
// We add -PI so that we get values ordered from -1 to +1
|
||||
// sin(-M_PI_2 + dtheta*j); also works
|
||||
return a + (b - a) * (1. + cos(-M_PI + dtheta * j)) / 2;
|
||||
const double dTheta = M_PI / (N - 1);
|
||||
return -cos(dTheta * j);
|
||||
}
|
||||
|
||||
Weights Chebyshev2::CalculateWeights(size_t N, double x, double a, double b) {
|
||||
// Allocate space for weights
|
||||
Weights weights(N);
|
||||
double Chebyshev2::Point(size_t N, int j, double a, double b) {
|
||||
if (N == 1) return (a + b) / 2;
|
||||
return a + (b - a) * (Point(N, j) + 1.0) / 2.0;
|
||||
}
|
||||
|
||||
// We start by getting distances from x to all Chebyshev points
|
||||
// as well as getting smallest distance
|
||||
Weights distances(N);
|
||||
Vector Chebyshev2::Points(size_t N) {
|
||||
Vector points(N);
|
||||
if (N == 1) {
|
||||
points(0) = 0.0;
|
||||
return points;
|
||||
}
|
||||
size_t half = N / 2;
|
||||
const double dTheta = M_PI / (N - 1);
|
||||
for (size_t j = 0; j < half; ++j) {
|
||||
double c = cos(j * dTheta);
|
||||
points(j) = -c;
|
||||
points(N - 1 - j) = c;
|
||||
}
|
||||
if (N % 2 == 1) {
|
||||
points(half) = 0.0;
|
||||
}
|
||||
return points;
|
||||
}
|
||||
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
const double dj =
|
||||
x - Point(N, j, a, b); // only thing that depends on [a,b]
|
||||
Vector Chebyshev2::Points(size_t N, double a, double b) {
|
||||
Vector points = Points(N);
|
||||
const double T1 = (a + b) / 2, T2 = (b - a) / 2;
|
||||
points = T1 + (T2 * points).array();
|
||||
return points;
|
||||
}
|
||||
|
||||
if (std::abs(dj) < 1e-12) {
|
||||
// exceptional case: x coincides with a Chebyshev point
|
||||
weights.setZero();
|
||||
weights(j) = 1;
|
||||
return weights;
|
||||
namespace {
|
||||
// Find the index of the Chebyshev point that coincides with x
|
||||
// within the interval [a, b]. If no such point exists, return nullopt.
|
||||
std::optional<size_t> coincidentPoint(size_t N, double x, double a, double b, double tol = 1e-12) {
|
||||
if (N == 0) return std::nullopt;
|
||||
if (N == 1) {
|
||||
double mid = (a + b) / 2;
|
||||
if (std::abs(x - mid) < tol) return 0;
|
||||
} else {
|
||||
// Compute normalized value y such that cos(j*dTheta) = y.
|
||||
double y = 1.0 - 2.0 * (x - a) / (b - a);
|
||||
if (y < -1.0 || y > 1.0) return std::nullopt;
|
||||
double dTheta = M_PI / (N - 1);
|
||||
double jCandidate = std::acos(y) / dTheta;
|
||||
size_t jRounded = static_cast<size_t>(std::round(jCandidate));
|
||||
if (std::abs(jCandidate - jRounded) < tol) return jRounded;
|
||||
}
|
||||
distances(j) = dj;
|
||||
return std::nullopt;
|
||||
}
|
||||
|
||||
// Get signed distances from x to all Chebyshev points
|
||||
Vector signedDistances(size_t N, double x, double a, double b) {
|
||||
Vector result(N);
|
||||
const Vector points = Chebyshev2::Points(N, a, b);
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
const double dj = x - points[j];
|
||||
result(j) = dj;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
// Helper function to calculate a row of the differentiation matrix, [-1,1] interval
|
||||
Vector differentiationMatrixRow(size_t N, const Vector& points, size_t i) {
|
||||
Vector row(N);
|
||||
const size_t K = N - 1;
|
||||
double xi = points(i);
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
if (i == j) {
|
||||
// Diagonal elements
|
||||
if (i == 0 || i == K)
|
||||
row(j) = (i == 0 ? -1 : 1) * (2.0 * K * K + 1) / 6.0;
|
||||
else
|
||||
row(j) = -xi / (2.0 * (1.0 - xi * xi));
|
||||
}
|
||||
else {
|
||||
double xj = points(j);
|
||||
double ci = (i == 0 || i == K) ? 2. : 1.;
|
||||
double cj = (j == 0 || j == K) ? 2. : 1.;
|
||||
double t = ((i + j) % 2) == 0 ? 1 : -1;
|
||||
row(j) = (ci / cj) * t / (xi - xj);
|
||||
}
|
||||
}
|
||||
return row;
|
||||
}
|
||||
} // namespace
|
||||
|
||||
Weights Chebyshev2::CalculateWeights(size_t N, double x, double a, double b) {
|
||||
// We start by getting distances from x to all Chebyshev points
|
||||
const Vector distances = signedDistances(N, x, a, b);
|
||||
|
||||
Weights weights(N);
|
||||
if (auto j = coincidentPoint(N, x, a, b)) {
|
||||
// exceptional case: x coincides with a Chebyshev point
|
||||
weights.setZero();
|
||||
weights(*j) = 1;
|
||||
return weights;
|
||||
}
|
||||
|
||||
// Beginning of interval, j = 0, x(0) = a
|
||||
|
@ -69,75 +149,40 @@ Weights Chebyshev2::CalculateWeights(size_t N, double x, double a, double b) {
|
|||
}
|
||||
|
||||
Weights Chebyshev2::DerivativeWeights(size_t N, double x, double a, double b) {
|
||||
// Allocate space for weights
|
||||
Weights weightDerivatives(N);
|
||||
|
||||
// toggle variable so we don't need to use `pow` for -1
|
||||
double t = -1;
|
||||
|
||||
// We start by getting distances from x to all Chebyshev points
|
||||
// as well as getting smallest distance
|
||||
Weights distances(N);
|
||||
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
const double dj =
|
||||
x - Point(N, j, a, b); // only thing that depends on [a,b]
|
||||
if (std::abs(dj) < 1e-12) {
|
||||
// exceptional case: x coincides with a Chebyshev point
|
||||
weightDerivatives.setZero();
|
||||
// compute the jth row of the differentiation matrix for this point
|
||||
double cj = (j == 0 || j == N - 1) ? 2. : 1.;
|
||||
for (size_t k = 0; k < N; k++) {
|
||||
if (j == 0 && k == 0) {
|
||||
// we reverse the sign since we order the cheb points from -1 to 1
|
||||
weightDerivatives(k) = -(cj * (N - 1) * (N - 1) + 1) / 6.0;
|
||||
} else if (j == N - 1 && k == N - 1) {
|
||||
// we reverse the sign since we order the cheb points from -1 to 1
|
||||
weightDerivatives(k) = (cj * (N - 1) * (N - 1) + 1) / 6.0;
|
||||
} else if (k == j) {
|
||||
double xj = Point(N, j);
|
||||
double xj2 = xj * xj;
|
||||
weightDerivatives(k) = -0.5 * xj / (1 - xj2);
|
||||
} else {
|
||||
double xj = Point(N, j);
|
||||
double xk = Point(N, k);
|
||||
double ck = (k == 0 || k == N - 1) ? 2. : 1.;
|
||||
t = ((j + k) % 2) == 0 ? 1 : -1;
|
||||
weightDerivatives(k) = (cj / ck) * t / (xj - xk);
|
||||
}
|
||||
}
|
||||
return 2 * weightDerivatives / (b - a);
|
||||
}
|
||||
distances(j) = dj;
|
||||
if (auto j = coincidentPoint(N, x, a, b)) {
|
||||
// exceptional case: x coincides with a Chebyshev point
|
||||
return differentiationMatrixRow(N, Points(N), *j) / ((b - a) / 2.0);
|
||||
}
|
||||
|
||||
|
||||
// This section of code computes the derivative of
|
||||
// the Barycentric Interpolation weights formula by applying
|
||||
// the chain rule on the original formula.
|
||||
|
||||
|
||||
// g and k are multiplier terms which represent the derivatives of
|
||||
// the numerator and denominator
|
||||
double g = 0, k = 0;
|
||||
double w = 1;
|
||||
|
||||
double w;
|
||||
|
||||
const Vector distances = signedDistances(N, x, a, b);
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
if (j == 0 || j == N - 1) {
|
||||
w = 0.5;
|
||||
} else {
|
||||
w = 1.0;
|
||||
}
|
||||
|
||||
t = (j % 2 == 0) ? 1 : -1;
|
||||
|
||||
|
||||
double t = (j % 2 == 0) ? 1 : -1;
|
||||
|
||||
double c = t / distances(j);
|
||||
g += w * c;
|
||||
k += (w * c / distances(j));
|
||||
}
|
||||
|
||||
|
||||
double s = 1; // changes sign s at every iteration
|
||||
double g2 = g * g;
|
||||
|
||||
for (size_t j = 0; j < N; j++, s = -s) {
|
||||
|
||||
Weights weightDerivatives(N);
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
// Beginning of interval, j = 0, x0 = -1.0 and end of interval, j = N-1,
|
||||
// x0 = 1.0
|
||||
if (j == 0 || j == N - 1) {
|
||||
|
@ -148,67 +193,121 @@ Weights Chebyshev2::DerivativeWeights(size_t N, double x, double a, double b) {
|
|||
}
|
||||
weightDerivatives(j) = (w * -s / (g * distances(j) * distances(j))) -
|
||||
(w * -s * k / (g2 * distances(j)));
|
||||
s *= -1;
|
||||
}
|
||||
|
||||
return weightDerivatives;
|
||||
}
|
||||
|
||||
Chebyshev2::DiffMatrix Chebyshev2::DifferentiationMatrix(size_t N, double a,
|
||||
double b) {
|
||||
Chebyshev2::DiffMatrix Chebyshev2::DifferentiationMatrix(size_t N) {
|
||||
DiffMatrix D(N, N);
|
||||
if (N == 1) {
|
||||
D(0, 0) = 1;
|
||||
return D;
|
||||
}
|
||||
|
||||
// toggle variable so we don't need to use `pow` for -1
|
||||
double t = -1;
|
||||
|
||||
const Vector points = Points(N);
|
||||
for (size_t i = 0; i < N; i++) {
|
||||
double xi = Point(N, i);
|
||||
double ci = (i == 0 || i == N - 1) ? 2. : 1.;
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
if (i == 0 && j == 0) {
|
||||
// we reverse the sign since we order the cheb points from -1 to 1
|
||||
D(i, j) = -(ci * (N - 1) * (N - 1) + 1) / 6.0;
|
||||
} else if (i == N - 1 && j == N - 1) {
|
||||
// we reverse the sign since we order the cheb points from -1 to 1
|
||||
D(i, j) = (ci * (N - 1) * (N - 1) + 1) / 6.0;
|
||||
} else if (i == j) {
|
||||
double xi2 = xi * xi;
|
||||
D(i, j) = -xi / (2 * (1 - xi2));
|
||||
} else {
|
||||
double xj = Point(N, j);
|
||||
double cj = (j == 0 || j == N - 1) ? 2. : 1.;
|
||||
t = ((i + j) % 2) == 0 ? 1 : -1;
|
||||
D(i, j) = (ci / cj) * t / (xi - xj);
|
||||
}
|
||||
}
|
||||
D.row(i) = differentiationMatrixRow(N, points, i);
|
||||
}
|
||||
// scale the matrix to the range
|
||||
return D / ((b - a) / 2.0);
|
||||
return D;
|
||||
}
|
||||
|
||||
Weights Chebyshev2::IntegrationWeights(size_t N, double a, double b) {
|
||||
// Allocate space for weights
|
||||
Weights weights(N);
|
||||
size_t K = N - 1, // number of intervals between N points
|
||||
K2 = K * K;
|
||||
weights(0) = 0.5 * (b - a) / (K2 + K % 2 - 1);
|
||||
weights(N - 1) = weights(0);
|
||||
|
||||
size_t last_k = K / 2 + K % 2 - 1;
|
||||
|
||||
for (size_t i = 1; i <= N - 2; ++i) {
|
||||
double theta = i * M_PI / K;
|
||||
weights(i) = (K % 2 == 0) ? 1 - cos(K * theta) / (K2 - 1) : 1;
|
||||
|
||||
for (size_t k = 1; k <= last_k; ++k)
|
||||
weights(i) -= 2 * cos(2 * k * theta) / (4 * k * k - 1);
|
||||
weights(i) *= (b - a) / K;
|
||||
Chebyshev2::DiffMatrix Chebyshev2::DifferentiationMatrix(size_t N, double a, double b) {
|
||||
DiffMatrix D(N, N);
|
||||
if (N == 1) {
|
||||
D(0, 0) = 1;
|
||||
return D;
|
||||
}
|
||||
|
||||
// Calculate for [-1,1] and scale for [a,b]
|
||||
return DifferentiationMatrix(N) / ((b - a) / 2.0);
|
||||
}
|
||||
|
||||
Matrix Chebyshev2::IntegrationMatrix(size_t N) {
|
||||
// Obtain the differentiation matrix.
|
||||
const Matrix D = DifferentiationMatrix(N);
|
||||
|
||||
// Compute the pseudo-inverse of the differentiation matrix.
|
||||
Eigen::JacobiSVD<Matrix> svd(D, Eigen::ComputeThinU | Eigen::ComputeThinV);
|
||||
const auto& S = svd.singularValues();
|
||||
Matrix invS = Matrix::Zero(N, N);
|
||||
for (size_t i = 0; i < N - 1; ++i) invS(i, i) = 1.0 / S(i);
|
||||
Matrix P = svd.matrixV() * invS * svd.matrixU().transpose();
|
||||
|
||||
// Return a version of P that makes sure (P*f)(0) = 0.
|
||||
const Weights row0 = P.row(0);
|
||||
P.rowwise() -= row0;
|
||||
return P;
|
||||
}
|
||||
|
||||
Matrix Chebyshev2::IntegrationMatrix(size_t N, double a, double b) {
|
||||
return IntegrationMatrix(N) * (b - a) / 2.0;
|
||||
}
|
||||
|
||||
/*
|
||||
Trefethen00book, pg 128, clencurt.m
|
||||
Note that N in clencurt.m is 1 less than our N, we call it K below.
|
||||
K = N-1;
|
||||
theta = pi*(0:K)'/K;
|
||||
w = zeros(1,N); ii = 2:K; v = ones(K-1, 1);
|
||||
if mod(K,2) == 0
|
||||
w(1) = 1/(K^2-1); w(N) = w(1);
|
||||
for k=1:K/2-1, v = v-2*cos(2*k*theta(ii))/(4*k^2-1); end
|
||||
v = v - cos(K*theta(ii))/(K^2-1);
|
||||
else
|
||||
w(1) = 1/K^2; w(N) = w(1);
|
||||
for k=1:K/2, v = v-2*cos(2*k*theta(ii))/(4*k^2-1); end
|
||||
end
|
||||
w(ii) = 2*v/K;
|
||||
*/
|
||||
Weights Chebyshev2::IntegrationWeights(size_t N) {
|
||||
Weights weights(N);
|
||||
const size_t K = N - 1, // number of intervals between N points
|
||||
K2 = K * K;
|
||||
|
||||
// Compute endpoint weight.
|
||||
weights(0) = 1.0 / (K2 + K % 2 - 1);
|
||||
weights(N - 1) = weights(0);
|
||||
|
||||
// Compute up to the middle; mirror symmetry holds.
|
||||
const size_t mid = (N - 1) / 2;
|
||||
double dTheta = M_PI / K;
|
||||
for (size_t i = 1; i <= mid; ++i) {
|
||||
double w = (K % 2 == 0) ? 1 - cos(i * M_PI) / (K2 - 1) : 1;
|
||||
const size_t last_k = K / 2 + K % 2 - 1;
|
||||
const double theta = i * dTheta;
|
||||
for (size_t k = 1; k <= last_k; ++k)
|
||||
w -= 2.0 * cos(2 * k * theta) / (4 * k * k - 1);
|
||||
w *= 2.0 / K;
|
||||
weights(i) = w;
|
||||
weights(N - 1 - i) = w;
|
||||
}
|
||||
return weights;
|
||||
}
|
||||
|
||||
Weights Chebyshev2::IntegrationWeights(size_t N, double a, double b) {
|
||||
return IntegrationWeights(N) * (b - a) / 2.0;
|
||||
}
|
||||
|
||||
Weights Chebyshev2::DoubleIntegrationWeights(size_t N) {
|
||||
// we have w * P, where w are the Clenshaw-Curtis weights and P is the integration matrix
|
||||
// But P does not by default return a function starting at zero.
|
||||
return Chebyshev2::IntegrationWeights(N) * Chebyshev2::IntegrationMatrix(N);
|
||||
}
|
||||
|
||||
Weights Chebyshev2::DoubleIntegrationWeights(size_t N, double a, double b) {
|
||||
return Chebyshev2::IntegrationWeights(N, a, b) * Chebyshev2::IntegrationMatrix(N, a, b);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create vector of values at Chebyshev points given scalar-valued function.
|
||||
*/
|
||||
Vector Chebyshev2::vector(std::function<double(double)> f, size_t N, double a, double b) {
|
||||
Vector fvals(N);
|
||||
const Vector points = Points(N, a, b);
|
||||
for (size_t j = 0; j < N; j++) fvals(j) = f(points(j));
|
||||
return fvals;
|
||||
}
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -51,9 +51,17 @@ class GTSAM_EXPORT Chebyshev2 : public Basis<Chebyshev2> {
|
|||
using Parameters = Eigen::Matrix<double, /*Nx1*/ -1, 1>;
|
||||
using DiffMatrix = Eigen::Matrix<double, /*NxN*/ -1, -1>;
|
||||
|
||||
/**
|
||||
* @brief Specific Chebyshev point, within [-1,1] interval.
|
||||
*
|
||||
* @param N The degree of the polynomial
|
||||
* @param j The index of the Chebyshev point
|
||||
* @return double
|
||||
*/
|
||||
static double Point(size_t N, int j);
|
||||
|
||||
/**
|
||||
* @brief Specific Chebyshev point, within [a,b] interval.
|
||||
* Default interval is [-1, 1]
|
||||
*
|
||||
* @param N The degree of the polynomial
|
||||
* @param j The index of the Chebyshev point
|
||||
|
@ -61,24 +69,13 @@ class GTSAM_EXPORT Chebyshev2 : public Basis<Chebyshev2> {
|
|||
* @param b Upper bound of interval (default: 1)
|
||||
* @return double
|
||||
*/
|
||||
static double Point(size_t N, int j, double a = -1, double b = 1);
|
||||
static double Point(size_t N, int j, double a, double b);
|
||||
|
||||
/// All Chebyshev points
|
||||
static Vector Points(size_t N) {
|
||||
Vector points(N);
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
points(j) = Point(N, j);
|
||||
}
|
||||
return points;
|
||||
}
|
||||
static Vector Points(size_t N);
|
||||
|
||||
/// All Chebyshev points, within [a,b] interval
|
||||
static Vector Points(size_t N, double a, double b) {
|
||||
Vector points = Points(N);
|
||||
const double T1 = (a + b) / 2, T2 = (b - a) / 2;
|
||||
points = T1 + (T2 * points).array();
|
||||
return points;
|
||||
}
|
||||
static Vector Points(size_t N, double a, double b);
|
||||
|
||||
/**
|
||||
* Evaluate Chebyshev Weights on [-1,1] at any x up to order N-1 (N values)
|
||||
|
@ -88,53 +85,61 @@ class GTSAM_EXPORT Chebyshev2 : public Basis<Chebyshev2> {
|
|||
* obtain a linear map from parameter vectors f to interpolated values f(x).
|
||||
* Optional [a,b] interval can be specified as well.
|
||||
*/
|
||||
static Weights CalculateWeights(size_t N, double x, double a = -1,
|
||||
double b = 1);
|
||||
static Weights CalculateWeights(size_t N, double x, double a = -1, double b = 1);
|
||||
|
||||
/**
|
||||
* Evaluate derivative of barycentric weights.
|
||||
* This is easy and efficient via the DifferentiationMatrix.
|
||||
*/
|
||||
static Weights DerivativeWeights(size_t N, double x, double a = -1,
|
||||
double b = 1);
|
||||
static Weights DerivativeWeights(size_t N, double x, double a = -1, double b = 1);
|
||||
|
||||
/// compute D = differentiation matrix, Trefethen00book p.53
|
||||
/// when given a parameter vector f of function values at the Chebyshev
|
||||
/// Compute D = differentiation matrix, Trefethen00book p.53
|
||||
/// When given a parameter vector f of function values at the Chebyshev
|
||||
/// points, D*f are the values of f'.
|
||||
/// https://people.maths.ox.ac.uk/trefethen/8all.pdf Theorem 8.4
|
||||
static DiffMatrix DifferentiationMatrix(size_t N, double a = -1,
|
||||
double b = 1);
|
||||
static DiffMatrix DifferentiationMatrix(size_t N);
|
||||
|
||||
/// Compute D = differentiation matrix, for interval [a,b]
|
||||
static DiffMatrix DifferentiationMatrix(size_t N, double a, double b);
|
||||
|
||||
/// IntegrationMatrix returns the (N+1)×(N+1) matrix P such that for any f,
|
||||
/// F = P * f recovers F (the antiderivative) satisfying f = D * F and F(0)=0.
|
||||
static Matrix IntegrationMatrix(size_t N);
|
||||
|
||||
/// IntegrationMatrix returns the (N+1)×(N+1) matrix P for interval [a,b]
|
||||
static Matrix IntegrationMatrix(size_t N, double a, double b);
|
||||
|
||||
/**
|
||||
* Evaluate Clenshaw-Curtis integration weights.
|
||||
* Calculate Clenshaw-Curtis integration weights.
|
||||
* Trefethen00book, pg 128, clencurt.m
|
||||
* Note that N in clencurt.m is 1 less than our N
|
||||
* K = N-1;
|
||||
theta = pi*(0:K)'/K;
|
||||
w = zeros(1,N); ii = 2:K; v = ones(K-1, 1);
|
||||
if mod(K,2) == 0
|
||||
w(1) = 1/(K^2-1); w(N) = w(1);
|
||||
for k=1:K/2-1, v = v-2*cos(2*k*theta(ii))/(4*k^2-1); end
|
||||
v = v - cos(K*theta(ii))/(K^2-1);
|
||||
else
|
||||
w(1) = 1/K^2; w(N) = w(1);
|
||||
for k=1:K/2, v = v-2*cos(2*k*theta(ii))/(4*k^2-1); end
|
||||
end
|
||||
w(ii) = 2*v/K;
|
||||
|
||||
*/
|
||||
static Weights IntegrationWeights(size_t N, double a = -1, double b = 1);
|
||||
static Weights IntegrationWeights(size_t N);
|
||||
|
||||
/// Calculate Clenshaw-Curtis integration weights, for interval [a,b]
|
||||
static Weights IntegrationWeights(size_t N, double a, double b);
|
||||
|
||||
/**
|
||||
* Create matrix of values at Chebyshev points given vector-valued function.
|
||||
* Calculate Double Clenshaw-Curtis integration weights
|
||||
* We compute them as W * P, where W are the Clenshaw-Curtis weights and P is
|
||||
* the integration matrix.
|
||||
*/
|
||||
static Weights DoubleIntegrationWeights(size_t N);
|
||||
|
||||
/// Calculate Double Clenshaw-Curtis integration weights, for interval [a,b]
|
||||
static Weights DoubleIntegrationWeights(size_t N, double a, double b);
|
||||
|
||||
/// Create matrix of values at Chebyshev points given vector-valued function.
|
||||
static Vector vector(std::function<double(double)> f,
|
||||
size_t N, double a = -1, double b = 1);
|
||||
|
||||
/// Create matrix of values at Chebyshev points given vector-valued function.
|
||||
template <size_t M>
|
||||
static Matrix matrix(std::function<Eigen::Matrix<double, M, 1>(double)> f,
|
||||
size_t N, double a = -1, double b = 1) {
|
||||
size_t N, double a = -1, double b = 1) {
|
||||
Matrix Xmat(M, N);
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
Xmat.col(j) = f(Point(N, j, a, b));
|
||||
}
|
||||
const Vector points = Points(N, a, b);
|
||||
for (size_t j = 0; j < N; j++) Xmat.col(j) = f(points(j));
|
||||
return Xmat;
|
||||
}
|
||||
}; // \ Chebyshev2
|
||||
|
|
|
@ -40,10 +40,20 @@ class Chebyshev2 {
|
|||
static gtsam::Matrix WeightMatrix(size_t N, gtsam::Vector X);
|
||||
static gtsam::Matrix WeightMatrix(size_t N, gtsam::Vector X, double a, double b);
|
||||
|
||||
static gtsam::Matrix CalculateWeights(size_t N, double x);
|
||||
static gtsam::Matrix DerivativeWeights(size_t N, double x);
|
||||
|
||||
static gtsam::Matrix IntegrationMatrix(size_t N);
|
||||
static gtsam::Matrix DifferentiationMatrix(size_t N);
|
||||
static gtsam::Matrix IntegrationWeights(size_t N);
|
||||
static gtsam::Matrix DoubleIntegrationWeights(size_t N);
|
||||
|
||||
static gtsam::Matrix CalculateWeights(size_t N, double x, double a, double b);
|
||||
static gtsam::Matrix DerivativeWeights(size_t N, double x, double a, double b);
|
||||
static gtsam::Matrix IntegrationWeights(size_t N, double a, double b);
|
||||
static gtsam::Matrix IntegrationMatrix(size_t N, double a, double b);
|
||||
static gtsam::Matrix DifferentiationMatrix(size_t N, double a, double b);
|
||||
static gtsam::Matrix IntegrationWeights(size_t N, double a, double b);
|
||||
static gtsam::Matrix DoubleIntegrationWeights(size_t N, double a, double b);
|
||||
};
|
||||
|
||||
#include <gtsam/basis/BasisFactors.h>
|
||||
|
|
|
@ -9,13 +9,13 @@
|
|||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/**
|
||||
* @file testChebyshev2.cpp
|
||||
* @date July 4, 2020
|
||||
* @author Varun Agrawal
|
||||
* @brief Unit tests for Chebyshev Basis Decompositions via pseudo-spectral
|
||||
* methods
|
||||
*/
|
||||
/**
|
||||
* @file testChebyshev2.cpp
|
||||
* @date July 4, 2020
|
||||
* @author Varun Agrawal
|
||||
* @brief Unit tests for Chebyshev Basis Decompositions via pseudo-spectral
|
||||
* methods
|
||||
*/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
@ -28,18 +28,11 @@
|
|||
#include <cstddef>
|
||||
#include <functional>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
namespace {
|
||||
noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1);
|
||||
|
||||
const size_t N = 32;
|
||||
} // namespace
|
||||
|
||||
//******************************************************************************
|
||||
TEST(Chebyshev2, Point) {
|
||||
static const int N = 5;
|
||||
static const size_t N = 5;
|
||||
auto points = Chebyshev2::Points(N);
|
||||
Vector expected(N);
|
||||
expected << -1., -sqrt(2.) / 2., 0., sqrt(2.) / 2., 1.;
|
||||
|
@ -57,7 +50,7 @@ TEST(Chebyshev2, Point) {
|
|||
|
||||
//******************************************************************************
|
||||
TEST(Chebyshev2, PointInInterval) {
|
||||
static const int N = 5;
|
||||
static const size_t N = 5;
|
||||
auto points = Chebyshev2::Points(N, 0, 20);
|
||||
Vector expected(N);
|
||||
expected << 0., 1. - sqrt(2.) / 2., 1., 1. + sqrt(2.) / 2., 2.;
|
||||
|
@ -77,7 +70,7 @@ TEST(Chebyshev2, PointInInterval) {
|
|||
//******************************************************************************
|
||||
// InterpolatingPolynomial[{{-1, 4}, {0, 2}, {1, 6}}, 0.5]
|
||||
TEST(Chebyshev2, Interpolate2) {
|
||||
size_t N = 3;
|
||||
const size_t N = 3;
|
||||
Chebyshev2::EvaluationFunctor fx(N, 0.5);
|
||||
Vector f(N);
|
||||
f << 4, 2, 6;
|
||||
|
@ -121,16 +114,17 @@ TEST(Chebyshev2, InterpolateVector) {
|
|||
|
||||
// Check derivative
|
||||
std::function<Vector2(Matrix)> f =
|
||||
std::bind(&Chebyshev2::VectorEvaluationFunctor::operator(), fx,
|
||||
std::placeholders::_1, nullptr);
|
||||
std::bind(&Chebyshev2::VectorEvaluationFunctor::operator(), fx,
|
||||
std::placeholders::_1, nullptr);
|
||||
Matrix numericalH =
|
||||
numericalDerivative11<Vector2, Matrix, 2 * N>(f, X);
|
||||
numericalDerivative11<Vector2, Matrix, 2 * N>(f, X);
|
||||
EXPECT(assert_equal(numericalH, actualH, 1e-9));
|
||||
}
|
||||
|
||||
//******************************************************************************
|
||||
// Interpolating poses using the exponential map
|
||||
TEST(Chebyshev2, InterpolatePose2) {
|
||||
const size_t N = 32;
|
||||
double t = 30, a = 0, b = 100;
|
||||
|
||||
Matrix X(3, N);
|
||||
|
@ -149,10 +143,10 @@ TEST(Chebyshev2, InterpolatePose2) {
|
|||
|
||||
// Check derivative
|
||||
std::function<Pose2(Matrix)> f =
|
||||
std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose2>::operator(), fx,
|
||||
std::placeholders::_1, nullptr);
|
||||
std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose2>::operator(), fx,
|
||||
std::placeholders::_1, nullptr);
|
||||
Matrix numericalH =
|
||||
numericalDerivative11<Pose2, Matrix, 3 * N>(f, X);
|
||||
numericalDerivative11<Pose2, Matrix, 3 * N>(f, X);
|
||||
EXPECT(assert_equal(numericalH, actualH, 1e-9));
|
||||
}
|
||||
|
||||
|
@ -160,6 +154,7 @@ TEST(Chebyshev2, InterpolatePose2) {
|
|||
//******************************************************************************
|
||||
// Interpolating poses using the exponential map
|
||||
TEST(Chebyshev2, InterpolatePose3) {
|
||||
const size_t N = 32;
|
||||
double a = 10, b = 100;
|
||||
double t = Chebyshev2::Points(N, a, b)(11);
|
||||
|
||||
|
@ -179,10 +174,10 @@ TEST(Chebyshev2, InterpolatePose3) {
|
|||
|
||||
// Check derivative
|
||||
std::function<Pose3(Matrix)> f =
|
||||
std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose3>::operator(), fx,
|
||||
std::placeholders::_1, nullptr);
|
||||
std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose3>::operator(), fx,
|
||||
std::placeholders::_1, nullptr);
|
||||
Matrix numericalH =
|
||||
numericalDerivative11<Pose3, Matrix, 6 * N>(f, X);
|
||||
numericalDerivative11<Pose3, Matrix, 6 * N>(f, X);
|
||||
EXPECT(assert_equal(numericalH, actualH, 1e-8));
|
||||
}
|
||||
#endif
|
||||
|
@ -197,7 +192,7 @@ TEST(Chebyshev2, Decomposition) {
|
|||
}
|
||||
|
||||
// Do Chebyshev Decomposition
|
||||
FitBasis<Chebyshev2> actual(sequence, model, 3);
|
||||
FitBasis<Chebyshev2> actual(sequence, nullptr, 3);
|
||||
|
||||
// Check
|
||||
Vector expected(3);
|
||||
|
@ -212,8 +207,8 @@ TEST(Chebyshev2, DifferentiationMatrix3) {
|
|||
Matrix expected(N, N);
|
||||
// Differentiation matrix computed from chebfun
|
||||
expected << 1.5000, -2.0000, 0.5000, //
|
||||
0.5000, -0.0000, -0.5000, //
|
||||
-0.5000, 2.0000, -1.5000;
|
||||
0.5000, -0.0000, -0.5000, //
|
||||
-0.5000, 2.0000, -1.5000;
|
||||
// multiply by -1 since the chebyshev points have a phase shift wrt Trefethen
|
||||
// This was verified with chebfun
|
||||
expected = -expected;
|
||||
|
@ -228,11 +223,11 @@ TEST(Chebyshev2, DerivativeMatrix6) {
|
|||
const size_t N = 6;
|
||||
Matrix expected(N, N);
|
||||
expected << 8.5000, -10.4721, 2.8944, -1.5279, 1.1056, -0.5000, //
|
||||
2.6180, -1.1708, -2.0000, 0.8944, -0.6180, 0.2764, //
|
||||
-0.7236, 2.0000, -0.1708, -1.6180, 0.8944, -0.3820, //
|
||||
0.3820, -0.8944, 1.6180, 0.1708, -2.0000, 0.7236, //
|
||||
-0.2764, 0.6180, -0.8944, 2.0000, 1.1708, -2.6180, //
|
||||
0.5000, -1.1056, 1.5279, -2.8944, 10.4721, -8.5000;
|
||||
2.6180, -1.1708, -2.0000, 0.8944, -0.6180, 0.2764, //
|
||||
-0.7236, 2.0000, -0.1708, -1.6180, 0.8944, -0.3820, //
|
||||
0.3820, -0.8944, 1.6180, 0.1708, -2.0000, 0.7236, //
|
||||
-0.2764, 0.6180, -0.8944, 2.0000, 1.1708, -2.6180, //
|
||||
0.5000, -1.1056, 1.5279, -2.8944, 10.4721, -8.5000;
|
||||
// multiply by -1 since the chebyshev points have a phase shift wrt Trefethen
|
||||
// This was verified with chebfun
|
||||
expected = -expected;
|
||||
|
@ -255,10 +250,8 @@ double fprime(double x) {
|
|||
|
||||
//******************************************************************************
|
||||
TEST(Chebyshev2, CalculateWeights) {
|
||||
Eigen::Matrix<double, -1, 1> fvals(N);
|
||||
for (size_t i = 0; i < N; i++) {
|
||||
fvals(i) = f(Chebyshev2::Point(N, i));
|
||||
}
|
||||
const size_t N = 32;
|
||||
Vector fvals = Chebyshev2::vector(f, N);
|
||||
double x1 = 0.7, x2 = -0.376;
|
||||
Weights weights1 = Chebyshev2::CalculateWeights(N, x1);
|
||||
Weights weights2 = Chebyshev2::CalculateWeights(N, x2);
|
||||
|
@ -267,12 +260,9 @@ TEST(Chebyshev2, CalculateWeights) {
|
|||
}
|
||||
|
||||
TEST(Chebyshev2, CalculateWeights2) {
|
||||
const size_t N = 32;
|
||||
double a = 0, b = 10, x1 = 7, x2 = 4.12;
|
||||
|
||||
Eigen::Matrix<double, -1, 1> fvals(N);
|
||||
for (size_t i = 0; i < N; i++) {
|
||||
fvals(i) = f(Chebyshev2::Point(N, i, a, b));
|
||||
}
|
||||
Vector fvals = Chebyshev2::vector(f, N, a, b);
|
||||
|
||||
Weights weights1 = Chebyshev2::CalculateWeights(N, x1, a, b);
|
||||
EXPECT_DOUBLES_EQUAL(f(x1), weights1 * fvals, 1e-8);
|
||||
|
@ -283,34 +273,39 @@ TEST(Chebyshev2, CalculateWeights2) {
|
|||
EXPECT_DOUBLES_EQUAL(expected2, actual2, 1e-8);
|
||||
}
|
||||
|
||||
TEST(Chebyshev2, DerivativeWeights) {
|
||||
Eigen::Matrix<double, -1, 1> fvals(N);
|
||||
for (size_t i = 0; i < N; i++) {
|
||||
fvals(i) = f(Chebyshev2::Point(N, i));
|
||||
// Test CalculateWeights when a point coincides with a Chebyshev point
|
||||
TEST(Chebyshev2, CalculateWeights_CoincidingPoint) {
|
||||
const size_t N = 5;
|
||||
const double coincidingPoint = Chebyshev2::Point(N, 1); // Pick the 2nd point
|
||||
|
||||
// Generate weights for the coinciding point
|
||||
Weights weights = Chebyshev2::CalculateWeights(N, coincidingPoint);
|
||||
|
||||
// Verify that the weights are zero everywhere except at the coinciding point
|
||||
for (size_t j = 0; j < N; ++j) {
|
||||
EXPECT_DOUBLES_EQUAL(j == 1 ? 1.0 : 0.0, weights(j), 1e-9);
|
||||
}
|
||||
double x1 = 0.7, x2 = -0.376, x3 = 0.0;
|
||||
Weights dWeights1 = Chebyshev2::DerivativeWeights(N, x1);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x1), dWeights1 * fvals, 1e-9);
|
||||
}
|
||||
|
||||
Weights dWeights2 = Chebyshev2::DerivativeWeights(N, x2);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x2), dWeights2 * fvals, 1e-9);
|
||||
TEST(Chebyshev2, DerivativeWeights) {
|
||||
const size_t N = 32;
|
||||
Vector fvals = Chebyshev2::vector(f, N);
|
||||
std::vector<double> testPoints = { 0.7, -0.376, 0.0 };
|
||||
for (double x : testPoints) {
|
||||
Weights dWeights = Chebyshev2::DerivativeWeights(N, x);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x), dWeights * fvals, 1e-9);
|
||||
}
|
||||
|
||||
Weights dWeights3 = Chebyshev2::DerivativeWeights(N, x3);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x3), dWeights3 * fvals, 1e-9);
|
||||
|
||||
// test if derivative calculation and cheb point is correct
|
||||
// test if derivative calculation at Chebyshev point is correct
|
||||
double x4 = Chebyshev2::Point(N, 3);
|
||||
Weights dWeights4 = Chebyshev2::DerivativeWeights(N, x4);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x4), dWeights4 * fvals, 1e-9);
|
||||
}
|
||||
|
||||
TEST(Chebyshev2, DerivativeWeights2) {
|
||||
const size_t N = 32;
|
||||
double x1 = 5, x2 = 4.12, a = 0, b = 10;
|
||||
|
||||
Eigen::Matrix<double, -1, 1> fvals(N);
|
||||
for (size_t i = 0; i < N; i++) {
|
||||
fvals(i) = f(Chebyshev2::Point(N, i, a, b));
|
||||
}
|
||||
Vector fvals = Chebyshev2::vector(f, N, a, b);
|
||||
|
||||
Weights dWeights1 = Chebyshev2::DerivativeWeights(N, x1, a, b);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x1), dWeights1 * fvals, 1e-8);
|
||||
|
@ -318,12 +313,13 @@ TEST(Chebyshev2, DerivativeWeights2) {
|
|||
Weights dWeights2 = Chebyshev2::DerivativeWeights(N, x2, a, b);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x2), dWeights2 * fvals, 1e-8);
|
||||
|
||||
// test if derivative calculation and Chebyshev point is correct
|
||||
// test if derivative calculation at Chebyshev point is correct
|
||||
double x3 = Chebyshev2::Point(N, 3, a, b);
|
||||
Weights dWeights3 = Chebyshev2::DerivativeWeights(N, x3, a, b);
|
||||
EXPECT_DOUBLES_EQUAL(fprime(x3), dWeights3 * fvals, 1e-8);
|
||||
}
|
||||
|
||||
|
||||
//******************************************************************************
|
||||
// Check two different ways to calculate the derivative weights
|
||||
TEST(Chebyshev2, DerivativeWeightsDifferentiationMatrix) {
|
||||
|
@ -366,9 +362,8 @@ double proxy3(double x) {
|
|||
return Chebyshev2::EvaluationFunctor(6, x)(f3_at_6points);
|
||||
}
|
||||
|
||||
// Check Derivative evaluation at point x=0.2
|
||||
TEST(Chebyshev2, Derivative6) {
|
||||
// Check Derivative evaluation at point x=0.2
|
||||
|
||||
// calculate expected values by numerical derivative of synthesis
|
||||
const double x = 0.2;
|
||||
Matrix numeric_dTdx = numericalDerivative11<double, double>(proxy3, x);
|
||||
|
@ -420,15 +415,15 @@ TEST(Chebyshev2, VectorDerivativeFunctor) {
|
|||
EXPECT(assert_equal(Vector::Zero(M), (Vector)fx(X, actualH), 1e-8));
|
||||
|
||||
// Test Jacobian
|
||||
Matrix expectedH = numericalDerivative11<Vector2, Matrix, M * N>(
|
||||
std::bind(&VecD::operator(), fx, std::placeholders::_1, nullptr), X);
|
||||
Matrix expectedH = numericalDerivative11<Vector2, Matrix, M* N>(
|
||||
std::bind(&VecD::operator(), fx, std::placeholders::_1, nullptr), X);
|
||||
EXPECT(assert_equal(expectedH, actualH, 1e-7));
|
||||
}
|
||||
|
||||
//******************************************************************************
|
||||
// Test VectorDerivativeFunctor with polynomial function
|
||||
TEST(Chebyshev2, VectorDerivativeFunctor2) {
|
||||
const size_t N = 64, M = 1, T = 15;
|
||||
const size_t N = 4, M = 1, T = 15;
|
||||
using VecD = Chebyshev2::VectorDerivativeFunctor;
|
||||
|
||||
const Vector points = Chebyshev2::Points(N, 0, T);
|
||||
|
@ -451,8 +446,8 @@ TEST(Chebyshev2, VectorDerivativeFunctor2) {
|
|||
Matrix actualH(M, M * N);
|
||||
VecD vecd(M, N, points(0), 0, T);
|
||||
vecd(X, actualH);
|
||||
Matrix expectedH = numericalDerivative11<Vector1, Matrix, M * N>(
|
||||
std::bind(&VecD::operator(), vecd, std::placeholders::_1, nullptr), X);
|
||||
Matrix expectedH = numericalDerivative11<Vector1, Matrix, M* N>(
|
||||
std::bind(&VecD::operator(), vecd, std::placeholders::_1, nullptr), X);
|
||||
EXPECT(assert_equal(expectedH, actualH, 1e-6));
|
||||
}
|
||||
|
||||
|
@ -468,28 +463,120 @@ TEST(Chebyshev2, ComponentDerivativeFunctor) {
|
|||
Matrix actualH(1, M * N);
|
||||
EXPECT_DOUBLES_EQUAL(0, fx(X, actualH), 1e-8);
|
||||
|
||||
Matrix expectedH = numericalDerivative11<double, Matrix, M * N>(
|
||||
std::bind(&CompFunc::operator(), fx, std::placeholders::_1, nullptr), X);
|
||||
Matrix expectedH = numericalDerivative11<double, Matrix, M* N>(
|
||||
std::bind(&CompFunc::operator(), fx, std::placeholders::_1, nullptr), X);
|
||||
EXPECT(assert_equal(expectedH, actualH, 1e-7));
|
||||
}
|
||||
|
||||
//******************************************************************************
|
||||
TEST(Chebyshev2, IntegralWeights) {
|
||||
const size_t N7 = 7;
|
||||
Vector actual = Chebyshev2::IntegrationWeights(N7);
|
||||
Vector expected = (Vector(N7) << 0.0285714285714286, 0.253968253968254,
|
||||
0.457142857142857, 0.520634920634921, 0.457142857142857,
|
||||
0.253968253968254, 0.0285714285714286)
|
||||
.finished();
|
||||
TEST(Chebyshev2, IntegrationMatrix) {
|
||||
const size_t N = 10; // number of intervals => N+1 nodes
|
||||
const double a = 0, b = 10;
|
||||
|
||||
// Create integration matrix
|
||||
Matrix P = Chebyshev2::IntegrationMatrix(N, a, b);
|
||||
|
||||
// Let's check that integrating a constant yields
|
||||
// the sum of the lengths of the intervals:
|
||||
Vector F = P * Vector::Ones(N);
|
||||
EXPECT_DOUBLES_EQUAL(0, F(0), 1e-9); // check first value is 0
|
||||
Vector points = Chebyshev2::Points(N, a, b);
|
||||
Vector ramp(N);
|
||||
for (size_t i = 0; i < N; ++i) ramp(i) = points(i) - a;
|
||||
EXPECT(assert_equal(ramp, F, 1e-9));
|
||||
|
||||
// Get values of the derivative (fprime) at the Chebyshev nodes
|
||||
Vector fp = Chebyshev2::vector(fprime, N, a, b);
|
||||
|
||||
// Integrate to get back f, using the integration matrix.
|
||||
// Since there is a constant term, we need to add it back.
|
||||
Vector F_est = P * fp;
|
||||
EXPECT_DOUBLES_EQUAL(0, F_est(0), 1e-9); // check first value is 0
|
||||
|
||||
// For comparison, get actual function values at the nodes
|
||||
Vector F_true = Chebyshev2::vector(f, N, a, b);
|
||||
|
||||
// Verify the integration matrix worked correctly, after adding back the
|
||||
// constant term
|
||||
F_est.array() += f(a);
|
||||
EXPECT(assert_equal(F_true, F_est, 1e-9));
|
||||
|
||||
// Differentiate the result to get back to our derivative function
|
||||
Matrix D = Chebyshev2::DifferentiationMatrix(N, a, b);
|
||||
Vector ff_est = D * F_est;
|
||||
|
||||
// Verify the round trip worked
|
||||
EXPECT(assert_equal(fp, ff_est, 1e-9));
|
||||
}
|
||||
|
||||
//******************************************************************************
|
||||
TEST(Chebyshev2, IntegrationWeights7) {
|
||||
const size_t N = 7;
|
||||
Weights actual = Chebyshev2::IntegrationWeights(N, -1, 1);
|
||||
|
||||
// Expected values were calculated using chebfun:
|
||||
Weights expected = (Weights(N) << 0.0285714285714286, 0.253968253968254,
|
||||
0.457142857142857, 0.520634920634921, 0.457142857142857,
|
||||
0.253968253968254, 0.0285714285714286)
|
||||
.finished();
|
||||
EXPECT(assert_equal(expected, actual));
|
||||
|
||||
const size_t N8 = 8;
|
||||
Vector actual2 = Chebyshev2::IntegrationWeights(N8);
|
||||
Vector expected2 = (Vector(N8) << 0.0204081632653061, 0.190141007218208,
|
||||
0.352242423718159, 0.437208405798326, 0.437208405798326,
|
||||
0.352242423718159, 0.190141007218208, 0.0204081632653061)
|
||||
.finished();
|
||||
EXPECT(assert_equal(expected2, actual2));
|
||||
// Assert that multiplying with all ones gives the correct integral (2.0)
|
||||
EXPECT_DOUBLES_EQUAL(2.0, actual.array().sum(), 1e-9);
|
||||
|
||||
// Integrating f' over [-1,1] should give f(1) - f(-1)
|
||||
Vector fp = Chebyshev2::vector(fprime, N);
|
||||
double expectedF = f(1) - f(-1);
|
||||
double actualW = actual * fp;
|
||||
EXPECT_DOUBLES_EQUAL(expectedF, actualW, 1e-9);
|
||||
|
||||
// We can calculate an alternate set of weights using the integration matrix:
|
||||
Matrix P = Chebyshev2::IntegrationMatrix(N);
|
||||
Weights p7 = P.row(N-1);
|
||||
|
||||
// Check that the two sets of weights give the same results
|
||||
EXPECT_DOUBLES_EQUAL(expectedF, p7 * fp, 1e-9);
|
||||
|
||||
// And same for integrate f itself:
|
||||
Vector fvals = Chebyshev2::vector(f, N);
|
||||
EXPECT_DOUBLES_EQUAL(p7*fvals, actual * fvals, 1e-9);
|
||||
}
|
||||
|
||||
// Check N=8
|
||||
TEST(Chebyshev2, IntegrationWeights8) {
|
||||
const size_t N = 8;
|
||||
Weights actual = Chebyshev2::IntegrationWeights(N, -1, 1);
|
||||
Weights expected = (Weights(N) << 0.0204081632653061, 0.190141007218208,
|
||||
0.352242423718159, 0.437208405798326, 0.437208405798326,
|
||||
0.352242423718159, 0.190141007218208, 0.0204081632653061)
|
||||
.finished();
|
||||
EXPECT(assert_equal(expected, actual));
|
||||
EXPECT_DOUBLES_EQUAL(2.0, actual.array().sum(), 1e-9);
|
||||
}
|
||||
|
||||
//******************************************************************************
|
||||
TEST(Chebyshev2, DoubleIntegrationWeights) {
|
||||
const size_t N = 7;
|
||||
const double a = 0, b = 10;
|
||||
// Let's integrate constant twice get a test case:
|
||||
Matrix P = Chebyshev2::IntegrationMatrix(N, a, b);
|
||||
auto ones = Vector::Ones(N);
|
||||
|
||||
// Check the sum which should be 0.5*t^2 | [0,b] = b^2/2:
|
||||
Weights w = Chebyshev2::DoubleIntegrationWeights(N, a, b);
|
||||
EXPECT_DOUBLES_EQUAL(b*b/2, w * ones, 1e-9);
|
||||
}
|
||||
|
||||
TEST(Chebyshev2, DoubleIntegrationWeights2) {
|
||||
const size_t N = 8;
|
||||
const double a = 0, b = 3;
|
||||
// Let's integrate constant twice get a test case:
|
||||
Matrix P = Chebyshev2::IntegrationMatrix(N, a, b);
|
||||
auto ones = Vector::Ones(N);
|
||||
|
||||
// Check the sum which should be 0.5*t^2 | [0,b] = b^2/2:
|
||||
Weights w = Chebyshev2::DoubleIntegrationWeights(N, a, b);
|
||||
EXPECT_DOUBLES_EQUAL(b*b/2, w * ones, 1e-9);
|
||||
}
|
||||
|
||||
//******************************************************************************
|
||||
|
|
|
@ -200,6 +200,19 @@ class GTSAM_EXPORT Similarity2 : public LieGroup<Similarity2, 4> {
|
|||
/// Dimensionality of tangent space = 4 DOF
|
||||
inline size_t dim() const { return 4; }
|
||||
|
||||
private:
|
||||
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(R_);
|
||||
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||
ar & BOOST_SERIALIZATION_NVP(s_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
||||
|
|
|
@ -73,9 +73,10 @@ HybridBayesNet HybridBayesNet::prune(
|
|||
if (conditional->isDiscrete()) continue;
|
||||
|
||||
// No-op if not a HybridGaussianConditional.
|
||||
if (marginalThreshold)
|
||||
if (marginalThreshold) {
|
||||
conditional = std::static_pointer_cast<HybridConditional>(
|
||||
conditional->restrict(fixed));
|
||||
}
|
||||
|
||||
// Now decide on type what to do:
|
||||
if (auto hgc = conditional->asHybrid()) {
|
||||
|
|
|
@ -134,10 +134,12 @@ void HybridNonlinearFactor::print(const std::string& s,
|
|||
std::cout << (s.empty() ? "" : s + " ");
|
||||
Base::print("", keyFormatter);
|
||||
std::cout << "\nHybridNonlinearFactor\n";
|
||||
auto valueFormatter = [](const std::pair<sharedFactor, double>& v) {
|
||||
auto valueFormatter = [&keyFormatter](const std::pair<sharedFactor, double>& v) {
|
||||
auto [factor, val] = v;
|
||||
if (factor) {
|
||||
return "Nonlinear factor on " + std::to_string(factor->size()) + " keys";
|
||||
RedirectCout rd;
|
||||
factor->print("", keyFormatter);
|
||||
return rd.str();
|
||||
} else {
|
||||
return std::string("nullptr");
|
||||
}
|
||||
|
|
|
@ -62,31 +62,12 @@ Ordering HybridSmoother::getOrdering(const HybridGaussianFactorGraph &factors,
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void HybridSmoother::update(const HybridGaussianFactorGraph &newFactors,
|
||||
std::optional<size_t> maxNrLeaves,
|
||||
const std::optional<Ordering> given_ordering) {
|
||||
const KeySet originalNewFactorKeys = newFactors.keys();
|
||||
#ifdef DEBUG_SMOOTHER
|
||||
std::cout << "hybridBayesNet_ size before: " << hybridBayesNet_.size()
|
||||
<< std::endl;
|
||||
std::cout << "newFactors size: " << newFactors.size() << std::endl;
|
||||
#endif
|
||||
HybridGaussianFactorGraph updatedGraph;
|
||||
// Add the necessary conditionals from the previous timestep(s).
|
||||
std::tie(updatedGraph, hybridBayesNet_) =
|
||||
addConditionals(newFactors, hybridBayesNet_);
|
||||
#ifdef DEBUG_SMOOTHER
|
||||
// print size of newFactors, updatedGraph, hybridBayesNet_
|
||||
std::cout << "updatedGraph size: " << updatedGraph.size() << std::endl;
|
||||
std::cout << "hybridBayesNet_ size after: " << hybridBayesNet_.size()
|
||||
<< std::endl;
|
||||
std::cout << "total size: " << updatedGraph.size() + hybridBayesNet_.size()
|
||||
<< std::endl;
|
||||
#endif
|
||||
|
||||
Ordering HybridSmoother::maybeComputeOrdering(
|
||||
const HybridGaussianFactorGraph &updatedGraph,
|
||||
const std::optional<Ordering> givenOrdering) {
|
||||
Ordering ordering;
|
||||
// If no ordering provided, then we compute one
|
||||
if (!given_ordering.has_value()) {
|
||||
if (!givenOrdering.has_value()) {
|
||||
// Get the keys from the new factors
|
||||
KeySet continuousKeysToInclude; // Scheme 1: empty, 15sec/2000, 64sec/3000
|
||||
// (69s without TF)
|
||||
|
@ -98,9 +79,55 @@ void HybridSmoother::update(const HybridGaussianFactorGraph &newFactors,
|
|||
// we can get the correct ordering.
|
||||
ordering = this->getOrdering(updatedGraph, continuousKeysToInclude);
|
||||
} else {
|
||||
ordering = *given_ordering;
|
||||
ordering = *givenOrdering;
|
||||
}
|
||||
|
||||
return ordering;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void HybridSmoother::removeFixedValues(
|
||||
const HybridGaussianFactorGraph &newFactors) {
|
||||
for (Key key : newFactors.discreteKeySet()) {
|
||||
if (fixedValues_.find(key) != fixedValues_.end()) {
|
||||
fixedValues_.erase(key);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void HybridSmoother::update(const HybridNonlinearFactorGraph &newFactors,
|
||||
const Values &initial,
|
||||
std::optional<size_t> maxNrLeaves,
|
||||
const std::optional<Ordering> given_ordering) {
|
||||
HybridGaussianFactorGraph linearizedFactors = *newFactors.linearize(initial);
|
||||
|
||||
// Record the new nonlinear factors and
|
||||
// linearization point for relinearization
|
||||
allFactors_.push_back(newFactors);
|
||||
linearizationPoint_.insert_or_assign(initial);
|
||||
|
||||
const KeySet originalNewFactorKeys = newFactors.keys();
|
||||
#ifdef DEBUG_SMOOTHER
|
||||
std::cout << "hybridBayesNet_ size before: " << hybridBayesNet_.size()
|
||||
<< std::endl;
|
||||
std::cout << "newFactors size: " << newFactors.size() << std::endl;
|
||||
#endif
|
||||
HybridGaussianFactorGraph updatedGraph;
|
||||
// Add the necessary conditionals from the previous timestep(s).
|
||||
std::tie(updatedGraph, hybridBayesNet_) =
|
||||
addConditionals(linearizedFactors, hybridBayesNet_);
|
||||
#ifdef DEBUG_SMOOTHER
|
||||
// print size of newFactors, updatedGraph, hybridBayesNet_
|
||||
std::cout << "updatedGraph size: " << updatedGraph.size() << std::endl;
|
||||
std::cout << "hybridBayesNet_ size after: " << hybridBayesNet_.size()
|
||||
<< std::endl;
|
||||
std::cout << "total size: " << updatedGraph.size() + hybridBayesNet_.size()
|
||||
<< std::endl;
|
||||
#endif
|
||||
|
||||
Ordering ordering = this->maybeComputeOrdering(updatedGraph, given_ordering);
|
||||
|
||||
#if GTSAM_HYBRID_TIMING
|
||||
gttic_(HybridSmootherEliminate);
|
||||
#endif
|
||||
|
@ -118,6 +145,9 @@ void HybridSmoother::update(const HybridGaussianFactorGraph &newFactors,
|
|||
}
|
||||
#endif
|
||||
|
||||
// Remove fixed values for discrete keys which are introduced in newFactors
|
||||
removeFixedValues(newFactors);
|
||||
|
||||
#ifdef DEBUG_SMOOTHER
|
||||
// Print discrete keys in the bayesNetFragment:
|
||||
std::cout << "Discrete keys in bayesNetFragment: ";
|
||||
|
@ -171,7 +201,7 @@ HybridSmoother::addConditionals(const HybridGaussianFactorGraph &newFactors,
|
|||
HybridBayesNet updatedHybridBayesNet(hybridBayesNet);
|
||||
|
||||
KeySet involvedKeys = newFactors.keys();
|
||||
auto involved = [&involvedKeys](const Key &key) {
|
||||
auto involved = [](const KeySet &involvedKeys, const Key &key) {
|
||||
return involvedKeys.find(key) != involvedKeys.end();
|
||||
};
|
||||
|
||||
|
@ -195,7 +225,7 @@ HybridSmoother::addConditionals(const HybridGaussianFactorGraph &newFactors,
|
|||
auto conditional = hybridBayesNet.at(i);
|
||||
|
||||
for (auto &key : conditional->frontals()) {
|
||||
if (involved(key)) {
|
||||
if (involved(involvedKeys, key)) {
|
||||
// Add the conditional parents to involvedKeys
|
||||
// so we add those conditionals too.
|
||||
for (auto &&parentKey : conditional->parents()) {
|
||||
|
@ -214,7 +244,7 @@ HybridSmoother::addConditionals(const HybridGaussianFactorGraph &newFactors,
|
|||
auto conditional = hybridBayesNet.at(i);
|
||||
|
||||
for (auto &key : conditional->frontals()) {
|
||||
if (involved(key)) {
|
||||
if (involved(involvedKeys, key)) {
|
||||
newConditionals.push_back(conditional);
|
||||
|
||||
// Remove the conditional from the updated Bayes net
|
||||
|
@ -261,4 +291,25 @@ HybridValues HybridSmoother::optimize() const {
|
|||
return HybridValues(continuous, mpe);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void HybridSmoother::relinearize() {
|
||||
allFactors_ = allFactors_.restrict(fixedValues_);
|
||||
HybridGaussianFactorGraph::shared_ptr linearized =
|
||||
allFactors_.linearize(linearizationPoint_);
|
||||
HybridBayesNet::shared_ptr bayesNet = linearized->eliminateSequential();
|
||||
HybridValues delta = bayesNet->optimize();
|
||||
linearizationPoint_ = linearizationPoint_.retract(delta.continuous());
|
||||
reInitialize(*bayesNet);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
Values HybridSmoother::linearizationPoint() const {
|
||||
return linearizationPoint_;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
HybridNonlinearFactorGraph HybridSmoother::allFactors() const {
|
||||
return allFactors_;
|
||||
}
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
#include <gtsam/discrete/DiscreteFactorGraph.h>
|
||||
#include <gtsam/hybrid/HybridBayesNet.h>
|
||||
#include <gtsam/hybrid/HybridGaussianFactorGraph.h>
|
||||
#include <gtsam/hybrid/HybridNonlinearFactorGraph.h>
|
||||
|
||||
#include <optional>
|
||||
|
||||
|
@ -26,8 +27,10 @@ namespace gtsam {
|
|||
|
||||
class GTSAM_EXPORT HybridSmoother {
|
||||
private:
|
||||
HybridBayesNet hybridBayesNet_;
|
||||
HybridNonlinearFactorGraph allFactors_;
|
||||
Values linearizationPoint_;
|
||||
|
||||
HybridBayesNet hybridBayesNet_;
|
||||
/// The threshold above which we make a decision about a mode.
|
||||
std::optional<double> marginalThreshold_;
|
||||
DiscreteValues fixedValues_;
|
||||
|
@ -73,12 +76,12 @@ class GTSAM_EXPORT HybridSmoother {
|
|||
* @param graph The new factors, should be linear only
|
||||
* @param maxNrLeaves The maximum number of leaves in the new discrete factor,
|
||||
* if applicable
|
||||
* @param given_ordering The (optional) ordering for elimination, only
|
||||
* @param givenOrdering The (optional) ordering for elimination, only
|
||||
* continuous variables are allowed
|
||||
*/
|
||||
void update(const HybridGaussianFactorGraph& graph,
|
||||
void update(const HybridNonlinearFactorGraph& graph, const Values& initial,
|
||||
std::optional<size_t> maxNrLeaves = {},
|
||||
const std::optional<Ordering> given_ordering = {});
|
||||
const std::optional<Ordering> givenOrdering = {});
|
||||
|
||||
/**
|
||||
* @brief Get an elimination ordering which eliminates continuous
|
||||
|
@ -122,6 +125,24 @@ class GTSAM_EXPORT HybridSmoother {
|
|||
|
||||
/// Optimize the hybrid Bayes Net, taking into accound fixed values.
|
||||
HybridValues optimize() const;
|
||||
|
||||
/// Relinearize the nonlinear factor graph
|
||||
/// with the latest linearization point.
|
||||
void relinearize();
|
||||
|
||||
/// Return the current linearization point.
|
||||
Values linearizationPoint() const;
|
||||
|
||||
/// Return all the recorded nonlinear factors
|
||||
HybridNonlinearFactorGraph allFactors() const;
|
||||
|
||||
private:
|
||||
/// Helper to compute the ordering if ordering is not given.
|
||||
Ordering maybeComputeOrdering(const HybridGaussianFactorGraph& updatedGraph,
|
||||
const std::optional<Ordering> givenOrdering);
|
||||
|
||||
/// Remove fixed discrete values for discrete keys introduced in `newFactors`.
|
||||
void removeFixedValues(const HybridGaussianFactorGraph& newFactors);
|
||||
};
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -283,10 +283,16 @@ class HybridSmoother {
|
|||
void reInitialize(gtsam::HybridBayesNet& hybridBayesNet);
|
||||
|
||||
void update(
|
||||
const gtsam::HybridGaussianFactorGraph& graph,
|
||||
const gtsam::HybridNonlinearFactorGraph& graph,
|
||||
const gtsam::Values& initial,
|
||||
std::optional<size_t> maxNrLeaves = std::nullopt,
|
||||
const std::optional<gtsam::Ordering> given_ordering = std::nullopt);
|
||||
|
||||
void relinearize();
|
||||
|
||||
gtsam::Values linearizationPoint() const;
|
||||
gtsam::HybridNonlinearFactorGraph allFactors() const;
|
||||
|
||||
gtsam::Ordering getOrdering(const gtsam::HybridGaussianFactorGraph& factors,
|
||||
const gtsam::KeySet& newFactorKeys);
|
||||
|
||||
|
|
|
@ -81,8 +81,14 @@ TEST(HybridNonlinearFactor, Printing) {
|
|||
R"(Hybrid [x1 x2; 1]
|
||||
HybridNonlinearFactor
|
||||
Choice(1)
|
||||
0 Leaf Nonlinear factor on 2 keys
|
||||
1 Leaf Nonlinear factor on 2 keys
|
||||
0 Leaf BetweenFactor(x1,x2)
|
||||
measured: 0
|
||||
noise model: diagonal sigmas [1];
|
||||
|
||||
1 Leaf BetweenFactor(x1,x2)
|
||||
measured: 1
|
||||
noise model: diagonal sigmas [1];
|
||||
|
||||
)";
|
||||
EXPECT(assert_print_equal(expected, hybridFactor));
|
||||
}
|
||||
|
|
|
@ -535,6 +535,9 @@ TEST(HybridNonlinearFactorGraph, Printing) {
|
|||
const auto [hybridBayesNet, remainingFactorGraph] =
|
||||
linearizedFactorGraph.eliminatePartialSequential(ordering);
|
||||
|
||||
// Set precision so we are consistent on all platforms
|
||||
std::cout << std::setprecision(6);
|
||||
|
||||
#ifdef GTSAM_DT_MERGING
|
||||
string expected_hybridFactorGraph = R"(
|
||||
size: 7
|
||||
|
|
|
@ -94,9 +94,7 @@ TEST(HybridSmoother, IncrementalSmoother) {
|
|||
|
||||
initial.insert(X(k), switching.linearizationPoint.at<double>(X(k)));
|
||||
|
||||
HybridGaussianFactorGraph linearized = *graph.linearize(initial);
|
||||
|
||||
smoother.update(linearized, maxNrLeaves);
|
||||
smoother.update(graph, initial, maxNrLeaves);
|
||||
|
||||
// Clear all the factors from the graph
|
||||
graph.resize(0);
|
||||
|
@ -152,9 +150,7 @@ TEST(HybridSmoother, ValidPruningError) {
|
|||
|
||||
initial.insert(X(k), switching.linearizationPoint.at<double>(X(k)));
|
||||
|
||||
HybridGaussianFactorGraph linearized = *graph.linearize(initial);
|
||||
|
||||
smoother.update(linearized, maxNrLeaves);
|
||||
smoother.update(graph, initial, maxNrLeaves);
|
||||
|
||||
// Clear all the factors from the graph
|
||||
graph.resize(0);
|
||||
|
@ -200,9 +196,7 @@ TEST(HybridSmoother, DeadModeRemoval) {
|
|||
|
||||
initial.insert(X(k), switching.linearizationPoint.at<double>(X(k)));
|
||||
|
||||
HybridGaussianFactorGraph linearized = *graph.linearize(initial);
|
||||
|
||||
smoother.update(linearized, maxNrLeaves);
|
||||
smoother.update(graph, initial, maxNrLeaves);
|
||||
|
||||
// Clear all the factors from the graph
|
||||
graph.resize(0);
|
||||
|
|
|
@ -17,6 +17,8 @@ namespace gtsam {
|
|||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/Similarity2.h>
|
||||
#include <gtsam/geometry/Similarity3.h>
|
||||
#include <gtsam/geometry/Rot2.h>
|
||||
#include <gtsam/geometry/Rot3.h>
|
||||
#include <gtsam/geometry/SO3.h>
|
||||
|
@ -74,6 +76,8 @@ class NonlinearFactorGraph {
|
|||
gtsam::Rot3,
|
||||
gtsam::Pose2,
|
||||
gtsam::Pose3,
|
||||
gtsam::Similarity2,
|
||||
gtsam::Similarity3,
|
||||
gtsam::Cal3_S2,
|
||||
gtsam::Cal3f,
|
||||
gtsam::Cal3Bundler,
|
||||
|
@ -544,7 +548,7 @@ class ISAM2 {
|
|||
bool valueExists(gtsam::Key key) const;
|
||||
gtsam::Values calculateEstimate() const;
|
||||
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
||||
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
|
||||
gtsam::Rot3, gtsam::Pose3, gtsam::Similarity2, gtsam::Similarity3, gtsam::Cal3_S2, gtsam::Cal3DS2,
|
||||
gtsam::Cal3f, gtsam::Cal3Bundler,
|
||||
gtsam::EssentialMatrix, gtsam::FundamentalMatrix, gtsam::SimpleFundamentalMatrix,
|
||||
gtsam::PinholeCamera<gtsam::Cal3_S2>,
|
||||
|
@ -609,6 +613,8 @@ template <T = {double,
|
|||
gtsam::Rot3,
|
||||
gtsam::Pose2,
|
||||
gtsam::Pose3,
|
||||
gtsam::Similarity2,
|
||||
gtsam::Similarity3,
|
||||
gtsam::Unit3,
|
||||
gtsam::Cal3_S2,
|
||||
gtsam::Cal3DS2,
|
||||
|
@ -633,7 +639,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor {
|
|||
#include <gtsam/nonlinear/NonlinearEquality.h>
|
||||
template <T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
|
||||
gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2,
|
||||
gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
||||
gtsam::Pose3, gtsam::Similarity2, gtsam::Similarity3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
||||
gtsam::PinholeCamera<gtsam::Cal3_S2>,
|
||||
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
||||
gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
|
||||
|
@ -651,7 +657,7 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
|||
|
||||
template <T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
|
||||
gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2,
|
||||
gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
||||
gtsam::Pose3, gtsam::Similarity2, gtsam::Similarity3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
||||
gtsam::PinholeCamera<gtsam::Cal3_S2>,
|
||||
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
||||
gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
|
||||
|
@ -720,10 +726,29 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
|
|||
gtsam::NonlinearFactorGraph getFactors() const;
|
||||
|
||||
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
||||
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
|
||||
gtsam::Rot3, gtsam::Pose3, gtsam::Similarity2, gtsam::Similarity3, gtsam::Cal3_S2, gtsam::Cal3DS2,
|
||||
gtsam::Vector, gtsam::Matrix}>
|
||||
VALUE calculateEstimate(size_t key) const;
|
||||
};
|
||||
|
||||
#include <gtsam/nonlinear/ExtendedKalmanFilter.h>
|
||||
template <T = {gtsam::Point2,
|
||||
gtsam::Point3,
|
||||
gtsam::Rot2,
|
||||
gtsam::Rot3,
|
||||
gtsam::Pose2,
|
||||
gtsam::Pose3,
|
||||
gtsam::Similarity2,
|
||||
gtsam::Similarity3,
|
||||
gtsam::NavState,
|
||||
gtsam::imuBias::ConstantBias}>
|
||||
virtual class ExtendedKalmanFilter {
|
||||
ExtendedKalmanFilter(gtsam::Key key_initial, const T& x_initial, const gtsam::noiseModel::Gaussian* P_initial);
|
||||
|
||||
T predict(const gtsam::NoiseModelFactor& motionFactor);
|
||||
T update(const gtsam::NoiseModelFactor& measurementFactor);
|
||||
|
||||
gtsam::JacobianFactor::shared_ptr Density() const;
|
||||
};
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -17,6 +17,8 @@ namespace gtsam {
|
|||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/Similarity2.h>
|
||||
#include <gtsam/geometry/Similarity3.h>
|
||||
#include <gtsam/geometry/Rot2.h>
|
||||
#include <gtsam/geometry/Rot3.h>
|
||||
#include <gtsam/geometry/SO3.h>
|
||||
|
@ -80,6 +82,8 @@ class Values {
|
|||
void insert(size_t j, const gtsam::SOn& P);
|
||||
void insert(size_t j, const gtsam::Rot3& rot3);
|
||||
void insert(size_t j, const gtsam::Pose3& pose3);
|
||||
void insert(size_t j, const gtsam::Similarity2& similarity2);
|
||||
void insert(size_t j, const gtsam::Similarity3& similarity3);
|
||||
void insert(size_t j, const gtsam::Unit3& unit3);
|
||||
void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler);
|
||||
void insert(size_t j, const gtsam::Cal3f& cal3f);
|
||||
|
@ -122,6 +126,8 @@ class Values {
|
|||
void update(size_t j, const gtsam::SOn& P);
|
||||
void update(size_t j, const gtsam::Rot3& rot3);
|
||||
void update(size_t j, const gtsam::Pose3& pose3);
|
||||
void update(size_t j, const gtsam::Similarity2& similarity2);
|
||||
void update(size_t j, const gtsam::Similarity3& similarity3);
|
||||
void update(size_t j, const gtsam::Unit3& unit3);
|
||||
void update(size_t j, const gtsam::Cal3Bundler& cal3bundler);
|
||||
void update(size_t j, const gtsam::Cal3f& cal3f);
|
||||
|
@ -161,6 +167,8 @@ class Values {
|
|||
void insert_or_assign(size_t j, const gtsam::SOn& P);
|
||||
void insert_or_assign(size_t j, const gtsam::Rot3& rot3);
|
||||
void insert_or_assign(size_t j, const gtsam::Pose3& pose3);
|
||||
void insert_or_assign(size_t j, const gtsam::Similarity2& similarity2);
|
||||
void insert_or_assign(size_t j, const gtsam::Similarity3& similarity3);
|
||||
void insert_or_assign(size_t j, const gtsam::Unit3& unit3);
|
||||
void insert_or_assign(size_t j, const gtsam::Cal3Bundler& cal3bundler);
|
||||
void insert_or_assign(size_t j, const gtsam::Cal3f& cal3f);
|
||||
|
@ -196,6 +204,8 @@ class Values {
|
|||
gtsam::SOn,
|
||||
gtsam::Rot3,
|
||||
gtsam::Pose3,
|
||||
gtsam::Similarity2,
|
||||
gtsam::Similarity3,
|
||||
gtsam::Unit3,
|
||||
gtsam::Cal3Bundler,
|
||||
gtsam::Cal3f,
|
||||
|
|
|
@ -7,13 +7,14 @@ namespace gtsam {
|
|||
#include <gtsam/geometry/Cal3DS2.h>
|
||||
#include <gtsam/geometry/SO4.h>
|
||||
#include <gtsam/navigation/ImuBias.h>
|
||||
#include <gtsam/geometry/Similarity2.h>
|
||||
#include <gtsam/geometry/Similarity3.h>
|
||||
|
||||
// ######
|
||||
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
template <T = {double, gtsam::Vector, gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::SO3,
|
||||
gtsam::SO4, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Similarity3,
|
||||
gtsam::SO4, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Similarity2, gtsam::Similarity3,
|
||||
gtsam::imuBias::ConstantBias}>
|
||||
virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
||||
BetweenFactor(size_t key1, size_t key2, const T& relativePose,
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,739 @@
|
|||
"""
|
||||
Implementation of Attitude-Bias-Calibration EqF form:
|
||||
"Overcoming Bias: Equivariant Filter Design for Biased Attitude Estimation with Online Calibration"
|
||||
https://ieeexplore.ieee.org/document/9905914
|
||||
|
||||
This module is Alessandro Fornasier's equivariant filter code (https://github.com/aau-cns/ABC-EqF)
|
||||
converted to use GTSAM's libraries.
|
||||
|
||||
Authors: Jennifer Oum & Darshan Rajasekaran
|
||||
"""
|
||||
|
||||
import numpy as np
|
||||
import gtsam
|
||||
from gtsam import Rot3, Unit3
|
||||
from dataclasses import dataclass
|
||||
from typing import List
|
||||
|
||||
coordinate = "EXPONENTIAL"
|
||||
|
||||
|
||||
def checkNorm(x: np.ndarray, tol: float = 1e-3):
|
||||
"""Check norm of a vector being 1 or nan
|
||||
|
||||
:param x: A numpy array
|
||||
:param tol: tollerance, default 1e-3
|
||||
:return: Boolean true if norm is 1 or nan
|
||||
"""
|
||||
return abs(np.linalg.norm(x) - 1) < tol or np.isnan(np.linalg.norm(x))
|
||||
|
||||
|
||||
class State:
|
||||
"""Define the state of the Biased Attitude System
|
||||
----------
|
||||
R is a rotation matrix representing the attitude of the body
|
||||
b is a 3-vector representing the gyroscope bias
|
||||
S is a list of rotation matrix, each representing the calibration of the corresponding direction sensor
|
||||
----------
|
||||
Let's assume we want to use three known direction a, b, and c, where only the sensor that measure b is
|
||||
uncalibrated (we'd like to estimate the calibration states). Therefore, the system's d list looks like
|
||||
d = [b, a, c], and the S list should look like S = [Sb]. The association between d and S is done via indeces.
|
||||
In general S[i] correspond to the calibration state of the sensor that measure the direcion d[i]
|
||||
----------
|
||||
"""
|
||||
|
||||
# Attitude rotation matrix R
|
||||
R: Rot3
|
||||
|
||||
# Gyroscope bias b
|
||||
b: np.ndarray
|
||||
|
||||
# Sensor calibrations S
|
||||
S: List[Rot3]
|
||||
|
||||
def __init__(
|
||||
self,
|
||||
R: Rot3 = Rot3.Identity(),
|
||||
b: np.ndarray = np.zeros(3),
|
||||
S: List[Rot3] = None,
|
||||
):
|
||||
"""Initialize State
|
||||
|
||||
:param R: A SO3 element representing the attitude of the system as a rotation matrix
|
||||
:param b: A numpy array with size 3 representing the gyroscope bias
|
||||
:param S: A list of SO3 elements representing the calibration states for "uncalibrated" sensors,
|
||||
if no sensor require a calibration state, than S will be initialized as an empty list
|
||||
"""
|
||||
|
||||
if not isinstance(R, gtsam.Rot3):
|
||||
|
||||
raise TypeError(
|
||||
"the attitude rotation matrix R has to be of type SO3 but type is",
|
||||
type(R),
|
||||
)
|
||||
self.R = R
|
||||
|
||||
if not (isinstance(b, np.ndarray) and b.size == 3):
|
||||
raise TypeError(
|
||||
"The gyroscope bias has to be probvided as numpy array with size 3"
|
||||
)
|
||||
self.b = b
|
||||
|
||||
if S is None:
|
||||
self.S = []
|
||||
else:
|
||||
if not isinstance(S, list):
|
||||
raise TypeError("Calibration states has to be provided as a list")
|
||||
for calibration in S:
|
||||
if not isinstance(calibration, Rot3):
|
||||
raise TypeError(
|
||||
"Elements of the list of calibration states have to be of type SO3"
|
||||
)
|
||||
self.S = S
|
||||
|
||||
@staticmethod
|
||||
def identity(n: int):
|
||||
"""Return a identity state with n calibration states
|
||||
|
||||
:param n: number of elements in list B associated with calibration states
|
||||
:return: The identity element of the State
|
||||
"""
|
||||
|
||||
return State(Rot3.Identity(), np.zeros(3), [Rot3.Identity() for _ in range(n)])
|
||||
|
||||
|
||||
class Input:
|
||||
"""Define the input space of the Biased Attitude System
|
||||
----------
|
||||
w is a 3-vector representing the angular velocity measured by a gyroscope
|
||||
----------
|
||||
"""
|
||||
|
||||
# Angular velocity
|
||||
w: np.ndarray
|
||||
|
||||
# Noise covariance of angular velocity
|
||||
Sigma: np.ndarray
|
||||
|
||||
def __init__(self, w: np.ndarray, Sigma: np.ndarray):
|
||||
"""Initialize Input
|
||||
|
||||
:param w: A numpy array with size 3 representing the angular velocity measurement from a gyroscope
|
||||
:param Sigma: A numpy array with shape (6, 6) representing the noise covariance of the
|
||||
angular velocity measurement and gyro bias random walk
|
||||
"""
|
||||
|
||||
if not (isinstance(w, np.ndarray) and w.size == 3):
|
||||
raise TypeError(
|
||||
"Angular velocity has to be provided as a numpy array with size 3"
|
||||
)
|
||||
if not (
|
||||
isinstance(Sigma, np.ndarray) and Sigma.shape[0] == Sigma.shape[1] == 6
|
||||
):
|
||||
raise TypeError(
|
||||
"Input measurement noise covariance has to be provided as a numpy array with shape (6. 6)"
|
||||
)
|
||||
if not np.all(np.linalg.eigvals(Sigma) >= 0):
|
||||
raise TypeError("Covariance matrix has to be semi-positive definite")
|
||||
|
||||
self.w = w
|
||||
self.Sigma = Sigma
|
||||
|
||||
@staticmethod
|
||||
def random() -> "Input":
|
||||
"""Return a random angular velocity
|
||||
|
||||
:return: A random angular velocity as a Input element
|
||||
"""
|
||||
|
||||
return Input(np.random.randn(3), np.eye(6))
|
||||
|
||||
def W(self) -> np.ndarray:
|
||||
"""Return the Input as a skew-symmetric matrix
|
||||
|
||||
:return: self.w as a skew-symmetric matrix
|
||||
"""
|
||||
|
||||
return Rot3.Hat(self.w)
|
||||
|
||||
|
||||
class G:
|
||||
"""Symmetry group (SO(3) |x so(3)) x SO(3) x ... x SO(3)
|
||||
----------
|
||||
Each element of the B list is associated with a calibration states in State's S list where the association is done
|
||||
via corresponding index. In general B[i] is the SO(3) element of the symmetry group that correspond to the
|
||||
state's calibration state S[i]. For example, let's assume we want to use three known direction a, b, and c, where
|
||||
only the sensor that measure b is uncalibrated (we'd like to estimate the calibration states). Therefore,
|
||||
the system's d list is defined as d = [b, a, c], and the state's S list is defined as S = [Sb]. The symmetry group
|
||||
B list should be defined as B = [Bb] where Ba is the SO(3) element of the symmetry group that is related to Sb
|
||||
----------
|
||||
"""
|
||||
|
||||
A: Rot3
|
||||
a: np.ndarray
|
||||
B: List[Rot3]
|
||||
|
||||
def __init__(
|
||||
self,
|
||||
A: Rot3 = Rot3.Identity(),
|
||||
a: np.ndarray = np.zeros((3, 3)),
|
||||
B: List[Rot3] = None,
|
||||
):
|
||||
"""Initialize the symmetry group G
|
||||
|
||||
:param A: SO3 element
|
||||
:param a: np.ndarray with shape (3, 3) corresponding to a skew symmetric matrix
|
||||
:param B: list of SO3 elements
|
||||
"""
|
||||
|
||||
if not isinstance(A, Rot3):
|
||||
raise TypeError("A has to be of type SO3")
|
||||
self.A = A
|
||||
if not (isinstance(a, np.ndarray) and a.shape == (3, 3)):
|
||||
raise TypeError("a has to be a numpy array with shape (3, 3)")
|
||||
self.a = a
|
||||
if B is None:
|
||||
self.B = []
|
||||
else:
|
||||
for b in B:
|
||||
if not isinstance(b, Rot3):
|
||||
raise TypeError("Elements of B have to be of type SO3")
|
||||
self.B = B
|
||||
|
||||
def __mul__(self, other: "G") -> "G":
|
||||
"""Define the group operation
|
||||
|
||||
:param other: G
|
||||
:return: A element of the group G given by the "multiplication" of self and other
|
||||
"""
|
||||
|
||||
assert isinstance(other, G)
|
||||
assert len(self.B) == len(other.B)
|
||||
return G(
|
||||
self.A * other.A,
|
||||
self.a + Rot3.Hat(self.A.matrix() @ Rot3.Vee(other.a)),
|
||||
[self.B[i] * other.B[i] for i in range(len(self.B))],
|
||||
)
|
||||
|
||||
@staticmethod
|
||||
def identity(n: int):
|
||||
"""Return the identity of the symmetry group with n elements of SO3 related to sensor calibration states
|
||||
|
||||
:param n: number of elements in list B associated with calibration states
|
||||
:return: The identity of the group G
|
||||
"""
|
||||
|
||||
return G(Rot3.Identity(), np.zeros((3, 3)), [Rot3.Identity() for _ in range(n)])
|
||||
|
||||
@staticmethod
|
||||
def Rot3LeftJacobian(arr: np.ndarray) -> np.ndarray:
|
||||
"""Return the SO(3) Left Jacobian
|
||||
:param arr: A numpy array with size 3
|
||||
:return: The left Jacobian of SO(3)
|
||||
"""
|
||||
if not (isinstance(arr, np.ndarray) and arr.size == 3):
|
||||
raise ValueError("A numpy array with size 3 has to be provided")
|
||||
angle = np.linalg.norm(arr)
|
||||
# Near |phi|==0, use first order Taylor expansion
|
||||
if np.isclose(angle, 0.0):
|
||||
return np.eye(3) + 0.5 * Rot3.Hat(arr)
|
||||
axis = arr / angle
|
||||
s = np.sin(angle)
|
||||
c = np.cos(angle)
|
||||
return (
|
||||
(s / angle) * np.eye(3)
|
||||
+ (1 - (s / angle)) * np.outer(axis, axis)
|
||||
+ ((1 - c) / angle) * Rot3.Hat(axis)
|
||||
)
|
||||
|
||||
def exp(x: np.ndarray) -> "G":
|
||||
"""Return a group element X given by X = exp(x) where x is a numpy array
|
||||
|
||||
:param x: A numpy array
|
||||
:return: A element of the group G given by the exponential of x
|
||||
"""
|
||||
|
||||
if not (isinstance(x, np.ndarray) and x.size >= 6):
|
||||
raise ValueError(
|
||||
"Wrong shape, a numpy array with size 3n has to be provided"
|
||||
)
|
||||
if (x.size % 3) != 0:
|
||||
raise ValueError(
|
||||
"Wrong size, a numpy array with size multiple of 3 has to be provided"
|
||||
)
|
||||
|
||||
n = int((x.size - 6) / 3)
|
||||
A = Rot3.Expmap(x[0:3])
|
||||
a = Rot3.Hat(G.Rot3LeftJacobian(x[0:3]) @ x[3:6])
|
||||
B = [Rot3.Expmap(x[(6 + 3 * i) : (9 + 3 * i)]) for i in range(n)]
|
||||
|
||||
return G(A, a, B)
|
||||
|
||||
def inv(self) -> "G":
|
||||
"""Return the inverse element of the symmetry group
|
||||
|
||||
:return: A element of the group G given by the inverse of self
|
||||
"""
|
||||
|
||||
return G(
|
||||
self.A.inverse(),
|
||||
-Rot3.Hat(self.A.inverse().matrix() @ Rot3.Vee(self.a)),
|
||||
[B.inverse() for B in self.B],
|
||||
)
|
||||
|
||||
|
||||
class Direction:
|
||||
"""Define a direction as a S2 element"""
|
||||
|
||||
# Direction
|
||||
d: Unit3
|
||||
|
||||
def __init__(self, d: np.ndarray):
|
||||
"""Initialize direction
|
||||
|
||||
:param d: A numpy array with size 3 and norm 1 representing the direction
|
||||
"""
|
||||
|
||||
if not (isinstance(d, np.ndarray) and d.size == 3 and checkNorm(d)):
|
||||
raise TypeError("Direction has to be provided as a 3 vector")
|
||||
self.d = Unit3(d)
|
||||
|
||||
|
||||
def blockDiag(A: np.ndarray, B: np.ndarray) -> np.ndarray:
|
||||
"""Create a lock diagonal matrix from blocks A and B
|
||||
|
||||
:param A: numpy array
|
||||
:param B: numpy array
|
||||
:return: numpy array representing a block diagonal matrix composed of blocks A and B
|
||||
"""
|
||||
|
||||
if A is None:
|
||||
return B
|
||||
elif B is None:
|
||||
return A
|
||||
else:
|
||||
return np.block(
|
||||
[
|
||||
[A, np.zeros((A.shape[0], B.shape[1]))],
|
||||
[np.zeros((B.shape[0], A.shape[1])), B],
|
||||
]
|
||||
)
|
||||
|
||||
|
||||
def repBlock(A: np.ndarray, n: int) -> np.ndarray:
|
||||
"""Create a block diagonal matrix repeating the A block n times
|
||||
|
||||
:param A: numpy array representing the block A
|
||||
:param n: number of times to repeat A
|
||||
:return: numpy array representing a block diagonal matrix composed of n-times the blocks A
|
||||
"""
|
||||
|
||||
res = None
|
||||
for _ in range(n):
|
||||
res = blockDiag(res, A)
|
||||
return res
|
||||
|
||||
|
||||
def numericalDifferential(f, x) -> np.ndarray:
|
||||
"""Compute the numerical derivative via central difference"""
|
||||
|
||||
if isinstance(x, float):
|
||||
x = np.reshape([x], (1, 1))
|
||||
h = 1e-6
|
||||
fx = f(x)
|
||||
n = fx.shape[0]
|
||||
m = x.shape[0]
|
||||
Df = np.zeros((n, m))
|
||||
for j in range(m):
|
||||
ej = np.zeros(m)
|
||||
ej[j] = 1.0
|
||||
Df[:, j : j + 1] = (f(x + h * ej) - f(x - h * ej)).reshape(m, 1) / (2 * h)
|
||||
return Df
|
||||
|
||||
|
||||
def lift(xi: State, u: Input) -> np.ndarray:
|
||||
"""The Lift of the system (Theorem 3.8, Equation 7)
|
||||
|
||||
:param xi: A element of the State
|
||||
:param u: A element of the Input space
|
||||
:return: A numpy array representing the Lift
|
||||
"""
|
||||
|
||||
n = len(xi.S)
|
||||
L = np.zeros(6 + 3 * n)
|
||||
L[0:3] = u.w - xi.b
|
||||
L[3:6] = -u.W() @ xi.b
|
||||
for i in range(n):
|
||||
L[(6 + 3 * i) : (9 + 3 * i)] = xi.S[i].inverse().matrix() @ L[0:3]
|
||||
|
||||
return L
|
||||
|
||||
|
||||
def checkNorm(x: np.ndarray, tol: float = 1e-3):
|
||||
"""Check norm of a vector being 1 or nan
|
||||
|
||||
:param x: A numpy array
|
||||
:param tol: tollerance, default 1e-3
|
||||
:return: Boolean true if norm is 1 or nan
|
||||
"""
|
||||
return abs(np.linalg.norm(x) - 1) < tol or np.isnan(np.linalg.norm(x))
|
||||
|
||||
|
||||
def stateAction(X: G, xi: State) -> State:
|
||||
"""Action of the symmetry group on the state space, return phi(X, xi) (Equation 4)
|
||||
|
||||
:param X: A element of the group G
|
||||
:param xi: A element of the State
|
||||
:return: A new element of the state given by the action of phi of G in the State space
|
||||
"""
|
||||
|
||||
if len(xi.S) != len(X.B):
|
||||
raise ValueError(
|
||||
"the number of calibration states and B elements of the symmetry group has to match"
|
||||
)
|
||||
|
||||
return State(
|
||||
xi.R * X.A,
|
||||
X.A.inverse().matrix() @ (xi.b - Rot3.Vee(X.a)),
|
||||
[(X.A.inverse() * xi.S[i] * X.B[i]) for i in range(len(X.B))],
|
||||
)
|
||||
|
||||
|
||||
def velocityAction(X: G, u: Input) -> Input:
|
||||
"""Action of the symmetry group on the input space, return psi(X, u) (Equation 5)
|
||||
|
||||
:param X: A element of the group G
|
||||
:param u: A element of the Input
|
||||
:return: A new element of the Input given by the action of psi of G in the Input space
|
||||
"""
|
||||
|
||||
return Input(X.A.inverse().matrix() @ (u.w - Rot3.Vee(X.a)), u.Sigma)
|
||||
|
||||
|
||||
def outputAction(X: G, y: Direction, idx: int = -1) -> np.ndarray:
|
||||
"""Action of the symmetry group on the output space, return rho(X, y) (Equation 6)
|
||||
|
||||
:param X: A element of the group G
|
||||
:param y: A direction measurement
|
||||
:param idx: indicate the index of the B element in the list, -1 in case no B element exist
|
||||
:return: A numpy array given by the action of rho of G in the Output space
|
||||
"""
|
||||
|
||||
if idx == -1:
|
||||
return X.A.inverse().matrix() @ y.d.unitVector()
|
||||
else:
|
||||
return X.B[idx].inverse().matrix() @ y.d.unitVector()
|
||||
|
||||
|
||||
def local_coords(e: State) -> np.ndarray:
|
||||
"""Local coordinates assuming __xi_0 = identity (Equation 9)
|
||||
|
||||
:param e: A element of the State representing the equivariant error
|
||||
:return: Local coordinates assuming __xi_0 = identity
|
||||
"""
|
||||
|
||||
if coordinate == "EXPONENTIAL":
|
||||
tmp = [Rot3.Logmap(S) for S in e.S]
|
||||
eps = np.concatenate(
|
||||
(
|
||||
Rot3.Logmap(e.R),
|
||||
e.b,
|
||||
np.asarray(tmp).reshape(
|
||||
3 * len(tmp),
|
||||
),
|
||||
)
|
||||
)
|
||||
elif coordinate == "NORMAL":
|
||||
raise ValueError("Normal coordinate representation is not implemented yet")
|
||||
# X = G(e.R, -SO3.Rot3.Hat(e.R @ e.b), e.S)
|
||||
# eps = G.log(X)
|
||||
else:
|
||||
raise ValueError("Invalid coordinate representation")
|
||||
|
||||
return eps
|
||||
|
||||
|
||||
def local_coords_inv(eps: np.ndarray) -> "State":
|
||||
"""Local coordinates inverse assuming __xi_0 = identity
|
||||
|
||||
:param eps: A numpy array representing the equivariant error in local coordinates
|
||||
:return: Local coordinates inverse assuming __xi_0 = identity
|
||||
"""
|
||||
|
||||
X = G.exp(eps) # G
|
||||
if coordinate == "EXPONENTIAL":
|
||||
e = State(X.A, eps[3:6, :], X.B) # State
|
||||
elif coordinate == "NORMAL":
|
||||
raise ValueError("Normal coordinate representation is not implemented yet")
|
||||
# stateAction(X, State(SO3.identity(), np.zeros(3), [SO3.identity() for _ in range(len(X.B))]))
|
||||
else:
|
||||
raise ValueError("Invalid coordinate representation")
|
||||
|
||||
return e
|
||||
|
||||
|
||||
def stateActionDiff(xi: State) -> np.ndarray:
|
||||
"""Differential of the phi action phi(xi, E) at E = Id in local coordinates (can be found within equation 23)
|
||||
|
||||
:param xi: A element of the State
|
||||
:return: (Dtheta) * (Dphi(xi, E) at E = Id)
|
||||
"""
|
||||
coordsAction = lambda U: local_coords(stateAction(G.exp(U), xi))
|
||||
differential = numericalDifferential(coordsAction, np.zeros(6 + 3 * len(xi.S)))
|
||||
return differential
|
||||
|
||||
|
||||
class Measurement:
|
||||
"""Define a measurement
|
||||
----------
|
||||
cal_idx is a index corresponding to the cal_idx-th calibration related to the measurement. Let's consider the case
|
||||
of 2 uncalibrated sensor with two associated calibration state in State.S = [S0, S1], and a single calibrated sensor.
|
||||
cal_idx = 0 indicates a measurement coming from the sensor that has calibration S0, cal_idx = 1 indicates a
|
||||
measurement coming from the sensor that has calibration S1. cal_idx = -1 indicates that the measurement is coming
|
||||
from a calibrated sensor
|
||||
----------
|
||||
"""
|
||||
|
||||
# measurement
|
||||
y: Direction
|
||||
|
||||
# Known direction in global frame
|
||||
d: Direction
|
||||
|
||||
# Covariance matrix of the measurement
|
||||
Sigma: np.ndarray
|
||||
|
||||
# Calibration index
|
||||
cal_idx: int = -1
|
||||
|
||||
def __init__(self, y: np.ndarray, d: np.ndarray, Sigma: np.ndarray, i: int = -1):
|
||||
"""Initialize measurement
|
||||
|
||||
:param y: A numpy array with size 3 and norm 1 representing the direction measurement in the sensor frame
|
||||
:param d: A numpy array with size 3 and norm 1 representing the direction in the global frame
|
||||
:param Sigma: A numpy array with shape (3, 3) representing the noise covariance of the direction measurement
|
||||
:param i: index of the corresponding calibration state
|
||||
"""
|
||||
|
||||
if not (isinstance(y, np.ndarray) and y.size == 3 and checkNorm(y)):
|
||||
raise TypeError("Measurement has to be provided as a (3, 1) vector")
|
||||
if not (isinstance(d, np.ndarray) and d.size == 3 and checkNorm(d)):
|
||||
raise TypeError("Direction has to be provided as a (3, 1) vector")
|
||||
if not (
|
||||
isinstance(Sigma, np.ndarray) and Sigma.shape[0] == Sigma.shape[1] == 3
|
||||
):
|
||||
raise TypeError(
|
||||
"Direction measurement noise covariance has to be provided as a numpy array with shape (3. 3)"
|
||||
)
|
||||
if not np.all(np.linalg.eigvals(Sigma) >= 0):
|
||||
raise TypeError("Covariance matrix has to be semi-positive definite")
|
||||
if not (isinstance(i, int) or i == -1 or i > 0):
|
||||
raise TypeError("calibration index is a positive integer or -1")
|
||||
|
||||
self.y = Direction(y)
|
||||
self.d = Direction(d)
|
||||
self.Sigma = Sigma
|
||||
self.cal_idx = i
|
||||
|
||||
|
||||
@dataclass
|
||||
class Data:
|
||||
"""Define ground-truth, input and output data"""
|
||||
|
||||
# Ground-truth state
|
||||
xi: State
|
||||
n_cal: int
|
||||
|
||||
# Input measurements
|
||||
u: Input
|
||||
|
||||
# Output measurements as a list of Measurement
|
||||
y: list
|
||||
n_meas: int
|
||||
|
||||
# Time
|
||||
t: float
|
||||
dt: float
|
||||
|
||||
|
||||
class EqF:
|
||||
def __init__(self, Sigma: np.ndarray, n: int, m: int):
|
||||
"""Initialize EqF
|
||||
|
||||
:param Sigma: Initial covariance
|
||||
:param n: Number of calibration states
|
||||
:param m: Total number of available sensor
|
||||
"""
|
||||
|
||||
self.__dof = 6 + 3 * n
|
||||
self.__n_cal = n
|
||||
self.__n_sensor = m
|
||||
|
||||
if not (
|
||||
isinstance(Sigma, np.ndarray)
|
||||
and (Sigma.shape[0] == Sigma.shape[1] == self.__dof)
|
||||
):
|
||||
raise TypeError(
|
||||
f"Initial covariance has to be provided as a numpy array with shape ({self.__dof}, {self.__dof})"
|
||||
)
|
||||
if not np.all(np.linalg.eigvals(Sigma) >= 0):
|
||||
raise TypeError("Covariance matrix has to be semi-positive definite")
|
||||
if not (isinstance(n, int) and n >= 0):
|
||||
raise TypeError("Number of calibration state has to be unsigned")
|
||||
if not (isinstance(m, int) and m > 1):
|
||||
raise TypeError("Number of direction sensor has to be grater-equal than 2")
|
||||
|
||||
self.__X_hat = G.identity(n)
|
||||
self.__Sigma = Sigma
|
||||
self.__xi_0 = State.identity(n)
|
||||
self.__Dphi0 = stateActionDiff(self.__xi_0) # Within equation 23
|
||||
self.__InnovationLift = np.linalg.pinv(self.__Dphi0) # Within equation 23
|
||||
|
||||
def stateEstimate(self) -> State:
|
||||
"""Return estimated state
|
||||
|
||||
:return: Estimated state
|
||||
"""
|
||||
return stateAction(self.__X_hat, self.__xi_0)
|
||||
|
||||
def propagation(self, u: Input, dt: float):
|
||||
"""Propagate the filter state
|
||||
|
||||
:param u: Angular velocity measurement from IMU
|
||||
:param dt: delta time between timestamp of last propagation/update and timestamp of angular velocity measurement
|
||||
"""
|
||||
|
||||
if not isinstance(u, Input):
|
||||
raise TypeError(
|
||||
"angular velocity measurement has to be provided as a Input element"
|
||||
)
|
||||
|
||||
L = lift(self.stateEstimate(), u) # Equation 7
|
||||
|
||||
Phi_DT = self.__stateTransitionMatrix(u, dt) # Equation 17
|
||||
# Equivalent
|
||||
# A0t = self.__stateMatrixA(u) # Equation 14a
|
||||
# Phi_DT = expm(A0t * dt)
|
||||
|
||||
Bt = self.__inputMatrixBt() # Equation 27
|
||||
M_DT = (
|
||||
Bt @ blockDiag(u.Sigma, repBlock(1e-9 * np.eye(3), self.__n_cal)) @ Bt.T
|
||||
) * dt
|
||||
|
||||
self.__X_hat = self.__X_hat * G.exp(L * dt) # Equation 18
|
||||
self.__Sigma = Phi_DT @ self.__Sigma @ Phi_DT.T + M_DT # Equation 19
|
||||
|
||||
def update(self, y: Measurement):
|
||||
"""Update the filter state
|
||||
|
||||
:param y: A measurement
|
||||
"""
|
||||
|
||||
# Cross-check calibration
|
||||
assert y.cal_idx <= self.__n_cal
|
||||
|
||||
Ct = self.__measurementMatrixC(y.d, y.cal_idx) # Equation 14b
|
||||
delta = Rot3.Hat(y.d.d.unitVector()) @ outputAction(
|
||||
self.__X_hat.inv(), y.y, y.cal_idx
|
||||
)
|
||||
Dt = self.__outputMatrixDt(y.cal_idx)
|
||||
S = Ct @ self.__Sigma @ Ct.T + Dt @ y.Sigma @ Dt.T # Equation 21
|
||||
K = self.__Sigma @ Ct.T @ np.linalg.inv(S) # Equation 22
|
||||
Delta = self.__InnovationLift @ K @ delta # Equation 23
|
||||
self.__X_hat = G.exp(Delta) * self.__X_hat # Equation 24
|
||||
self.__Sigma = (np.eye(self.__dof) - K @ Ct) @ self.__Sigma # Equation 25
|
||||
|
||||
def __stateMatrixA(self, u: Input) -> np.ndarray:
|
||||
"""Return the state matrix A0t (Equation 14a)
|
||||
|
||||
:param u: Input
|
||||
:return: numpy array representing the state matrix A0t
|
||||
"""
|
||||
|
||||
W0 = velocityAction(self.__X_hat.inv(), u).W()
|
||||
A1 = np.zeros((6, 6))
|
||||
|
||||
if coordinate == "EXPONENTIAL":
|
||||
A1[0:3, 3:6] = -np.eye(3)
|
||||
A1[3:6, 3:6] = W0
|
||||
A2 = repBlock(W0, self.__n_cal)
|
||||
elif coordinate == "NORMAL":
|
||||
raise ValueError("Normal coordinate representation is not implemented yet")
|
||||
else:
|
||||
raise ValueError("Invalid coordinate representation")
|
||||
|
||||
return blockDiag(A1, A2)
|
||||
|
||||
def __stateTransitionMatrix(self, u: Input, dt: float) -> np.ndarray:
|
||||
"""Return the state transition matrix Phi (Equation 17)
|
||||
|
||||
:param u: Input
|
||||
:param dt: Delta time
|
||||
:return: numpy array representing the state transition matrix Phi
|
||||
"""
|
||||
|
||||
W0 = velocityAction(self.__X_hat.inv(), u).W()
|
||||
Phi1 = np.zeros((6, 6))
|
||||
Phi12 = -dt * (np.eye(3) + (dt / 2) * W0 + ((dt**2) / 6) * W0 * W0)
|
||||
Phi22 = np.eye(3) + dt * W0 + ((dt**2) / 2) * W0 * W0
|
||||
|
||||
if coordinate == "EXPONENTIAL":
|
||||
Phi1[0:3, 0:3] = np.eye(3)
|
||||
Phi1[0:3, 3:6] = Phi12
|
||||
Phi1[3:6, 3:6] = Phi22
|
||||
Phi2 = repBlock(Phi22, self.__n_cal)
|
||||
elif coordinate == "NORMAL":
|
||||
raise ValueError("Normal coordinate representation is not implemented yet")
|
||||
else:
|
||||
raise ValueError("Invalid coordinate representation")
|
||||
|
||||
return blockDiag(Phi1, Phi2)
|
||||
|
||||
def __inputMatrixBt(self) -> np.ndarray:
|
||||
"""Return the Input matrix Bt
|
||||
|
||||
:return: numpy array representing the state matrix Bt
|
||||
"""
|
||||
|
||||
if coordinate == "EXPONENTIAL":
|
||||
B1 = blockDiag(self.__X_hat.A.matrix(), self.__X_hat.A.matrix())
|
||||
B2 = None
|
||||
for B in self.__X_hat.B:
|
||||
B2 = blockDiag(B2, B.matrix())
|
||||
elif coordinate == "NORMAL":
|
||||
raise ValueError("Normal coordinate representation is not implemented yet")
|
||||
else:
|
||||
raise ValueError("Invalid coordinate representation")
|
||||
|
||||
return blockDiag(B1, B2)
|
||||
|
||||
def __measurementMatrixC(self, d: Direction, idx: int) -> np.ndarray:
|
||||
"""Return the measurement matrix C0 (Equation 14b)
|
||||
|
||||
:param d: Known direction
|
||||
:param idx: index of the related calibration state
|
||||
:return: numpy array representing the measurement matrix C0
|
||||
"""
|
||||
|
||||
Cc = np.zeros((3, 3 * self.__n_cal))
|
||||
|
||||
# If the measurement is related to a sensor that has a calibration state
|
||||
if idx >= 0:
|
||||
Cc[(3 * idx) : (3 + 3 * idx), :] = Rot3.Hat(d.d.unitVector())
|
||||
|
||||
return Rot3.Hat(d.d.unitVector()) @ np.hstack(
|
||||
(Rot3.Hat(d.d.unitVector()), np.zeros((3, 3)), Cc)
|
||||
)
|
||||
|
||||
def __outputMatrixDt(self, idx: int) -> np.ndarray:
|
||||
"""Return the measurement output matrix Dt
|
||||
|
||||
:param idx: index of the related calibration state
|
||||
:return: numpy array representing the output matrix Dt
|
||||
"""
|
||||
|
||||
# If the measurement is related to a sensor that has a calibration state
|
||||
if idx >= 0:
|
||||
return self.__X_hat.B[idx].matrix()
|
||||
else:
|
||||
return self.__X_hat.A.matrix()
|
|
@ -194,7 +194,6 @@ class Experiment:
|
|||
|
||||
self.smoother_ = HybridSmoother(marginal_threshold)
|
||||
self.new_factors_ = HybridNonlinearFactorGraph()
|
||||
self.all_factors_ = HybridNonlinearFactorGraph()
|
||||
self.initial_ = Values()
|
||||
|
||||
self.plot_hypotheses = plot_hypotheses
|
||||
|
@ -231,24 +230,18 @@ class Experiment:
|
|||
"""Perform smoother update and optimize the graph."""
|
||||
print(f"Smoother update: {self.new_factors_.size()}")
|
||||
before_update = time.time()
|
||||
linearized = self.new_factors_.linearize(self.initial_)
|
||||
self.smoother_.update(linearized, max_num_hypotheses)
|
||||
self.all_factors_.push_back(self.new_factors_)
|
||||
self.smoother_.update(self.new_factors_, self.initial_,
|
||||
max_num_hypotheses)
|
||||
self.new_factors_.resize(0)
|
||||
after_update = time.time()
|
||||
return after_update - before_update
|
||||
|
||||
def reinitialize(self) -> float:
|
||||
"""Re-linearize, solve ALL, and re-initialize smoother."""
|
||||
print(f"================= Re-Initialize: {self.all_factors_.size()}")
|
||||
print(f"================= Re-Initialize: {self.smoother_.allFactors().size()}")
|
||||
before_update = time.time()
|
||||
self.all_factors_ = self.all_factors_.restrict(
|
||||
self.smoother_.fixedValues())
|
||||
linearized = self.all_factors_.linearize(self.initial_)
|
||||
bayesNet = linearized.eliminateSequential()
|
||||
delta: HybridValues = bayesNet.optimize()
|
||||
self.initial_ = self.initial_.retract(delta.continuous())
|
||||
self.smoother_.reInitialize(bayesNet)
|
||||
self.smoother_.relinearize()
|
||||
self.initial_ = self.smoother_.linearizationPoint()
|
||||
after_update = time.time()
|
||||
print(f"Took {after_update - before_update} seconds.")
|
||||
return after_update - before_update
|
||||
|
|
|
@ -0,0 +1,122 @@
|
|||
{
|
||||
"cells": [
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": 1,
|
||||
"metadata": {},
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\"\"\"\n",
|
||||
"Extended Kalman filter on a moving 2D point, but done using factor graphs.\n",
|
||||
"This example uses the ExtendedKalmanFilter class to perform filtering\n",
|
||||
"on a linear system, demonstrating the same operations as in elaboratePoint2KalmanFilter.\n",
|
||||
"\"\"\"\n",
|
||||
"\n",
|
||||
"import gtsam\n",
|
||||
"import numpy as np"
|
||||
]
|
||||
},
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": 2,
|
||||
"metadata": {},
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"# Create the Kalman Filter initialization point\n",
|
||||
"X0 = gtsam.Point2(0.0, 0.0)\n",
|
||||
"P0 = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1]))\n",
|
||||
"\n",
|
||||
"# Create Key for initial pose\n",
|
||||
"x0 = gtsam.symbol('x', 0)\n",
|
||||
"\n",
|
||||
"# Create an ExtendedKalmanFilter object\n",
|
||||
"ekf = gtsam.ExtendedKalmanFilterPoint2(x0, X0, P0)\n",
|
||||
"\n",
|
||||
"# For this example, we use a constant-position model where\n",
|
||||
"# controls drive the point to the right at 1 m/s\n",
|
||||
"# F = [1 0; 0 1], B = [1 0; 0 1], and u = [1; 0]\n",
|
||||
"# Process noise Q = [0.1 0; 0 0.1]\n",
|
||||
"Q = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1]), True)\n",
|
||||
"\n",
|
||||
"# Measurement noise, assuming a GPS-like sensor\n",
|
||||
"R = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.25, 0.25]), True)\n",
|
||||
"\n",
|
||||
"# Motion model - move right by 1.0 units\n",
|
||||
"dX = gtsam.Point2(1.0, 0.0)\n",
|
||||
"\n",
|
||||
"last_symbol = x0"
|
||||
]
|
||||
},
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": 3,
|
||||
"metadata": {},
|
||||
"outputs": [
|
||||
{
|
||||
"name": "stdout",
|
||||
"output_type": "stream",
|
||||
"text": [
|
||||
"X1 Predict: [1. 0.]\n",
|
||||
"X1 Update: [1. 0.]\n",
|
||||
"X2 Predict: [2. 0.]\n",
|
||||
"X2 Update: [2. 0.]\n",
|
||||
"X3 Predict: [3. 0.]\n",
|
||||
"X3 Update: [3. 0.]\n",
|
||||
"\n",
|
||||
"Easy Final Covariance (after update):\n",
|
||||
" [[0.0193 0. ]\n",
|
||||
" [0. 0.0193]]\n"
|
||||
]
|
||||
}
|
||||
],
|
||||
"source": [
|
||||
"for i in range(1, 4):\n",
|
||||
" # Create symbol for new state\n",
|
||||
" xi = gtsam.symbol('x', i)\n",
|
||||
" \n",
|
||||
" # Prediction step: P(x_i) ~ P(x_i|x_{i-1}) P(x_{i-1})\n",
|
||||
" # In Kalman Filter notation: x_{t+1|t} and P_{t+1|t}\n",
|
||||
" motion = gtsam.BetweenFactorPoint2(last_symbol, xi, dX, Q)\n",
|
||||
" Xi_predict = ekf.predict(motion)\n",
|
||||
" print(f\"X{i} Predict:\", Xi_predict)\n",
|
||||
" \n",
|
||||
" # Update step: P(x_i|z_i) ~ P(z_i|x_i)*P(x_i)\n",
|
||||
" # Assuming a measurement model h(x_{t}) = H*x_{t} + v\n",
|
||||
" # where H is the observation model/matrix and v is noise with covariance R\n",
|
||||
" measurement = gtsam.Point2(float(i), 0.0)\n",
|
||||
" meas_factor = gtsam.PriorFactorPoint2(xi, measurement, R)\n",
|
||||
" Xi_update = ekf.update(meas_factor)\n",
|
||||
" print(f\"X{i} Update:\", Xi_update)\n",
|
||||
" \n",
|
||||
" # Move to next state\n",
|
||||
" last_symbol = xi\n",
|
||||
"\n",
|
||||
"A = ekf.Density().getA()\n",
|
||||
"information_matrix = A.transpose() @ A\n",
|
||||
"covariance_matrix = np.linalg.inv(information_matrix)\n",
|
||||
"print (\"\\nEasy Final Covariance (after update):\\n\", covariance_matrix)"
|
||||
]
|
||||
}
|
||||
],
|
||||
"metadata": {
|
||||
"kernelspec": {
|
||||
"display_name": "Python 3",
|
||||
"language": "python",
|
||||
"name": "python3"
|
||||
},
|
||||
"language_info": {
|
||||
"codemirror_mode": {
|
||||
"name": "ipython",
|
||||
"version": 3
|
||||
},
|
||||
"file_extension": ".py",
|
||||
"mimetype": "text/x-python",
|
||||
"name": "python",
|
||||
"nbconvert_exporter": "python",
|
||||
"pygments_lexer": "ipython3",
|
||||
"version": "3.10.12"
|
||||
}
|
||||
},
|
||||
"nbformat": 4,
|
||||
"nbformat_minor": 2
|
||||
}
|
|
@ -0,0 +1,191 @@
|
|||
{
|
||||
"cells": [
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": 1,
|
||||
"metadata": {},
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\"\"\"\n",
|
||||
"Simple linear Kalman filter on a moving 2D point using factor graphs in GTSAM.\n",
|
||||
"This example manually creates all of the needed data structures to show how\n",
|
||||
"the Kalman filter works under the hood using factor graphs, but uses a loop\n",
|
||||
"to handle the repetitive prediction and update steps.\n",
|
||||
"\n",
|
||||
"Based on the C++ example by Frank Dellaert and Stephen Williams\n",
|
||||
"\"\"\"\n",
|
||||
"\n",
|
||||
"import gtsam\n",
|
||||
"import numpy as np\n",
|
||||
"from gtsam import Point2, noiseModel\n",
|
||||
"from gtsam.symbol_shorthand import X"
|
||||
]
|
||||
},
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": 2,
|
||||
"metadata": {},
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"# [code below basically does SRIF with Cholesky]\n",
|
||||
"\n",
|
||||
"# Setup containers for linearization points\n",
|
||||
"linearization_points = gtsam.Values()\n",
|
||||
"\n",
|
||||
"# Initialize state x0 at origin\n",
|
||||
"x_initial = Point2(0, 0)\n",
|
||||
"p_initial = noiseModel.Isotropic.Sigma(2, 0.1)\n",
|
||||
"\n",
|
||||
"# Add x0 to linearization points\n",
|
||||
"linearization_points.insert(X(0), x_initial)\n",
|
||||
"\n",
|
||||
"# Initial factor graph with prior on X(0)\n",
|
||||
"gfg = gtsam.GaussianFactorGraph()\n",
|
||||
"ordering = gtsam.Ordering()\n",
|
||||
"ordering.push_back(X(0))\n",
|
||||
"gfg.add(X(0), p_initial.R(), np.zeros(2), noiseModel.Unit.Create(2))\n",
|
||||
"\n",
|
||||
"# Common parameters for all steps\n",
|
||||
"motion_delta = Point2(1, 0) # Always move 1 unit to the right\n",
|
||||
"process_noise = noiseModel.Isotropic.Sigma(2, 0.1)\n",
|
||||
"measurement_noise = noiseModel.Isotropic.Sigma(2, 0.25)"
|
||||
]
|
||||
},
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": 3,
|
||||
"metadata": {},
|
||||
"outputs": [
|
||||
{
|
||||
"name": "stdout",
|
||||
"output_type": "stream",
|
||||
"text": [
|
||||
"X1 Predict: [1. 0.]\n",
|
||||
"X1 Update: [1. 0.]\n",
|
||||
"X2 Predict: [2. 0.]\n",
|
||||
"X2 Update: [2. 0.]\n",
|
||||
"X3 Predict: [3. 0.]\n",
|
||||
"X3 Update: [3. 0.]\n",
|
||||
"\n",
|
||||
"Elaborate Final Covariance (after update):\n",
|
||||
" [[0.0193 0. ]\n",
|
||||
" [0. 0.0193]]\n"
|
||||
]
|
||||
}
|
||||
],
|
||||
"source": [
|
||||
"# Current state and conditional\n",
|
||||
"current_x = X(0)\n",
|
||||
"current_conditional = None\n",
|
||||
"current_result = None\n",
|
||||
"\n",
|
||||
"# Run three predict-update cycles\n",
|
||||
"for step in range(1, 4):\n",
|
||||
" # =====================================================================\n",
|
||||
" # Prediction step\n",
|
||||
" # =====================================================================\n",
|
||||
" next_x = X(step)\n",
|
||||
" \n",
|
||||
" # Create new graph with prior from previous step if not the first step\n",
|
||||
" if step > 1:\n",
|
||||
" gfg = gtsam.GaussianFactorGraph()\n",
|
||||
" gfg.add(\n",
|
||||
" current_x,\n",
|
||||
" current_conditional.R(),\n",
|
||||
" current_conditional.d() - current_conditional.R() @ current_result.at(current_x),\n",
|
||||
" current_conditional.get_model()\n",
|
||||
" )\n",
|
||||
" \n",
|
||||
" # Add next state to ordering and create motion model\n",
|
||||
" ordering = gtsam.Ordering()\n",
|
||||
" ordering.push_back(current_x)\n",
|
||||
" ordering.push_back(next_x)\n",
|
||||
" \n",
|
||||
" # Create motion factor and add to graph\n",
|
||||
" motion_factor = gtsam.BetweenFactorPoint2(current_x, next_x, motion_delta, process_noise)\n",
|
||||
" \n",
|
||||
" # Add next state to linearization points if this is the first step\n",
|
||||
" if step == 1:\n",
|
||||
" linearization_points.insert(next_x, x_initial)\n",
|
||||
" else:\n",
|
||||
" linearization_points.insert(next_x, \n",
|
||||
" linearization_points.atPoint2(current_x))\n",
|
||||
" \n",
|
||||
" # Add linearized factor to graph\n",
|
||||
" gfg.push_back(motion_factor.linearize(linearization_points))\n",
|
||||
" \n",
|
||||
" # Solve for prediction\n",
|
||||
" prediction_bayes_net = gfg.eliminateSequential(ordering)\n",
|
||||
" next_conditional = prediction_bayes_net.back()\n",
|
||||
" prediction_result = prediction_bayes_net.optimize()\n",
|
||||
" \n",
|
||||
" # Extract and store predicted state\n",
|
||||
" next_predict = linearization_points.atPoint2(next_x) + Point2(prediction_result.at(next_x))\n",
|
||||
" print(f\"X{step} Predict:\", next_predict)\n",
|
||||
" linearization_points.update(next_x, next_predict)\n",
|
||||
" \n",
|
||||
" # =====================================================================\n",
|
||||
" # Update step\n",
|
||||
" # =====================================================================\n",
|
||||
" # Create new graph with prior from prediction\n",
|
||||
" gfg = gtsam.GaussianFactorGraph()\n",
|
||||
" gfg.add(\n",
|
||||
" next_x,\n",
|
||||
" next_conditional.R(),\n",
|
||||
" next_conditional.d() - next_conditional.R() @ prediction_result.at(next_x),\n",
|
||||
" next_conditional.get_model()\n",
|
||||
" )\n",
|
||||
" \n",
|
||||
" # Create ordering for update\n",
|
||||
" ordering = gtsam.Ordering()\n",
|
||||
" ordering.push_back(next_x)\n",
|
||||
" \n",
|
||||
" # Create measurement at correct position\n",
|
||||
" measurement = Point2(float(step), 0.0)\n",
|
||||
" meas_factor = gtsam.PriorFactorPoint2(next_x, measurement, measurement_noise)\n",
|
||||
" \n",
|
||||
" # Add measurement factor to graph\n",
|
||||
" gfg.push_back(meas_factor.linearize(linearization_points))\n",
|
||||
" \n",
|
||||
" # Solve for update\n",
|
||||
" update_bayes_net = gfg.eliminateSequential(ordering)\n",
|
||||
" current_conditional = update_bayes_net.back()\n",
|
||||
" current_result = update_bayes_net.optimize()\n",
|
||||
" \n",
|
||||
" # Extract and store updated state\n",
|
||||
" next_update = linearization_points.atPoint2(next_x) + Point2(current_result.at(next_x))\n",
|
||||
" print(f\"X{step} Update:\", next_update)\n",
|
||||
" linearization_points.update(next_x, next_update)\n",
|
||||
" \n",
|
||||
" # Move to next state\n",
|
||||
" current_x = next_x\n",
|
||||
"\n",
|
||||
"final_R = current_conditional.R()\n",
|
||||
"final_information = final_R.transpose() @ final_R\n",
|
||||
"final_covariance = np.linalg.inv(final_information)\n",
|
||||
"print(\"\\nElaborate Final Covariance (after update):\\n\", final_covariance)"
|
||||
]
|
||||
}
|
||||
],
|
||||
"metadata": {
|
||||
"kernelspec": {
|
||||
"display_name": "Python 3",
|
||||
"language": "python",
|
||||
"name": "python3"
|
||||
},
|
||||
"language_info": {
|
||||
"codemirror_mode": {
|
||||
"name": "ipython",
|
||||
"version": 3
|
||||
},
|
||||
"file_extension": ".py",
|
||||
"mimetype": "text/x-python",
|
||||
"name": "python",
|
||||
"nbconvert_exporter": "python",
|
||||
"pygments_lexer": "ipython3",
|
||||
"version": "3.10.12"
|
||||
}
|
||||
},
|
||||
"nbformat": 4,
|
||||
"nbformat_minor": 2
|
||||
}
|
|
@ -0,0 +1,279 @@
|
|||
"""
|
||||
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
|
||||
Atlanta, Georgia 30332-0415
|
||||
All Rights Reserved
|
||||
|
||||
See LICENSE for the license information
|
||||
|
||||
Unit tests for Chebyshev2 Basis using the GTSAM Python wrapper.
|
||||
Converted from the C++ tests.
|
||||
"""
|
||||
|
||||
import unittest
|
||||
|
||||
import numpy as np
|
||||
from gtsam.utils.test_case import GtsamTestCase
|
||||
|
||||
import gtsam
|
||||
from gtsam import Chebyshev2
|
||||
|
||||
|
||||
# Define test functions f and fprime:
|
||||
def f(x):
|
||||
return 3.0 * (x**3) - 2.0 * (x**2) + 5.0 * x - 11.0
|
||||
|
||||
|
||||
def fprime(x):
|
||||
return 9.0 * (x**2) - 4.0 * x + 5.0
|
||||
|
||||
|
||||
def Chebyshev2_vector(f, N, a=-1.0, b=1.0):
|
||||
points = Chebyshev2.Points(N, a, b)
|
||||
return np.array([f(x) for x in points])
|
||||
|
||||
|
||||
class TestChebyshev2(GtsamTestCase):
|
||||
|
||||
def test_Point(self):
|
||||
"""Test that Chebyshev points are correctly calculated and symmetrical."""
|
||||
N = 5
|
||||
points = Chebyshev2.Points(N)
|
||||
expected = np.array([-1.0, -np.sqrt(2.0) / 2.0, 0.0, np.sqrt(2.0) / 2.0, 1.0])
|
||||
tol = 1e-15
|
||||
np.testing.assert_allclose(points, expected, rtol=0, atol=tol)
|
||||
|
||||
# Check symmetry:
|
||||
p0 = Chebyshev2.Point(N, 0)
|
||||
p4 = Chebyshev2.Point(N, 4)
|
||||
p1 = Chebyshev2.Point(N, 1)
|
||||
p3 = Chebyshev2.Point(N, 3)
|
||||
self.assertAlmostEqual(p0, -p4, delta=tol)
|
||||
self.assertAlmostEqual(p1, -p3, delta=tol)
|
||||
|
||||
def test_PointInInterval(self):
|
||||
"""Test that Chebyshev points map correctly to arbitrary intervals [a,b]."""
|
||||
N = 5
|
||||
points = Chebyshev2.Points(N, 0, 20)
|
||||
expected = (
|
||||
np.array(
|
||||
[0.0, 1.0 - np.sqrt(2.0) / 2.0, 1.0, 1.0 + np.sqrt(2.0) / 2.0, 2.0]
|
||||
)
|
||||
* 10.0
|
||||
)
|
||||
tol = 1e-15
|
||||
np.testing.assert_allclose(points, expected, rtol=0, atol=tol)
|
||||
# Also check all-at-once:
|
||||
actual = Chebyshev2.Points(N, 0, 20)
|
||||
np.testing.assert_allclose(actual, expected, rtol=0, atol=tol)
|
||||
|
||||
def test_Decomposition(self):
|
||||
"""Test fitting a linear function with Chebyshev basis."""
|
||||
# Create a sequence: dictionary mapping x -> y.
|
||||
sequence = {}
|
||||
for i in range(16):
|
||||
x_val = (1.0 / 16) * i - 0.99
|
||||
sequence[x_val] = x_val
|
||||
fit = gtsam.FitBasisChebyshev2(sequence, None, 3)
|
||||
params = fit.parameters()
|
||||
expected = np.array([-1.0, 0.0, 1.0])
|
||||
np.testing.assert_allclose(params, expected, rtol=0, atol=1e-4)
|
||||
|
||||
def test_DifferentiationMatrix3(self):
|
||||
"""Test the 3×3 differentiation matrix against known values."""
|
||||
N = 3
|
||||
# Expected differentiation matrix (from chebfun) then multiplied by -1.
|
||||
expected = np.array([[1.5, -2.0, 0.5], [0.5, -0.0, -0.5], [-0.5, 2.0, -1.5]])
|
||||
expected = -expected
|
||||
actual = Chebyshev2.DifferentiationMatrix(N)
|
||||
np.testing.assert_allclose(actual, expected, rtol=0, atol=1e-4)
|
||||
|
||||
def test_DerivativeMatrix6(self):
|
||||
"""Test the 6×6 differentiation matrix against known values."""
|
||||
N = 6
|
||||
expected = np.array(
|
||||
[
|
||||
[8.5000, -10.4721, 2.8944, -1.5279, 1.1056, -0.5000],
|
||||
[2.6180, -1.1708, -2.0000, 0.8944, -0.6180, 0.2764],
|
||||
[-0.7236, 2.0000, -0.1708, -1.6180, 0.8944, -0.3820],
|
||||
[0.3820, -0.8944, 1.6180, 0.1708, -2.0000, 0.7236],
|
||||
[-0.2764, 0.6180, -0.8944, 2.0000, 1.1708, -2.6180],
|
||||
[0.5000, -1.1056, 1.5279, -2.8944, 10.4721, -8.5000],
|
||||
]
|
||||
)
|
||||
expected = -expected
|
||||
actual = Chebyshev2.DifferentiationMatrix(N)
|
||||
np.testing.assert_allclose(actual, expected, rtol=0, atol=1e-4)
|
||||
|
||||
def test_CalculateWeights(self):
|
||||
"""Test interpolation weights for a cubic function at arbitrary points."""
|
||||
N = 32
|
||||
fvals = Chebyshev2_vector(f, N)
|
||||
x1, x2 = 0.7, -0.376
|
||||
w1 = Chebyshev2.CalculateWeights(N, x1)
|
||||
w2 = Chebyshev2.CalculateWeights(N, x2)
|
||||
self.assertAlmostEqual(w1.dot(fvals), f(x1), delta=1e-8)
|
||||
self.assertAlmostEqual(w2.dot(fvals), f(x2), delta=1e-8)
|
||||
|
||||
def test_CalculateWeights2(self):
|
||||
"""Test interpolation weights in arbitrary interval [a,b]."""
|
||||
N = 32
|
||||
a, b = 0.0, 10.0
|
||||
x1, x2 = 7.0, 4.12
|
||||
fvals = Chebyshev2_vector(f, N, a, b)
|
||||
w1 = Chebyshev2.CalculateWeights(N, x1, a, b)
|
||||
self.assertAlmostEqual(w1.dot(fvals), f(x1), delta=1e-8)
|
||||
w2 = Chebyshev2.CalculateWeights(N, x2, a, b)
|
||||
self.assertAlmostEqual(w2.dot(fvals), f(x2), delta=1e-8)
|
||||
|
||||
def test_CalculateWeights_CoincidingPoint(self):
|
||||
"""Test that weights are correctly computed when x coincides with a Chebyshev point."""
|
||||
N = 5
|
||||
coincidingPoint = Chebyshev2.Point(N, 1)
|
||||
w = Chebyshev2.CalculateWeights(N, coincidingPoint)
|
||||
tol = 1e-9
|
||||
for j in range(N):
|
||||
expected = 1.0 if j == 1 else 0.0
|
||||
self.assertAlmostEqual(w[j], expected, delta=tol)
|
||||
|
||||
def test_DerivativeWeights(self):
|
||||
"""Test derivative weights for polynomial function at arbitrary points."""
|
||||
N = 32
|
||||
fvals = Chebyshev2_vector(f, N)
|
||||
for x in [0.7, -0.376, 0.0]:
|
||||
dw = Chebyshev2.DerivativeWeights(N, x)
|
||||
self.assertAlmostEqual(dw.dot(fvals), fprime(x), delta=1e-9)
|
||||
x4 = Chebyshev2.Point(N, 3)
|
||||
dw4 = Chebyshev2.DerivativeWeights(N, x4)
|
||||
self.assertAlmostEqual(dw4.dot(fvals), fprime(x4), delta=1e-9)
|
||||
|
||||
def test_DerivativeWeights2(self):
|
||||
"""Test derivative weights in arbitrary interval [a,b]."""
|
||||
N = 32
|
||||
a, b = 0.0, 10.0
|
||||
x1, x2 = 5.0, 4.12
|
||||
fvals = Chebyshev2_vector(f, N, a, b)
|
||||
dw1 = Chebyshev2.DerivativeWeights(N, x1, a, b)
|
||||
self.assertAlmostEqual(dw1.dot(fvals), fprime(x1), delta=1e-8)
|
||||
dw2 = Chebyshev2.DerivativeWeights(N, x2, a, b)
|
||||
self.assertAlmostEqual(dw2.dot(fvals), fprime(x2), delta=1e-8)
|
||||
x3 = Chebyshev2.Point(N, 3, a, b)
|
||||
dw3 = Chebyshev2.DerivativeWeights(N, x3, a, b)
|
||||
self.assertAlmostEqual(dw3.dot(fvals), fprime(x3), delta=1e-8)
|
||||
|
||||
def test_DerivativeWeightsDifferentiationMatrix(self):
|
||||
"""Test that derivative weights match multiplication by differentiation matrix."""
|
||||
N6 = 6
|
||||
x1 = 0.311
|
||||
D6 = Chebyshev2.DifferentiationMatrix(N6)
|
||||
expected = Chebyshev2.CalculateWeights(N6, x1).dot(D6)
|
||||
actual = Chebyshev2.DerivativeWeights(N6, x1)
|
||||
np.testing.assert_allclose(actual, expected, rtol=0, atol=1e-12)
|
||||
|
||||
a, b, x2 = -3.0, 8.0, 5.05
|
||||
D6_2 = Chebyshev2.DifferentiationMatrix(N6, a, b)
|
||||
expected1 = Chebyshev2.CalculateWeights(N6, x2, a, b).dot(D6_2)
|
||||
actual1 = Chebyshev2.DerivativeWeights(N6, x2, a, b)
|
||||
np.testing.assert_allclose(actual1, expected1, rtol=0, atol=1e-12)
|
||||
|
||||
def test_DerivativeWeights6(self):
|
||||
"""Test that differentiating the identity function gives a constant."""
|
||||
N6 = 6
|
||||
D6 = Chebyshev2.DifferentiationMatrix(N6)
|
||||
x = Chebyshev2.Points(N6) # ramp with slope 1
|
||||
ones = np.ones(N6)
|
||||
np.testing.assert_allclose(D6.dot(x), ones, rtol=0, atol=1e-9)
|
||||
|
||||
def test_DerivativeWeights7(self):
|
||||
"""Test that differentiating the identity function gives a constant (N=7)."""
|
||||
N7 = 7
|
||||
D7 = Chebyshev2.DifferentiationMatrix(N7)
|
||||
x = Chebyshev2.Points(N7)
|
||||
ones = np.ones(N7)
|
||||
np.testing.assert_allclose(D7.dot(x), ones, rtol=0, atol=1e-9)
|
||||
|
||||
def test_IntegrationMatrix(self):
|
||||
"""Test integration matrix properties and accuracy on polynomial functions."""
|
||||
N = 10
|
||||
a, b = 0.0, 10.0
|
||||
P = Chebyshev2.IntegrationMatrix(N, a, b)
|
||||
F = P.dot(np.ones(N))
|
||||
self.assertAlmostEqual(F[0], 0.0, delta=1e-9)
|
||||
points = Chebyshev2.Points(N, a, b)
|
||||
ramp = points - a
|
||||
np.testing.assert_allclose(F, ramp, rtol=0, atol=1e-9)
|
||||
fp = Chebyshev2_vector(fprime, N, a, b)
|
||||
F_est = P.dot(fp)
|
||||
self.assertAlmostEqual(F_est[0], 0.0, delta=1e-9)
|
||||
F_est += f(a)
|
||||
F_true = Chebyshev2_vector(f, N, a, b)
|
||||
np.testing.assert_allclose(F_est, F_true, rtol=0, atol=1e-9)
|
||||
D = Chebyshev2.DifferentiationMatrix(N, a, b)
|
||||
ff_est = D.dot(F_est)
|
||||
np.testing.assert_allclose(ff_est, fp, rtol=0, atol=1e-9)
|
||||
|
||||
def test_IntegrationWeights7(self):
|
||||
"""Test integration weights against known values for N=7."""
|
||||
N = 7
|
||||
actual = Chebyshev2.IntegrationWeights(N, -1, 1)
|
||||
expected = np.array(
|
||||
[
|
||||
0.0285714285714286,
|
||||
0.253968253968254,
|
||||
0.457142857142857,
|
||||
0.520634920634921,
|
||||
0.457142857142857,
|
||||
0.253968253968254,
|
||||
0.0285714285714286,
|
||||
]
|
||||
)
|
||||
np.testing.assert_allclose(actual, expected, rtol=0, atol=1e-9)
|
||||
self.assertAlmostEqual(np.sum(actual), 2.0, delta=1e-9)
|
||||
fp = Chebyshev2_vector(fprime, N)
|
||||
expectedF = f(1) - f(-1)
|
||||
self.assertAlmostEqual(actual.dot(fp), expectedF, delta=1e-9)
|
||||
P = Chebyshev2.IntegrationMatrix(N)
|
||||
p7 = P[-1, :]
|
||||
self.assertAlmostEqual(p7.dot(fp), expectedF, delta=1e-9)
|
||||
fvals = Chebyshev2_vector(f, N)
|
||||
self.assertAlmostEqual(p7.dot(fvals), actual.dot(fvals), delta=1e-9)
|
||||
|
||||
def test_IntegrationWeights8(self):
|
||||
"""Test integration weights against known values for N=8."""
|
||||
N = 8
|
||||
actual = Chebyshev2.IntegrationWeights(N, -1, 1)
|
||||
expected = np.array(
|
||||
[
|
||||
0.0204081632653061,
|
||||
0.190141007218208,
|
||||
0.352242423718159,
|
||||
0.437208405798326,
|
||||
0.437208405798326,
|
||||
0.352242423718159,
|
||||
0.190141007218208,
|
||||
0.0204081632653061,
|
||||
]
|
||||
)
|
||||
np.testing.assert_allclose(actual, expected, rtol=0, atol=1e-9)
|
||||
self.assertAlmostEqual(np.sum(actual), 2.0, delta=1e-9)
|
||||
|
||||
def test_DoubleIntegrationWeights(self):
|
||||
"""Test double integration weights for constant function (N=7)."""
|
||||
N = 7
|
||||
a, b = 0.0, 10.0
|
||||
P = Chebyshev2.IntegrationMatrix(N, a, b)
|
||||
ones = np.ones(N)
|
||||
w = Chebyshev2.DoubleIntegrationWeights(N, a, b)
|
||||
self.assertAlmostEqual(w.dot(ones), b * b / 2.0, delta=1e-9)
|
||||
|
||||
def test_DoubleIntegrationWeights2(self):
|
||||
"""Test double integration weights for constant function (N=8)."""
|
||||
N = 8
|
||||
a, b = 0.0, 3.0
|
||||
P = Chebyshev2.IntegrationMatrix(N, a, b)
|
||||
ones = np.ones(N)
|
||||
w = Chebyshev2.DoubleIntegrationWeights(N, a, b)
|
||||
self.assertAlmostEqual(w.dot(ones), b * b / 2.0, delta=1e-9)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
|
@ -16,7 +16,7 @@ import numpy as np
|
|||
from gtsam.utils.test_case import GtsamTestCase
|
||||
|
||||
import gtsam
|
||||
from gtsam import Point3, Pose3, Rot3, Similarity3
|
||||
from gtsam import Point3, Pose3, Rot3, Similarity3, BetweenFactorSimilarity3, NonlinearFactorGraph, Values, LevenbergMarquardtOptimizer, LevenbergMarquardtParams
|
||||
|
||||
|
||||
class TestSim3(GtsamTestCase):
|
||||
|
@ -130,6 +130,65 @@ class TestSim3(GtsamTestCase):
|
|||
for aTi, bTi in zip(aTi_list, bTi_list):
|
||||
self.gtsamAssertEquals(aTi, aSb.transformFrom(bTi))
|
||||
|
||||
def test_sim3_optimization(self)->None:
|
||||
# Create a PriorFactor with a Sim3 prior
|
||||
prior = Similarity3(Rot3.Ypr(0.1, 0.2, 0.3), Point3(1, 2, 3), 4)
|
||||
model = gtsam.noiseModel.Isotropic.Sigma(7, 1)
|
||||
|
||||
# Create graph
|
||||
graph = NonlinearFactorGraph()
|
||||
graph.addPriorSimilarity3(1, prior, model)
|
||||
|
||||
# Create initial estimate with Identity transform
|
||||
initial = Values()
|
||||
initial.insert(1, Similarity3())
|
||||
|
||||
# Optimize
|
||||
params = LevenbergMarquardtParams()
|
||||
params.setVerbosityLM("TRYCONFIG")
|
||||
result = LevenbergMarquardtOptimizer(graph, initial).optimize()
|
||||
|
||||
# After optimization, result should be prior
|
||||
self.gtsamAssertEquals(prior, result.atSimilarity3(1), 1e-4)
|
||||
|
||||
def test_sim3_optimization2(self) -> None:
|
||||
prior = Similarity3()
|
||||
m1 = Similarity3(Rot3.Ypr(np.pi / 4.0, 0, 0), Point3(2.0, 0, 0), 1.0)
|
||||
m2 = Similarity3(Rot3.Ypr(np.pi / 2.0, 0, 0), Point3(np.sqrt(8) * 0.9, 0, 0), 1.0)
|
||||
m3 = Similarity3(Rot3.Ypr(3 * np.pi / 4.0, 0, 0), Point3(np.sqrt(32) * 0.8, 0, 0), 1.0)
|
||||
m4 = Similarity3(Rot3.Ypr(np.pi / 2.0, 0, 0), Point3(6 * 0.7, 0, 0), 1.0)
|
||||
loop = Similarity3(1.42)
|
||||
|
||||
priorNoise = gtsam.noiseModel.Isotropic.Sigma(7, 0.01)
|
||||
betweenNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10]))
|
||||
betweenNoise2 = gtsam.noiseModel.Diagonal.Sigmas(np.array([ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0]))
|
||||
b1 = BetweenFactorSimilarity3(1, 2, m1, betweenNoise)
|
||||
b2 = BetweenFactorSimilarity3(2, 3, m2, betweenNoise)
|
||||
b3 = BetweenFactorSimilarity3(3, 4, m3, betweenNoise)
|
||||
b4 = BetweenFactorSimilarity3(4, 5, m4, betweenNoise)
|
||||
lc = BetweenFactorSimilarity3(5, 1, loop, betweenNoise2)
|
||||
|
||||
# Create graph
|
||||
graph = NonlinearFactorGraph()
|
||||
graph.addPriorSimilarity3(1, prior, priorNoise)
|
||||
graph.add(b1)
|
||||
graph.add(b2)
|
||||
graph.add(b3)
|
||||
graph.add(b4)
|
||||
graph.add(lc)
|
||||
|
||||
# graph.print("Full Graph\n");
|
||||
initial=Values()
|
||||
initial.insert(1, prior)
|
||||
initial.insert(2, Similarity3(Rot3.Ypr(np.pi / 2.0, 0, 0), Point3(1, 0, 0), 1.1))
|
||||
initial.insert(3, Similarity3(Rot3.Ypr(2.0 * np.pi / 2.0, 0, 0), Point3(0.9, 1.1, 0), 1.2))
|
||||
initial.insert(4, Similarity3(Rot3.Ypr(3.0 * np.pi / 2.0, 0, 0), Point3(0, 1, 0), 1.3))
|
||||
initial.insert(5, Similarity3(Rot3.Ypr(4.0 * np.pi / 2.0, 0, 0), Point3(0, 0, 0), 1.0))
|
||||
|
||||
|
||||
result = LevenbergMarquardtOptimizer(graph, initial).optimizeSafely()
|
||||
self.gtsamAssertEquals(Similarity3(0.7), result.atSimilarity3(5), 0.4)
|
||||
|
||||
def test_align_via_Sim3_to_poses_skydio32(self) -> None:
|
||||
"""Ensure scale estimate of Sim(3) object is non-negative.
|
||||
|
||||
|
|
|
@ -54,7 +54,7 @@ class XMLDocParser:
|
|||
|
||||
# Find which member to get docs from, if there are multiple that match in name and args
|
||||
documenting_index = self.determine_documenting_index(
|
||||
cpp_class, cpp_method, method_args_names)
|
||||
cpp_class, cpp_method, method_args_names, member_defs)
|
||||
|
||||
# Extract the docs for the function that matches cpp_class.cpp_method(*method_args_names).
|
||||
return self.get_formatted_docstring(member_defs[documenting_index],
|
||||
|
|
|
@ -12,17 +12,6 @@ template <op_id id, op_type ot, typename L, typename R>
|
|||
template <detail::op_id id, detail::op_type ot, typename L, typename R, typename... Extra>
|
||||
class_ &def(const detail::op_<id, ot, L, R> &op, const Extra &...extra) {
|
||||
class_ &def_cast(const detail::op_<id, ot, L, R> &op, const Extra &...extra) {
|
||||
int valu;
|
||||
explicit movable_int(int v) : valu{v} {}
|
||||
movable_int(movable_int &&other) noexcept : valu(other.valu) { other.valu = 91; }
|
||||
explicit indestructible_int(int v) : valu{v} {}
|
||||
REQUIRE(hld.as_raw_ptr_unowned<zombie>()->valu == 19);
|
||||
REQUIRE(othr.valu == 19);
|
||||
REQUIRE(orig.valu == 91);
|
||||
(m.pass_valu, "Valu", "pass_valu:Valu(_MvCtor)*_CpCtor"),
|
||||
atyp_valu rtrn_valu() { atyp_valu obj{"Valu"}; return obj; }
|
||||
assert m.atyp_valu().get_mtxt() == "Valu"
|
||||
// valu(e), ref(erence), ptr or p (pointer), r = rvalue, m = mutable, c = const,
|
||||
@pytest.mark.parametrize("access", ["ro", "rw", "static_ro", "static_rw"])
|
||||
struct IntStruct {
|
||||
explicit IntStruct(int v) : value(v){};
|
||||
|
|
|
@ -81,7 +81,7 @@ nox -s build
|
|||
### Full setup
|
||||
|
||||
To setup an ideal development environment, run the following commands on a
|
||||
system with CMake 3.15+:
|
||||
system with CMake 3.14+:
|
||||
|
||||
```bash
|
||||
python3 -m venv venv
|
||||
|
@ -96,8 +96,8 @@ Tips:
|
|||
* You can use `virtualenv` (faster, from PyPI) instead of `venv`.
|
||||
* You can select any name for your environment folder; if it contains "env" it
|
||||
will be ignored by git.
|
||||
* If you don't have CMake 3.15+, just add "cmake" to the pip install command.
|
||||
* You can use `-DPYBIND11_FINDPYTHON=ON` to use FindPython.
|
||||
* If you don't have CMake 3.14+, just add "cmake" to the pip install command.
|
||||
* You can use `-DPYBIND11_FINDPYTHON=ON` to use FindPython on CMake 3.12+
|
||||
* In classic mode, you may need to set `-DPYTHON_EXECUTABLE=/path/to/python`.
|
||||
FindPython uses `-DPython_ROOT_DIR=/path/to` or
|
||||
`-DPython_EXECUTABLE=/path/to/python`.
|
||||
|
@ -149,8 +149,8 @@ To run the tests, you can "build" the check target:
|
|||
cmake --build build --target check
|
||||
```
|
||||
|
||||
`--target` can be spelled `-t`. You can also run individual tests with these
|
||||
targets:
|
||||
`--target` can be spelled `-t` in CMake 3.15+. You can also run individual
|
||||
tests with these targets:
|
||||
|
||||
* `pytest`: Python tests only, using the
|
||||
[pytest](https://docs.pytest.org/en/stable/) framework
|
||||
|
|
|
@ -39,8 +39,6 @@ jobs:
|
|||
- 'pypy-3.8'
|
||||
- 'pypy-3.9'
|
||||
- 'pypy-3.10'
|
||||
- 'pypy-3.11'
|
||||
- 'graalpy-24.1'
|
||||
|
||||
# Items in here will either be added to the build matrix (if not
|
||||
# present), or add new keys to an existing matrix element if all the
|
||||
|
@ -66,45 +64,9 @@ jobs:
|
|||
# Inject a couple Windows 2019 runs
|
||||
- runs-on: windows-2019
|
||||
python: '3.9'
|
||||
# Inject a few runs with different runtime libraries
|
||||
- runs-on: windows-2022
|
||||
python: '3.9'
|
||||
args: >
|
||||
-DCMAKE_MSVC_RUNTIME_LIBRARY=MultiThreaded
|
||||
- runs-on: windows-2022
|
||||
python: '3.10'
|
||||
args: >
|
||||
-DCMAKE_MSVC_RUNTIME_LIBRARY=MultiThreadedDLL
|
||||
# This needs a python built with MTd
|
||||
# - runs-on: windows-2022
|
||||
# python: '3.11'
|
||||
# args: >
|
||||
# -DCMAKE_MSVC_RUNTIME_LIBRARY=MultiThreadedDebug
|
||||
- runs-on: windows-2022
|
||||
python: '3.12'
|
||||
args: >
|
||||
-DCMAKE_MSVC_RUNTIME_LIBRARY=MultiThreadedDebugDLL
|
||||
# Extra ubuntu latest job
|
||||
- runs-on: ubuntu-latest
|
||||
python: '3.11'
|
||||
# Run tests with py::smart_holder as the default holder
|
||||
# with recent (or ideally latest) released Python version.
|
||||
- runs-on: ubuntu-latest
|
||||
python: '3.12'
|
||||
args: >
|
||||
-DCMAKE_CXX_FLAGS="-DPYBIND11_RUN_TESTING_WITH_SMART_HOLDER_AS_DEFAULT_BUT_NEVER_USE_IN_PRODUCTION_PLEASE"
|
||||
- runs-on: macos-13
|
||||
python: '3.12'
|
||||
args: >
|
||||
-DCMAKE_CXX_FLAGS="-DPYBIND11_RUN_TESTING_WITH_SMART_HOLDER_AS_DEFAULT_BUT_NEVER_USE_IN_PRODUCTION_PLEASE"
|
||||
- runs-on: windows-2022
|
||||
python: '3.12'
|
||||
args: >
|
||||
-DCMAKE_CXX_FLAGS="/DPYBIND11_RUN_TESTING_WITH_SMART_HOLDER_AS_DEFAULT_BUT_NEVER_USE_IN_PRODUCTION_PLEASE /GR /EHsc"
|
||||
exclude:
|
||||
# The setup-python action currently doesn't have graalpy for windows
|
||||
- python: 'graalpy-24.1'
|
||||
runs-on: 'windows-2022'
|
||||
|
||||
|
||||
name: "🐍 ${{ matrix.python }} • ${{ matrix.runs-on }} • x64 ${{ matrix.args }}"
|
||||
|
@ -160,7 +122,6 @@ jobs:
|
|||
-DPYBIND11_DISABLE_HANDLE_TYPE_NAME_DEFAULT_IMPLEMENTATION=ON
|
||||
-DPYBIND11_SIMPLE_GIL_MANAGEMENT=ON
|
||||
-DPYBIND11_NUMPY_1_ONLY=ON
|
||||
-DPYBIND11_PYTEST_ARGS=-v
|
||||
-DDOWNLOAD_CATCH=ON
|
||||
-DDOWNLOAD_EIGEN=ON
|
||||
-DCMAKE_CXX_STANDARD=11
|
||||
|
@ -190,7 +151,6 @@ jobs:
|
|||
-DPYBIND11_WERROR=ON
|
||||
-DPYBIND11_SIMPLE_GIL_MANAGEMENT=OFF
|
||||
-DPYBIND11_NUMPY_1_ONLY=ON
|
||||
-DPYBIND11_PYTEST_ARGS=-v
|
||||
-DDOWNLOAD_CATCH=ON
|
||||
-DDOWNLOAD_EIGEN=ON
|
||||
-DCMAKE_CXX_STANDARD=17
|
||||
|
@ -210,7 +170,6 @@ jobs:
|
|||
run: >
|
||||
cmake -S . -B build3
|
||||
-DPYBIND11_WERROR=ON
|
||||
-DPYBIND11_PYTEST_ARGS=-v
|
||||
-DDOWNLOAD_CATCH=ON
|
||||
-DDOWNLOAD_EIGEN=ON
|
||||
-DCMAKE_CXX_STANDARD=17
|
||||
|
@ -351,11 +310,22 @@ jobs:
|
|||
strategy:
|
||||
fail-fast: false
|
||||
matrix:
|
||||
clang:
|
||||
- 3.6
|
||||
- 3.7
|
||||
- 3.9
|
||||
- 7
|
||||
- 9
|
||||
- dev
|
||||
std:
|
||||
- 11
|
||||
container_suffix:
|
||||
- ""
|
||||
include:
|
||||
- clang: 5
|
||||
std: 14
|
||||
- clang: 10
|
||||
std: 17
|
||||
- clang: 11
|
||||
std: 20
|
||||
- clang: 12
|
||||
|
@ -533,6 +503,10 @@ jobs:
|
|||
fail-fast: false
|
||||
matrix:
|
||||
include:
|
||||
- { gcc: 7, std: 11 }
|
||||
- { gcc: 7, std: 17 }
|
||||
- { gcc: 8, std: 14 }
|
||||
- { gcc: 8, std: 17 }
|
||||
- { gcc: 9, std: 20 }
|
||||
- { gcc: 10, std: 17 }
|
||||
- { gcc: 10, std: 20 }
|
||||
|
@ -753,9 +727,9 @@ jobs:
|
|||
|
||||
# This tests an "install" with the CMake tools
|
||||
install-classic:
|
||||
name: "🐍 3.9 • Debian • x86 • Install"
|
||||
name: "🐍 3.7 • Debian • x86 • Install"
|
||||
runs-on: ubuntu-latest
|
||||
container: i386/debian:bullseye
|
||||
container: i386/debian:buster
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v1 # v1 is required to run inside docker
|
||||
|
@ -835,6 +809,7 @@ jobs:
|
|||
fail-fast: false
|
||||
matrix:
|
||||
python:
|
||||
- '3.7'
|
||||
- '3.8'
|
||||
- '3.9'
|
||||
- '3.10'
|
||||
|
@ -852,6 +827,8 @@ jobs:
|
|||
args: -DCMAKE_CXX_STANDARD=20
|
||||
- python: '3.8'
|
||||
args: -DCMAKE_CXX_STANDARD=17
|
||||
- python: '3.7'
|
||||
args: -DCMAKE_CXX_STANDARD=14
|
||||
|
||||
|
||||
name: "🐍 ${{ matrix.python }} • MSVC 2019 • x86 ${{ matrix.args }}"
|
||||
|
@ -1030,6 +1007,7 @@ jobs:
|
|||
git
|
||||
mingw-w64-${{matrix.env}}-gcc
|
||||
mingw-w64-${{matrix.env}}-python-pip
|
||||
mingw-w64-${{matrix.env}}-python-numpy
|
||||
mingw-w64-${{matrix.env}}-cmake
|
||||
mingw-w64-${{matrix.env}}-make
|
||||
mingw-w64-${{matrix.env}}-python-pytest
|
||||
|
@ -1041,7 +1019,7 @@ jobs:
|
|||
with:
|
||||
msystem: ${{matrix.sys}}
|
||||
install: >-
|
||||
mingw-w64-${{matrix.env}}-python-numpy
|
||||
git
|
||||
mingw-w64-${{matrix.env}}-python-scipy
|
||||
mingw-w64-${{matrix.env}}-eigen3
|
||||
|
||||
|
@ -1139,7 +1117,7 @@ jobs:
|
|||
uses: jwlawson/actions-setup-cmake@v2.0
|
||||
|
||||
- name: Install ninja-build tool
|
||||
uses: seanmiddleditch/gha-setup-ninja@v6
|
||||
uses: seanmiddleditch/gha-setup-ninja@v5
|
||||
|
||||
- name: Run pip installs
|
||||
run: |
|
||||
|
|
|
@ -31,7 +31,7 @@ jobs:
|
|||
include:
|
||||
- runs-on: ubuntu-20.04
|
||||
arch: x64
|
||||
cmake: "3.15"
|
||||
cmake: "3.5"
|
||||
|
||||
- runs-on: ubuntu-20.04
|
||||
arch: x64
|
||||
|
@ -39,22 +39,22 @@ jobs:
|
|||
|
||||
- runs-on: macos-13
|
||||
arch: x64
|
||||
cmake: "3.15"
|
||||
cmake: "3.7"
|
||||
|
||||
- runs-on: windows-2019
|
||||
arch: x64 # x86 compilers seem to be missing on 2019 image
|
||||
cmake: "3.18"
|
||||
|
||||
name: 🐍 3.8 • CMake ${{ matrix.cmake }} • ${{ matrix.runs-on }}
|
||||
name: 🐍 3.7 • CMake ${{ matrix.cmake }} • ${{ matrix.runs-on }}
|
||||
runs-on: ${{ matrix.runs-on }}
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
|
||||
- name: Setup Python 3.8
|
||||
- name: Setup Python 3.7
|
||||
uses: actions/setup-python@v5
|
||||
with:
|
||||
python-version: 3.8
|
||||
python-version: 3.7
|
||||
architecture: ${{ matrix.arch }}
|
||||
|
||||
- name: Prepare env
|
||||
|
|
|
@ -22,7 +22,7 @@ jobs:
|
|||
submodules: true
|
||||
fetch-depth: 0
|
||||
|
||||
- uses: pypa/cibuildwheel@v2.23
|
||||
- uses: pypa/cibuildwheel@v2.20
|
||||
env:
|
||||
PYODIDE_BUILD_EXPORTS: whole_archive
|
||||
with:
|
||||
|
|
|
@ -103,7 +103,7 @@ jobs:
|
|||
- uses: actions/download-artifact@v4
|
||||
|
||||
- name: Generate artifact attestation for sdist and wheel
|
||||
uses: actions/attest-build-provenance@bd77c077858b8d561b7a36cbe48ef4cc642ca39d # v2.2.2
|
||||
uses: actions/attest-build-provenance@1c608d11d69870c2092266b3f9a6f3abbf17002c # v1.4.3
|
||||
with:
|
||||
subject-path: "*/pybind11*"
|
||||
|
||||
|
|
|
@ -25,14 +25,14 @@ repos:
|
|||
|
||||
# Clang format the codebase automatically
|
||||
- repo: https://github.com/pre-commit/mirrors-clang-format
|
||||
rev: "v19.1.7"
|
||||
rev: "v18.1.8"
|
||||
hooks:
|
||||
- id: clang-format
|
||||
types_or: [c++, c, cuda]
|
||||
|
||||
# Ruff, the Python auto-correcting linter/formatter written in Rust
|
||||
- repo: https://github.com/astral-sh/ruff-pre-commit
|
||||
rev: v0.9.9
|
||||
rev: v0.6.3
|
||||
hooks:
|
||||
- id: ruff
|
||||
args: ["--fix", "--show-fixes"]
|
||||
|
@ -40,7 +40,7 @@ repos:
|
|||
|
||||
# Check static types with mypy
|
||||
- repo: https://github.com/pre-commit/mirrors-mypy
|
||||
rev: "v1.15.0"
|
||||
rev: "v1.11.2"
|
||||
hooks:
|
||||
- id: mypy
|
||||
args: []
|
||||
|
@ -62,7 +62,7 @@ repos:
|
|||
|
||||
# Standard hooks
|
||||
- repo: https://github.com/pre-commit/pre-commit-hooks
|
||||
rev: "v5.0.0"
|
||||
rev: "v4.6.0"
|
||||
hooks:
|
||||
- id: check-added-large-files
|
||||
- id: check-case-conflict
|
||||
|
@ -76,11 +76,10 @@ repos:
|
|||
- id: mixed-line-ending
|
||||
- id: requirements-txt-fixer
|
||||
- id: trailing-whitespace
|
||||
exclude: \.patch?$
|
||||
|
||||
# Also code format the docs
|
||||
- repo: https://github.com/adamchainz/blacken-docs
|
||||
rev: "1.19.1"
|
||||
rev: "1.18.0"
|
||||
hooks:
|
||||
- id: blacken-docs
|
||||
additional_dependencies:
|
||||
|
@ -91,11 +90,10 @@ repos:
|
|||
rev: "v1.5.5"
|
||||
hooks:
|
||||
- id: remove-tabs
|
||||
exclude: (^docs/.*|\.patch)?$
|
||||
|
||||
# Avoid directional quotes
|
||||
- repo: https://github.com/sirosen/texthooks
|
||||
rev: "0.6.8"
|
||||
rev: "0.6.7"
|
||||
hooks:
|
||||
- id: fix-ligatures
|
||||
- id: fix-smartquotes
|
||||
|
@ -110,7 +108,7 @@ repos:
|
|||
|
||||
# Checks the manifest for missing files (native support)
|
||||
- repo: https://github.com/mgedmin/check-manifest
|
||||
rev: "0.50"
|
||||
rev: "0.49"
|
||||
hooks:
|
||||
- id: check-manifest
|
||||
# This is a slow hook, so only run this if --hook-stage manual is passed
|
||||
|
@ -121,7 +119,7 @@ repos:
|
|||
# Use tools/codespell_ignore_lines_from_errors.py
|
||||
# to rebuild .codespell-ignore-lines
|
||||
- repo: https://github.com/codespell-project/codespell
|
||||
rev: "v2.4.1"
|
||||
rev: "v2.3.0"
|
||||
hooks:
|
||||
- id: codespell
|
||||
exclude: ".supp$"
|
||||
|
@ -144,14 +142,14 @@ repos:
|
|||
|
||||
# PyLint has native support - not always usable, but works for us
|
||||
- repo: https://github.com/PyCQA/pylint
|
||||
rev: "v3.3.4"
|
||||
rev: "v3.2.7"
|
||||
hooks:
|
||||
- id: pylint
|
||||
files: ^pybind11
|
||||
|
||||
# Check schemas on some of our YAML files
|
||||
- repo: https://github.com/python-jsonschema/check-jsonschema
|
||||
rev: 0.31.2
|
||||
rev: 0.29.2
|
||||
hooks:
|
||||
- id: check-readthedocs
|
||||
- id: check-github-workflows
|
||||
|
|
|
@ -10,7 +10,16 @@ if(NOT CMAKE_VERSION VERSION_LESS "3.27")
|
|||
cmake_policy(GET CMP0148 _pybind11_cmp0148)
|
||||
endif()
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
|
||||
# The `cmake_minimum_required(VERSION 3.5...3.29)` syntax does not work with
|
||||
# some versions of VS that have a patched CMake 3.11. This forces us to emulate
|
||||
# the behavior using the following workaround:
|
||||
if(${CMAKE_VERSION} VERSION_LESS 3.29)
|
||||
cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION})
|
||||
else()
|
||||
cmake_policy(VERSION 3.29)
|
||||
endif()
|
||||
|
||||
if(_pybind11_cmp0148)
|
||||
cmake_policy(SET CMP0148 ${_pybind11_cmp0148})
|
||||
|
@ -18,7 +27,9 @@ if(_pybind11_cmp0148)
|
|||
endif()
|
||||
|
||||
# Avoid infinite recursion if tests include this as a subdirectory
|
||||
include_guard(GLOBAL)
|
||||
if(DEFINED PYBIND11_MASTER_PROJECT)
|
||||
return()
|
||||
endif()
|
||||
|
||||
# Extract project version from source
|
||||
file(STRINGS "${CMAKE_CURRENT_SOURCE_DIR}/include/pybind11/detail/common.h"
|
||||
|
@ -63,6 +74,14 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR)
|
|||
|
||||
set(PYBIND11_MASTER_PROJECT ON)
|
||||
|
||||
if(OSX AND CMAKE_VERSION VERSION_LESS 3.7)
|
||||
# Bug in macOS CMake < 3.7 is unable to download catch
|
||||
message(WARNING "CMAKE 3.7+ needed on macOS to download catch, and newer HIGHLY recommended")
|
||||
elseif(WINDOWS AND CMAKE_VERSION VERSION_LESS 3.8)
|
||||
# Only tested with 3.8+ in CI.
|
||||
message(WARNING "CMAKE 3.8+ tested on Windows, previous versions untested")
|
||||
endif()
|
||||
|
||||
message(STATUS "CMake ${CMAKE_VERSION}")
|
||||
|
||||
if(CMAKE_CXX_STANDARD)
|
||||
|
@ -114,7 +133,8 @@ cmake_dependent_option(
|
|||
"Install pybind11 headers in Python include directory instead of default installation prefix"
|
||||
OFF "PYBIND11_INSTALL" OFF)
|
||||
|
||||
option(PYBIND11_FINDPYTHON "Force new FindPython" ${_pybind11_findpython_default})
|
||||
cmake_dependent_option(PYBIND11_FINDPYTHON "Force new FindPython" ${_pybind11_findpython_default}
|
||||
"NOT CMAKE_VERSION VERSION_LESS 3.12" OFF)
|
||||
|
||||
# Allow PYTHON_EXECUTABLE if in FINDPYTHON mode and building pybind11's tests
|
||||
# (makes transition easier while we support both modes).
|
||||
|
@ -131,13 +151,10 @@ set(PYBIND11_HEADERS
|
|||
include/pybind11/detail/common.h
|
||||
include/pybind11/detail/cpp_conduit.h
|
||||
include/pybind11/detail/descr.h
|
||||
include/pybind11/detail/dynamic_raw_ptr_cast_if_possible.h
|
||||
include/pybind11/detail/init.h
|
||||
include/pybind11/detail/internals.h
|
||||
include/pybind11/detail/struct_smart_holder.h
|
||||
include/pybind11/detail/type_caster_base.h
|
||||
include/pybind11/detail/typeid.h
|
||||
include/pybind11/detail/using_smart_holder.h
|
||||
include/pybind11/detail/value_and_holder.h
|
||||
include/pybind11/detail/exception_translation.h
|
||||
include/pybind11/attr.h
|
||||
|
@ -146,9 +163,6 @@ set(PYBIND11_HEADERS
|
|||
include/pybind11/chrono.h
|
||||
include/pybind11/common.h
|
||||
include/pybind11/complex.h
|
||||
include/pybind11/conduit/pybind11_conduit_v1.h
|
||||
include/pybind11/conduit/pybind11_platform_abi_id.h
|
||||
include/pybind11/conduit/wrap_include_python_h.h
|
||||
include/pybind11/options.h
|
||||
include/pybind11/eigen.h
|
||||
include/pybind11/eigen/common.h
|
||||
|
@ -167,13 +181,11 @@ set(PYBIND11_HEADERS
|
|||
include/pybind11/stl.h
|
||||
include/pybind11/stl_bind.h
|
||||
include/pybind11/stl/filesystem.h
|
||||
include/pybind11/trampoline_self_life_support.h
|
||||
include/pybind11/type_caster_pyobject_ptr.h
|
||||
include/pybind11/typing.h
|
||||
include/pybind11/warnings.h)
|
||||
include/pybind11/typing.h)
|
||||
|
||||
# Compare with grep and warn if mismatched
|
||||
if(PYBIND11_MASTER_PROJECT)
|
||||
if(PYBIND11_MASTER_PROJECT AND NOT CMAKE_VERSION VERSION_LESS 3.12)
|
||||
file(
|
||||
GLOB_RECURSE _pybind11_header_check
|
||||
LIST_DIRECTORIES false
|
||||
|
@ -191,7 +203,10 @@ if(PYBIND11_MASTER_PROJECT)
|
|||
endif()
|
||||
endif()
|
||||
|
||||
list(TRANSFORM PYBIND11_HEADERS PREPEND "${CMAKE_CURRENT_SOURCE_DIR}/")
|
||||
# CMake 3.12 added list(TRANSFORM <list> PREPEND
|
||||
# But we can't use it yet
|
||||
string(REPLACE "include/" "${CMAKE_CURRENT_SOURCE_DIR}/include/" PYBIND11_HEADERS
|
||||
"${PYBIND11_HEADERS}")
|
||||
|
||||
# Cache variable so this can be used in parent projects
|
||||
set(pybind11_INCLUDE_DIR
|
||||
|
@ -261,11 +276,25 @@ if(PYBIND11_INSTALL)
|
|||
tools/${PROJECT_NAME}Config.cmake.in "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake"
|
||||
INSTALL_DESTINATION ${PYBIND11_CMAKECONFIG_INSTALL_DIR})
|
||||
|
||||
# CMake natively supports header-only libraries
|
||||
write_basic_package_version_file(
|
||||
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake
|
||||
VERSION ${PROJECT_VERSION}
|
||||
COMPATIBILITY AnyNewerVersion ARCH_INDEPENDENT)
|
||||
if(CMAKE_VERSION VERSION_LESS 3.14)
|
||||
# Remove CMAKE_SIZEOF_VOID_P from ConfigVersion.cmake since the library does
|
||||
# not depend on architecture specific settings or libraries.
|
||||
set(_PYBIND11_CMAKE_SIZEOF_VOID_P ${CMAKE_SIZEOF_VOID_P})
|
||||
unset(CMAKE_SIZEOF_VOID_P)
|
||||
|
||||
write_basic_package_version_file(
|
||||
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake
|
||||
VERSION ${PROJECT_VERSION}
|
||||
COMPATIBILITY AnyNewerVersion)
|
||||
|
||||
set(CMAKE_SIZEOF_VOID_P ${_PYBIND11_CMAKE_SIZEOF_VOID_P})
|
||||
else()
|
||||
# CMake 3.14+ natively supports header-only libraries
|
||||
write_basic_package_version_file(
|
||||
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake
|
||||
VERSION ${PROJECT_VERSION}
|
||||
COMPATIBILITY AnyNewerVersion ARCH_INDEPENDENT)
|
||||
endif()
|
||||
|
||||
install(
|
||||
FILES ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
.. figure:: https://github.com/pybind/pybind11/raw/master/docs/pybind11-logo.png
|
||||
:alt: pybind11 logo
|
||||
|
||||
**pybind11 (v3) — Seamless interoperability between C++ and Python**
|
||||
**pybind11 — Seamless operability between C++11 and Python**
|
||||
|
||||
|Latest Documentation Status| |Stable Documentation Status| |Gitter chat| |GitHub Discussions| |CI| |Build status|
|
||||
|
||||
|
@ -34,7 +34,7 @@ dependency.
|
|||
Think of this library as a tiny self-contained version of Boost.Python
|
||||
with everything stripped away that isn't relevant for binding
|
||||
generation. Without comments, the core header files only require ~4K
|
||||
lines of code and depend on Python (3.8+, or PyPy) and the C++
|
||||
lines of code and depend on Python (3.7+, or PyPy) and the C++
|
||||
standard library. This compact implementation was possible thanks to
|
||||
some C++11 language features (specifically: tuples, lambda functions and
|
||||
variadic templates). Since its creation, this library has grown beyond
|
||||
|
@ -79,7 +79,7 @@ Goodies
|
|||
In addition to the core functionality, pybind11 provides some extra
|
||||
goodies:
|
||||
|
||||
- Python 3.8+, and PyPy3 7.3 are supported with an implementation-agnostic
|
||||
- Python 3.7+, and PyPy3 7.3 are supported with an implementation-agnostic
|
||||
interface (pybind11 2.9 was the last version to support Python 2 and 3.5).
|
||||
|
||||
- It is possible to bind C++11 lambda functions with captured
|
||||
|
@ -134,34 +134,11 @@ About
|
|||
|
||||
This project was created by `Wenzel
|
||||
Jakob <http://rgl.epfl.ch/people/wjakob>`_. Significant features and/or
|
||||
improvements to the code were contributed by
|
||||
Jonas Adler,
|
||||
Lori A. Burns,
|
||||
Sylvain Corlay,
|
||||
Eric Cousineau,
|
||||
Aaron Gokaslan,
|
||||
Ralf Grosse-Kunstleve,
|
||||
Trent Houliston,
|
||||
Axel Huebl,
|
||||
@hulucc,
|
||||
Yannick Jadoul,
|
||||
Sergey Lyskov,
|
||||
Johan Mabille,
|
||||
Tomasz Miąsko,
|
||||
Dean Moldovan,
|
||||
Ben Pritchard,
|
||||
Jason Rhinelander,
|
||||
Boris Schäling,
|
||||
Pim Schellart,
|
||||
Henry Schreiner,
|
||||
Ivan Smirnov,
|
||||
Dustin Spicuzza,
|
||||
Boris Staletic,
|
||||
Ethan Steinberg,
|
||||
Patrick Stewart,
|
||||
Ivor Wanders,
|
||||
and
|
||||
Xiaofei Wang.
|
||||
improvements to the code were contributed by Jonas Adler, Lori A. Burns,
|
||||
Sylvain Corlay, Eric Cousineau, Aaron Gokaslan, Ralf Grosse-Kunstleve, Trent Houliston, Axel
|
||||
Huebl, @hulucc, Yannick Jadoul, Sergey Lyskov, Johan Mabille, Tomasz Miąsko,
|
||||
Dean Moldovan, Ben Pritchard, Jason Rhinelander, Boris Schäling, Pim
|
||||
Schellart, Henry Schreiner, Ivan Smirnov, Boris Staletic, and Patrick Stewart.
|
||||
|
||||
We thank Google for a generous financial contribution to the continuous
|
||||
integration infrastructure used by this project.
|
||||
|
|
|
@ -1,53 +1,35 @@
|
|||
Custom type casters
|
||||
===================
|
||||
|
||||
Some applications may prefer custom type casters that convert between existing
|
||||
Python types and C++ types, similar to the ``list`` ↔ ``std::vector``
|
||||
and ``dict`` ↔ ``std::map`` conversions which are built into pybind11.
|
||||
Implementing custom type casters is fairly advanced usage.
|
||||
While it is recommended to use the pybind11 API as much as possible, more complex examples may
|
||||
require familiarity with the intricacies of the Python C API.
|
||||
You can refer to the `Python/C API Reference Manual <https://docs.python.org/3/c-api/index.html>`_
|
||||
for more information.
|
||||
In very rare cases, applications may require custom type casters that cannot be
|
||||
expressed using the abstractions provided by pybind11, thus requiring raw
|
||||
Python C API calls. This is fairly advanced usage and should only be pursued by
|
||||
experts who are familiar with the intricacies of Python reference counting.
|
||||
|
||||
The following snippets demonstrate how this works for a very simple ``Point2D`` type.
|
||||
We want this type to be convertible to C++ from Python types implementing the
|
||||
``Sequence`` protocol and having two elements of type ``float``.
|
||||
When returned from C++ to Python, it should be converted to a Python ``tuple[float, float]``.
|
||||
For this type we could provide Python bindings for different arithmetic functions implemented
|
||||
in C++ (here demonstrated by a simple ``negate`` function).
|
||||
|
||||
..
|
||||
PLEASE KEEP THE CODE BLOCKS IN SYNC WITH
|
||||
tests/test_docs_advanced_cast_custom.cpp
|
||||
tests/test_docs_advanced_cast_custom.py
|
||||
Ideally, change the test, run pre-commit (incl. clang-format),
|
||||
then copy the changed code back here.
|
||||
Also use TEST_SUBMODULE in tests, but PYBIND11_MODULE in docs.
|
||||
The following snippets demonstrate how this works for a very simple ``inty``
|
||||
type that that should be convertible from Python types that provide a
|
||||
``__int__(self)`` method.
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
namespace user_space {
|
||||
struct inty { long long_value; };
|
||||
|
||||
struct Point2D {
|
||||
double x;
|
||||
double y;
|
||||
};
|
||||
void print(inty s) {
|
||||
std::cout << s.long_value << std::endl;
|
||||
}
|
||||
|
||||
Point2D negate(const Point2D &point) { return Point2D{-point.x, -point.y}; }
|
||||
|
||||
} // namespace user_space
|
||||
|
||||
|
||||
The following Python snippet demonstrates the intended usage of ``negate`` from the Python side:
|
||||
The following Python snippet demonstrates the intended usage from the Python side:
|
||||
|
||||
.. code-block:: python
|
||||
|
||||
from my_math_module import docs_advanced_cast_custom as m
|
||||
class A:
|
||||
def __int__(self):
|
||||
return 123
|
||||
|
||||
point1 = [1.0, -1.0]
|
||||
point2 = m.negate(point1)
|
||||
assert point2 == (-1.0, 1.0)
|
||||
|
||||
from example import print
|
||||
|
||||
print(A())
|
||||
|
||||
To register the necessary conversion routines, it is necessary to add an
|
||||
instantiation of the ``pybind11::detail::type_caster<T>`` template.
|
||||
|
@ -56,57 +38,47 @@ type is explicitly allowed.
|
|||
|
||||
.. code-block:: cpp
|
||||
|
||||
namespace pybind11 {
|
||||
namespace detail {
|
||||
namespace PYBIND11_NAMESPACE { namespace detail {
|
||||
template <> struct type_caster<inty> {
|
||||
public:
|
||||
/**
|
||||
* This macro establishes the name 'inty' in
|
||||
* function signatures and declares a local variable
|
||||
* 'value' of type inty
|
||||
*/
|
||||
PYBIND11_TYPE_CASTER(inty, const_name("inty"));
|
||||
|
||||
template <>
|
||||
struct type_caster<user_space::Point2D> {
|
||||
// This macro inserts a lot of boilerplate code and sets the type hint.
|
||||
// `io_name` is used to specify different type hints for arguments and return values.
|
||||
// The signature of our negate function would then look like:
|
||||
// `negate(Sequence[float]) -> tuple[float, float]`
|
||||
PYBIND11_TYPE_CASTER(user_space::Point2D, io_name("Sequence[float]", "tuple[float, float]"));
|
||||
|
||||
// C++ -> Python: convert `Point2D` to `tuple[float, float]`. The second and third arguments
|
||||
// are used to indicate the return value policy and parent object (for
|
||||
// return_value_policy::reference_internal) and are often ignored by custom casters.
|
||||
// The return value should reflect the type hint specified by the second argument of `io_name`.
|
||||
static handle
|
||||
cast(const user_space::Point2D &number, return_value_policy /*policy*/, handle /*parent*/) {
|
||||
return py::make_tuple(number.x, number.y).release();
|
||||
}
|
||||
|
||||
// Python -> C++: convert a `PyObject` into a `Point2D` and return false upon failure. The
|
||||
// second argument indicates whether implicit conversions should be allowed.
|
||||
// The accepted types should reflect the type hint specified by the first argument of
|
||||
// `io_name`.
|
||||
bool load(handle src, bool /*convert*/) {
|
||||
// Check if handle is a Sequence
|
||||
if (!py::isinstance<py::sequence>(src)) {
|
||||
return false;
|
||||
}
|
||||
auto seq = py::reinterpret_borrow<py::sequence>(src);
|
||||
// Check if exactly two values are in the Sequence
|
||||
if (seq.size() != 2) {
|
||||
return false;
|
||||
}
|
||||
// Check if each element is either a float or an int
|
||||
for (auto item : seq) {
|
||||
if (!py::isinstance<py::float_>(item) && !py::isinstance<py::int_>(item)) {
|
||||
/**
|
||||
* Conversion part 1 (Python->C++): convert a PyObject into a inty
|
||||
* instance or return false upon failure. The second argument
|
||||
* indicates whether implicit conversions should be applied.
|
||||
*/
|
||||
bool load(handle src, bool) {
|
||||
/* Extract PyObject from handle */
|
||||
PyObject *source = src.ptr();
|
||||
/* Try converting into a Python integer value */
|
||||
PyObject *tmp = PyNumber_Long(source);
|
||||
if (!tmp)
|
||||
return false;
|
||||
}
|
||||
/* Now try to convert into a C++ int */
|
||||
value.long_value = PyLong_AsLong(tmp);
|
||||
Py_DECREF(tmp);
|
||||
/* Ensure return code was OK (to avoid out-of-range errors etc) */
|
||||
return !(value.long_value == -1 && !PyErr_Occurred());
|
||||
}
|
||||
value.x = seq[0].cast<double>();
|
||||
value.y = seq[1].cast<double>();
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
} // namespace pybind11
|
||||
|
||||
// Bind the negate function
|
||||
PYBIND11_MODULE(docs_advanced_cast_custom, m) { m.def("negate", user_space::negate); }
|
||||
/**
|
||||
* Conversion part 2 (C++ -> Python): convert an inty instance into
|
||||
* a Python object. The second and third arguments are used to
|
||||
* indicate the return value policy and parent object (for
|
||||
* ``return_value_policy::reference_internal``) and are generally
|
||||
* ignored by implicit casters.
|
||||
*/
|
||||
static handle cast(inty src, return_value_policy /* policy */, handle /* parent */) {
|
||||
return PyLong_FromLong(src.long_value);
|
||||
}
|
||||
};
|
||||
}} // namespace PYBIND11_NAMESPACE::detail
|
||||
|
||||
.. note::
|
||||
|
||||
|
@ -114,22 +86,8 @@ type is explicitly allowed.
|
|||
that ``T`` is default-constructible (``value`` is first default constructed
|
||||
and then ``load()`` assigns to it).
|
||||
|
||||
.. note::
|
||||
For further information on the ``return_value_policy`` argument of ``cast`` refer to :ref:`return_value_policies`.
|
||||
To learn about the ``convert`` argument of ``load`` see :ref:`nonconverting_arguments`.
|
||||
|
||||
.. warning::
|
||||
|
||||
When using custom type casters, it's important to declare them consistently
|
||||
in every compilation unit of the Python extension module to satisfy the C++ One Definition Rule
|
||||
(`ODR <https://en.cppreference.com/w/cpp/language/definition>`_). Otherwise,
|
||||
in every compilation unit of the Python extension module. Otherwise,
|
||||
undefined behavior can ensue.
|
||||
|
||||
.. note::
|
||||
|
||||
Using the type hint ``Sequence[float]`` signals to static type checkers, that not only tuples may be
|
||||
passed, but any type implementing the Sequence protocol, e.g., ``list[float]``.
|
||||
Unfortunately, that loses the length information ``tuple[float, float]`` provides.
|
||||
One way of still providing some length information in type hints is using ``typing.Annotated``, e.g.,
|
||||
``Annotated[Sequence[float], 2]``, or further add libraries like
|
||||
`annotated-types <https://github.com/annotated-types/annotated-types>`_.
|
||||
|
|
|
@ -151,7 +151,7 @@ as arguments and return values, refer to the section on binding :ref:`classes`.
|
|||
+------------------------------------+---------------------------+-----------------------------------+
|
||||
| ``std::variant<...>`` | Type-safe union (C++17) | :file:`pybind11/stl.h` |
|
||||
+------------------------------------+---------------------------+-----------------------------------+
|
||||
| ``std::filesystem::path`` | STL path (C++17) [#]_ | :file:`pybind11/stl/filesystem.h` |
|
||||
| ``std::filesystem::path<T>`` | STL path (C++17) [#]_ | :file:`pybind11/stl/filesystem.h` |
|
||||
+------------------------------------+---------------------------+-----------------------------------+
|
||||
| ``std::function<...>`` | STL polymorphic function | :file:`pybind11/functional.h` |
|
||||
+------------------------------------+---------------------------+-----------------------------------+
|
||||
|
@ -167,4 +167,4 @@ as arguments and return values, refer to the section on binding :ref:`classes`.
|
|||
+------------------------------------+---------------------------+-----------------------------------+
|
||||
|
||||
.. [#] ``std::filesystem::path`` is converted to ``pathlib.Path`` and
|
||||
can be loaded from ``os.PathLike``, ``str``, and ``bytes``.
|
||||
``os.PathLike`` is converted to ``std::filesystem::path``.
|
||||
|
|
|
@ -169,8 +169,8 @@ macro must be specified at the top level (and outside of any namespaces), since
|
|||
it adds a template instantiation of ``type_caster``. If your binding code consists of
|
||||
multiple compilation units, it must be present in every file (typically via a
|
||||
common header) preceding any usage of ``std::vector<int>``. Opaque types must
|
||||
also have a corresponding ``py::class_`` declaration to associate them with a
|
||||
name in Python, and to define a set of available operations, e.g.:
|
||||
also have a corresponding ``class_`` declaration to associate them with a name
|
||||
in Python, and to define a set of available operations, e.g.:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
|
|
|
@ -64,7 +64,7 @@ helper class that is defined as follows:
|
|||
|
||||
.. code-block:: cpp
|
||||
|
||||
class PyAnimal : public Animal, py::trampoline_self_life_support {
|
||||
class PyAnimal : public Animal {
|
||||
public:
|
||||
/* Inherit the constructors */
|
||||
using Animal::Animal;
|
||||
|
@ -80,18 +80,6 @@ helper class that is defined as follows:
|
|||
}
|
||||
};
|
||||
|
||||
The ``py::trampoline_self_life_support`` base class is needed to ensure
|
||||
that a ``std::unique_ptr`` can safely be passed between Python and C++. To
|
||||
steer clear of notorious pitfalls (e.g. inheritance slicing), it is best
|
||||
practice to always use the base class, in combination with
|
||||
``py::smart_holder``.
|
||||
|
||||
.. note::
|
||||
For completeness, the base class has no effect if a holder other than
|
||||
``py::smart_holder`` used, including the default ``std::unique_ptr<T>``.
|
||||
Please think twice, though, the pitfalls are very real, and the overhead
|
||||
for using the safer ``py::smart_holder`` is very likely to be in the noise.
|
||||
|
||||
The macro :c:macro:`PYBIND11_OVERRIDE_PURE` should be used for pure virtual
|
||||
functions, and :c:macro:`PYBIND11_OVERRIDE` should be used for functions which have
|
||||
a default implementation. There are also two alternate macros
|
||||
|
@ -107,18 +95,18 @@ The binding code also needs a few minor adaptations (highlighted):
|
|||
:emphasize-lines: 2,3
|
||||
|
||||
PYBIND11_MODULE(example, m) {
|
||||
py::class_<Animal, PyAnimal /* <--- trampoline */, py::smart_holder>(m, "Animal")
|
||||
py::class_<Animal, PyAnimal /* <--- trampoline*/>(m, "Animal")
|
||||
.def(py::init<>())
|
||||
.def("go", &Animal::go);
|
||||
|
||||
py::class_<Dog, Animal, py::smart_holder>(m, "Dog")
|
||||
py::class_<Dog, Animal>(m, "Dog")
|
||||
.def(py::init<>());
|
||||
|
||||
m.def("call_go", &call_go);
|
||||
}
|
||||
|
||||
Importantly, pybind11 is made aware of the trampoline helper class by
|
||||
specifying it as an extra template argument to ``py::class_``. (This can also
|
||||
specifying it as an extra template argument to :class:`class_`. (This can also
|
||||
be combined with other template arguments such as a custom holder type; the
|
||||
order of template types does not matter). Following this, we are able to
|
||||
define a constructor as usual.
|
||||
|
@ -128,9 +116,9 @@ Bindings should be made against the actual class, not the trampoline helper clas
|
|||
.. code-block:: cpp
|
||||
:emphasize-lines: 3
|
||||
|
||||
py::class_<Animal, PyAnimal /* <--- trampoline */, py::smart_holder>(m, "Animal");
|
||||
py::class_<Animal, PyAnimal /* <--- trampoline*/>(m, "Animal");
|
||||
.def(py::init<>())
|
||||
.def("go", &Animal::go); /* <--- DO NOT USE &PyAnimal::go HERE */
|
||||
.def("go", &PyAnimal::go); /* <--- THIS IS WRONG, use &Animal::go */
|
||||
|
||||
Note, however, that the above is sufficient for allowing python classes to
|
||||
extend ``Animal``, but not ``Dog``: see :ref:`virtual_and_inheritance` for the
|
||||
|
@ -256,13 +244,13 @@ override the ``name()`` method):
|
|||
|
||||
.. code-block:: cpp
|
||||
|
||||
class PyAnimal : public Animal, py::trampoline_self_life_support {
|
||||
class PyAnimal : public Animal {
|
||||
public:
|
||||
using Animal::Animal; // Inherit constructors
|
||||
std::string go(int n_times) override { PYBIND11_OVERRIDE_PURE(std::string, Animal, go, n_times); }
|
||||
std::string name() override { PYBIND11_OVERRIDE(std::string, Animal, name, ); }
|
||||
};
|
||||
class PyDog : public Dog, py::trampoline_self_life_support {
|
||||
class PyDog : public Dog {
|
||||
public:
|
||||
using Dog::Dog; // Inherit constructors
|
||||
std::string go(int n_times) override { PYBIND11_OVERRIDE(std::string, Dog, go, n_times); }
|
||||
|
@ -284,7 +272,7 @@ declare or override any virtual methods itself:
|
|||
.. code-block:: cpp
|
||||
|
||||
class Husky : public Dog {};
|
||||
class PyHusky : public Husky, py::trampoline_self_life_support {
|
||||
class PyHusky : public Husky {
|
||||
public:
|
||||
using Husky::Husky; // Inherit constructors
|
||||
std::string go(int n_times) override { PYBIND11_OVERRIDE_PURE(std::string, Husky, go, n_times); }
|
||||
|
@ -299,15 +287,13 @@ follows:
|
|||
|
||||
.. code-block:: cpp
|
||||
|
||||
template <class AnimalBase = Animal>
|
||||
class PyAnimal : public AnimalBase, py::trampoline_self_life_support {
|
||||
template <class AnimalBase = Animal> class PyAnimal : public AnimalBase {
|
||||
public:
|
||||
using AnimalBase::AnimalBase; // Inherit constructors
|
||||
std::string go(int n_times) override { PYBIND11_OVERRIDE_PURE(std::string, AnimalBase, go, n_times); }
|
||||
std::string name() override { PYBIND11_OVERRIDE(std::string, AnimalBase, name, ); }
|
||||
};
|
||||
template <class DogBase = Dog>
|
||||
class PyDog : public PyAnimal<DogBase>, py::trampoline_self_life_support {
|
||||
template <class DogBase = Dog> class PyDog : public PyAnimal<DogBase> {
|
||||
public:
|
||||
using PyAnimal<DogBase>::PyAnimal; // Inherit constructors
|
||||
// Override PyAnimal's pure virtual go() with a non-pure one:
|
||||
|
@ -325,9 +311,9 @@ The classes are then registered with pybind11 using:
|
|||
|
||||
.. code-block:: cpp
|
||||
|
||||
py::class_<Animal, PyAnimal<>, py::smart_holder> animal(m, "Animal");
|
||||
py::class_<Dog, Animal, PyDog<>, py::smart_holder> dog(m, "Dog");
|
||||
py::class_<Husky, Dog, PyDog<Husky>, py::smart_holder> husky(m, "Husky");
|
||||
py::class_<Animal, PyAnimal<>> animal(m, "Animal");
|
||||
py::class_<Dog, Animal, PyDog<>> dog(m, "Dog");
|
||||
py::class_<Husky, Dog, PyDog<Husky>> husky(m, "Husky");
|
||||
// ... add animal, dog, husky definitions
|
||||
|
||||
Note that ``Husky`` did not require a dedicated trampoline template class at
|
||||
|
@ -513,12 +499,12 @@ an alias:
|
|||
// ...
|
||||
virtual ~Example() = default;
|
||||
};
|
||||
class PyExample : public Example, py::trampoline_self_life_support {
|
||||
class PyExample : public Example {
|
||||
public:
|
||||
using Example::Example;
|
||||
PyExample(Example &&base) : Example(std::move(base)) {}
|
||||
};
|
||||
py::class_<Example, PyExample, py::smart_holder>(m, "Example")
|
||||
py::class_<Example, PyExample>(m, "Example")
|
||||
// Returns an Example pointer. If a PyExample is needed, the Example
|
||||
// instance will be moved via the extra constructor in PyExample, above.
|
||||
.def(py::init([]() { return new Example(); }))
|
||||
|
@ -564,10 +550,9 @@ pybind11. The underlying issue is that the ``std::unique_ptr`` holder type that
|
|||
is responsible for managing the lifetime of instances will reference the
|
||||
destructor even if no deallocations ever take place. In order to expose classes
|
||||
with private or protected destructors, it is possible to override the holder
|
||||
type via a holder type argument to ``py::class_``. Pybind11 provides a helper
|
||||
class ``py::nodelete`` that disables any destructor invocations. In this case,
|
||||
it is crucial that instances are deallocated on the C++ side to avoid memory
|
||||
leaks.
|
||||
type via a holder type argument to ``class_``. Pybind11 provides a helper class
|
||||
``py::nodelete`` that disables any destructor invocations. In this case, it is
|
||||
crucial that instances are deallocated on the C++ side to avoid memory leaks.
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
|
@ -841,7 +826,8 @@ An instance can now be pickled as follows:
|
|||
always use the latest available version. Beware: failure to follow these
|
||||
instructions will cause important pybind11 memory allocation routines to be
|
||||
skipped during unpickling, which will likely lead to memory corruption
|
||||
and/or segmentation faults.
|
||||
and/or segmentation faults. Python defaults to version 3 (Python 3-3.7) and
|
||||
version 4 for Python 3.8+.
|
||||
|
||||
.. seealso::
|
||||
|
||||
|
@ -886,7 +872,7 @@ Multiple Inheritance
|
|||
|
||||
pybind11 can create bindings for types that derive from multiple base types
|
||||
(aka. *multiple inheritance*). To do so, specify all bases in the template
|
||||
arguments of the ``py::class_`` declaration:
|
||||
arguments of the ``class_`` declaration:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
|
@ -961,11 +947,11 @@ because of conflicting definitions on the external type:
|
|||
// dogs.cpp
|
||||
|
||||
// Binding for external library class:
|
||||
py::class_<pets::Pet>(m, "Pet")
|
||||
py::class<pets::Pet>(m, "Pet")
|
||||
.def("name", &pets::Pet::name);
|
||||
|
||||
// Binding for local extension class:
|
||||
py::class_<Dog, pets::Pet>(m, "Dog")
|
||||
py::class<Dog, pets::Pet>(m, "Dog")
|
||||
.def(py::init<std::string>());
|
||||
|
||||
.. code-block:: cpp
|
||||
|
@ -973,11 +959,11 @@ because of conflicting definitions on the external type:
|
|||
// cats.cpp, in a completely separate project from the above dogs.cpp.
|
||||
|
||||
// Binding for external library class:
|
||||
py::class_<pets::Pet>(m, "Pet")
|
||||
py::class<pets::Pet>(m, "Pet")
|
||||
.def("get_name", &pets::Pet::name);
|
||||
|
||||
// Binding for local extending class:
|
||||
py::class_<Cat, pets::Pet>(m, "Cat")
|
||||
py::class<Cat, pets::Pet>(m, "Cat")
|
||||
.def(py::init<std::string>());
|
||||
|
||||
.. code-block:: pycon
|
||||
|
@ -995,13 +981,13 @@ the ``py::class_`` constructor:
|
|||
.. code-block:: cpp
|
||||
|
||||
// Pet binding in dogs.cpp:
|
||||
py::class_<pets::Pet>(m, "Pet", py::module_local())
|
||||
py::class<pets::Pet>(m, "Pet", py::module_local())
|
||||
.def("name", &pets::Pet::name);
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
// Pet binding in cats.cpp:
|
||||
py::class_<pets::Pet>(m, "Pet", py::module_local())
|
||||
py::class<pets::Pet>(m, "Pet", py::module_local())
|
||||
.def("get_name", &pets::Pet::name);
|
||||
|
||||
This makes the Python-side ``dogs.Pet`` and ``cats.Pet`` into distinct classes,
|
||||
|
@ -1119,7 +1105,7 @@ described trampoline:
|
|||
virtual int foo() const { return 42; }
|
||||
};
|
||||
|
||||
class Trampoline : public A, py::trampoline_self_life_support {
|
||||
class Trampoline : public A {
|
||||
public:
|
||||
int foo() const override { PYBIND11_OVERRIDE(int, A, foo, ); }
|
||||
};
|
||||
|
@ -1129,7 +1115,7 @@ described trampoline:
|
|||
using A::foo;
|
||||
};
|
||||
|
||||
py::class_<A, Trampoline, py::smart_holder>(m, "A") // <-- `Trampoline` here
|
||||
py::class_<A, Trampoline>(m, "A") // <-- `Trampoline` here
|
||||
.def("foo", &Publicist::foo); // <-- `Publicist` here, not `Trampoline`!
|
||||
|
||||
Binding final classes
|
||||
|
@ -1210,7 +1196,7 @@ but once again each instantiation must be explicitly specified:
|
|||
T fn(V v);
|
||||
};
|
||||
|
||||
py::class_<MyClass<int>>(m, "MyClassT")
|
||||
py::class<MyClass<int>>(m, "MyClassT")
|
||||
.def("fn", &MyClass<int>::fn<std::string>);
|
||||
|
||||
Custom automatic downcasters
|
||||
|
|
|
@ -1,391 +0,0 @@
|
|||
# Double locking, deadlocking, GIL
|
||||
|
||||
[TOC]
|
||||
|
||||
## Introduction
|
||||
|
||||
### Overview
|
||||
|
||||
In concurrent programming with locks, *deadlocks* can arise when more than one
|
||||
mutex is locked at the same time, and careful attention has to be paid to lock
|
||||
ordering to avoid this. Here we will look at a common situation that occurs in
|
||||
native extensions for CPython written in C++.
|
||||
|
||||
### Deadlocks
|
||||
|
||||
A deadlock can occur when more than one thread attempts to lock more than one
|
||||
mutex, and two of the threads lock two of the mutexes in different orders. For
|
||||
example, consider mutexes `mu1` and `mu2`, and threads T1 and T2, executing:
|
||||
|
||||
| | T1 | T2 |
|
||||
|--- | ------------------- | -------------------|
|
||||
|1 | `mu1.lock()`{.good} | `mu2.lock()`{.good}|
|
||||
|2 | `mu2.lock()`{.bad} | `mu1.lock()`{.bad} |
|
||||
|3 | `/* work */` | `/* work */` |
|
||||
|4 | `mu2.unlock()` | `mu1.unlock()` |
|
||||
|5 | `mu1.unlock()` | `mu2.unlock()` |
|
||||
|
||||
Now if T1 manages to lock `mu1` and T2 manages to lock `mu2` (as indicated in
|
||||
green), then both threads will block while trying to lock the respective other
|
||||
mutex (as indicated in red), but they are also unable to release the mutex that
|
||||
they have locked (step 5).
|
||||
|
||||
**The problem** is that it is possible for one thread to attempt to lock `mu1`
|
||||
and then `mu2`, and for another thread to attempt to lock `mu2` and then `mu1`.
|
||||
Note that it does not matter if either mutex is unlocked at any intermediate
|
||||
point; what matters is only the order of any attempt to *lock* the mutexes. For
|
||||
example, the following, more complex series of operations is just as prone to
|
||||
deadlock:
|
||||
|
||||
| | T1 | T2 |
|
||||
|--- | ------------------- | -------------------|
|
||||
|1 | `mu1.lock()`{.good} | `mu1.lock()`{.good}|
|
||||
|2 | waiting for T2 | `mu2.lock()`{.good}|
|
||||
|3 | waiting for T2 | `/* work */` |
|
||||
|3 | waiting for T2 | `mu1.unlock()` |
|
||||
|3 | `mu2.lock()`{.bad} | `/* work */` |
|
||||
|3 | `/* work */` | `mu1.lock()`{.bad} |
|
||||
|3 | `/* work */` | `/* work */` |
|
||||
|4 | `mu2.unlock()` | `mu1.unlock()` |
|
||||
|5 | `mu1.unlock()` | `mu2.unlock()` |
|
||||
|
||||
When the mutexes involved in a locking sequence are known at compile-time, then
|
||||
avoiding deadlocks is “merely” a matter of arranging the lock
|
||||
operations carefully so as to only occur in one single, fixed order. However, it
|
||||
is also possible for mutexes to only be determined at runtime. A typical example
|
||||
of this is a database where each row has its own mutex. An operation that
|
||||
modifies two rows in a single transaction (e.g. “transferring an amount
|
||||
from one account to another”) must lock two row mutexes, but the locking
|
||||
order cannot be established at compile time. In this case, a dynamic
|
||||
“deadlock avoidance algorithm” is needed. (In C++, `std::lock`
|
||||
provides such an algorithm. An algorithm might use a non-blocking `try_lock`
|
||||
operation on a mutex, which can either succeed or fail to lock the mutex, but
|
||||
returns without blocking.)
|
||||
|
||||
Conceptually, one could also consider it a deadlock if _the same_ thread
|
||||
attempts to lock a mutex that it has already locked (e.g. when some locked
|
||||
operation accidentally recurses into itself): `mu.lock();`{.good}
|
||||
`mu.lock();`{.bad} However, this is a slightly separate issue: Typical mutexes
|
||||
are either of _recursive_ or _non-recursive_ kind. A recursive mutex allows
|
||||
repeated locking and requires balanced unlocking. A non-recursive mutex can be
|
||||
implemented more efficiently, and/but for efficiency reasons does not actually
|
||||
guarantee a deadlock on second lock. Instead, the API simply forbids such use,
|
||||
making it a precondition that the thread not already hold the mutex, with
|
||||
undefined behaviour on violation.
|
||||
|
||||
### “Once” initialization
|
||||
|
||||
A common programming problem is to have an operation happen precisely once, even
|
||||
if requested concurrently. While it is clear that we need to track in some
|
||||
shared state somewhere whether the operation has already happened, it is worth
|
||||
noting that this state only ever transitions, once, from `false` to `true`. This
|
||||
is considerably simpler than a general shared state that can change values
|
||||
arbitrarily. Next, we also need a mechanism for all but one thread to block
|
||||
until the initialization has completed, which we can provide with a mutex. The
|
||||
simplest solution just always locks the mutex:
|
||||
|
||||
```c++
|
||||
// The "once" mechanism:
|
||||
constinit absl::Mutex mu(absl::kConstInit);
|
||||
constinit bool init_done = false;
|
||||
|
||||
// The operation of interest:
|
||||
void f();
|
||||
|
||||
void InitOnceNaive() {
|
||||
absl::MutexLock lock(&mu);
|
||||
if (!init_done) {
|
||||
f();
|
||||
init_done = true;
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
This works, but the efficiency-minded reader will observe that once the
|
||||
operation has completed, all future lock contention on the mutex is
|
||||
unnecessary. This leads to the (in)famous “double-locking”
|
||||
algorithm, which was historically hard to write correctly. The idea is to check
|
||||
the boolean *before* locking the mutex, and avoid locking if the operation has
|
||||
already completed. However, accessing shared state concurrently when at least
|
||||
one access is a write is prone to causing a data race and needs to be done
|
||||
according to an appropriate concurrent programming model. In C++ we use atomic
|
||||
variables:
|
||||
|
||||
```c++
|
||||
// The "once" mechanism:
|
||||
constinit absl::Mutex mu(absl::kConstInit);
|
||||
constinit std::atomic<bool> init_done = false;
|
||||
|
||||
// The operation of interest:
|
||||
void f();
|
||||
|
||||
void InitOnceWithFastPath() {
|
||||
if (!init_done.load(std::memory_order_acquire)) {
|
||||
absl::MutexLock lock(&mu);
|
||||
if (!init_done.load(std::memory_order_relaxed)) {
|
||||
f();
|
||||
init_done.store(true, std::memory_order_release);
|
||||
}
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
Checking the flag now happens without holding the mutex lock, and if the
|
||||
operation has already completed, we return immediately. After locking the mutex,
|
||||
we need to check the flag again, since multiple threads can reach this point.
|
||||
|
||||
*Atomic details.* Since the atomic flag variable is accessed concurrently, we
|
||||
have to think about the memory order of the accesses. There are two separate
|
||||
cases: The first, outer check outside the mutex lock, and the second, inner
|
||||
check under the lock. The outer check and the flag update form an
|
||||
acquire/release pair: *if* the load sees the value `true` (which must have been
|
||||
written by the store operation), then it also sees everything that happened
|
||||
before the store, namely the operation `f()`. By contrast, the inner check can
|
||||
use relaxed memory ordering, since in that case the mutex operations provide the
|
||||
necessary ordering: if the inner load sees the value `true`, it happened after
|
||||
the `lock()`, which happened after the `unlock()`, which happened after the
|
||||
store.
|
||||
|
||||
The C++ standard library, and Abseil, provide a ready-made solution of this
|
||||
algorithm called `std::call_once`/`absl::call_once`. (The interface is the same,
|
||||
but the Abseil implementation is possibly better.)
|
||||
|
||||
```c++
|
||||
// The "once" mechanism:
|
||||
constinit absl::once_flag init_flag;
|
||||
|
||||
// The operation of interest:
|
||||
void f();
|
||||
|
||||
void InitOnceWithCallOnce() {
|
||||
absl::call_once(once_flag, f);
|
||||
}
|
||||
```
|
||||
|
||||
Even though conceptually this is performing the same algorithm, this
|
||||
implementation has some considerable advantages: The `once_flag` type is a small
|
||||
and trivial, integer-like type and is trivially destructible. Not only does it
|
||||
take up less space than a mutex, it also generates less code since it does not
|
||||
have to run a destructor, which would need to be added to the program's global
|
||||
destructor list.
|
||||
|
||||
The final clou comes with the C++ semantics of a `static` variable declared at
|
||||
block scope: According to [[stmt.dcl]](https://eel.is/c++draft/stmt.dcl#3):
|
||||
|
||||
> Dynamic initialization of a block variable with static storage duration or
|
||||
> thread storage duration is performed the first time control passes through its
|
||||
> declaration; such a variable is considered initialized upon the completion of
|
||||
> its initialization. [...] If control enters the declaration concurrently while
|
||||
> the variable is being initialized, the concurrent execution shall wait for
|
||||
> completion of the initialization.
|
||||
|
||||
This is saying that the initialization of a local, `static` variable precisely
|
||||
has the “once” semantics that we have been discussing. We can
|
||||
therefore write the above example as follows:
|
||||
|
||||
```c++
|
||||
// The operation of interest:
|
||||
void f();
|
||||
|
||||
void InitOnceWithStatic() {
|
||||
static int unused = (f(), 0);
|
||||
}
|
||||
```
|
||||
|
||||
This approach is by far the simplest and easiest, but the big difference is that
|
||||
the mutex (or mutex-like object) in this implementation is no longer visible or
|
||||
in the user’s control. This is perfectly fine if the initializer is
|
||||
simple, but if the initializer itself attempts to lock any other mutex
|
||||
(including by initializing another static variable!), then we have no control
|
||||
over the lock ordering!
|
||||
|
||||
Finally, you may have noticed the `constinit`s around the earlier code. Both
|
||||
`constinit` and `constexpr` specifiers on a declaration mean that the variable
|
||||
is *constant-initialized*, which means that no initialization is performed at
|
||||
runtime (the initial value is already known at compile time). This in turn means
|
||||
that a static variable guard mutex may not be needed, and static initialization
|
||||
never blocks. The difference between the two is that a `constexpr`-specified
|
||||
variable is also `const`, and a variable cannot be `constexpr` if it has a
|
||||
non-trivial destructor. Such a destructor also means that the guard mutex is
|
||||
needed after all, since the destructor must be registered to run at exit,
|
||||
conditionally on initialization having happened.
|
||||
|
||||
## Python, CPython, GIL
|
||||
|
||||
With CPython, a Python program can call into native code. To this end, the
|
||||
native code registers callback functions with the Python runtime via the CPython
|
||||
API. In order to ensure that the internal state of the Python runtime remains
|
||||
consistent, there is a single, shared mutex called the “global interpreter
|
||||
lock”, or GIL for short. Upon entry of one of the user-provided callback
|
||||
functions, the GIL is locked (or “held”), so that no other mutations
|
||||
of the Python runtime state can occur until the native callback returns.
|
||||
|
||||
Many native extensions do not interact with the Python runtime for at least some
|
||||
part of them, and so it is common for native extensions to _release_ the GIL, do
|
||||
some work, and then reacquire the GIL before returning. Similarly, when code is
|
||||
generally not holding the GIL but needs to interact with the runtime briefly, it
|
||||
will first reacquire the GIL. The GIL is reentrant, and constructions to acquire
|
||||
and subsequently release the GIL are common, and often don't worry about whether
|
||||
the GIL is already held.
|
||||
|
||||
If the native code is written in C++ and contains local, `static` variables,
|
||||
then we are now dealing with at least _two_ mutexes: the static variable guard
|
||||
mutex, and the GIL from CPython.
|
||||
|
||||
A common problem in such code is an operation with “only once”
|
||||
semantics that also ends up requiring the GIL to be held at some point. As per
|
||||
the above description of “once”-style techniques, one might find a
|
||||
static variable:
|
||||
|
||||
```c++
|
||||
// CPython callback, assumes that the GIL is held on entry.
|
||||
PyObject* InvokeWidget(PyObject* self) {
|
||||
static PyObject* impl = CreateWidget();
|
||||
return PyObject_CallOneArg(impl, self);
|
||||
}
|
||||
```
|
||||
|
||||
This seems reasonable, but bear in mind that there are two mutexes (the "guard
|
||||
mutex" and "the GIL"), and we must think about the lock order. Otherwise, if the
|
||||
callback is called from multiple threads, a deadlock may ensue.
|
||||
|
||||
Let us consider what we can see here: On entry, the GIL is already locked, and
|
||||
we are locking the guard mutex. This is one lock order. Inside the initializer
|
||||
`CreateWidget`, with both mutexes already locked, the function can freely access
|
||||
the Python runtime.
|
||||
|
||||
However, it is entirely possible that `CreateWidget` will want to release the
|
||||
GIL at one point and reacquire it later:
|
||||
|
||||
```c++
|
||||
// Assumes that the GIL is held on entry.
|
||||
// Ensures that the GIL is held on exit.
|
||||
PyObject* CreateWidget() {
|
||||
// ...
|
||||
Py_BEGIN_ALLOW_THREADS // releases GIL
|
||||
// expensive work, not accessing the Python runtime
|
||||
Py_END_ALLOW_THREADS // acquires GIL, #!
|
||||
// ...
|
||||
return result;
|
||||
}
|
||||
```
|
||||
|
||||
Now we have a second lock order: the guard mutex is locked, and then the GIL is
|
||||
locked (at `#!`). To see how this deadlocks, consider threads T1 and T2 both
|
||||
having the runtime attempt to call `InvokeWidget`. T1 locks the GIL and
|
||||
proceeds, locking the guard mutex and calling `CreateWidget`; T2 is blocked
|
||||
waiting for the GIL. Then T1 releases the GIL to do “expensive
|
||||
work”, and T2 awakes and locks the GIL. Now T2 is blocked trying to
|
||||
acquire the guard mutex, but T1 is blocked reacquiring the GIL (at `#!`).
|
||||
|
||||
In other words: if we want to support “once-called” functions that
|
||||
can arbitrarily release and reacquire the GIL, as is very common, then the only
|
||||
lock order that we can ensure is: guard mutex first, GIL second.
|
||||
|
||||
To implement this, we must rewrite our code. Naively, we could always release
|
||||
the GIL before a `static` variable with blocking initializer:
|
||||
|
||||
```c++
|
||||
// CPython callback, assumes that the GIL is held on entry.
|
||||
PyObject* InvokeWidget(PyObject* self) {
|
||||
Py_BEGIN_ALLOW_THREADS // releases GIL
|
||||
static PyObject* impl = CreateWidget();
|
||||
Py_END_ALLOW_THREADS // acquires GIL
|
||||
|
||||
return PyObject_CallOneArg(impl, self);
|
||||
}
|
||||
```
|
||||
|
||||
But similar to the `InitOnceNaive` example above, this code cycles the GIL
|
||||
(possibly descheduling the thread) even when the static variable has already
|
||||
been initialized. If we want to avoid this, we need to abandon the use of a
|
||||
static variable, since we do not control the guard mutex well enough. Instead,
|
||||
we use an operation whose mutex locking is under our control, such as
|
||||
`call_once`. For example:
|
||||
|
||||
```c++
|
||||
// CPython callback, assumes that the GIL is held on entry.
|
||||
PyObject* InvokeWidget(PyObject* self) {
|
||||
static constinit PyObject* impl = nullptr;
|
||||
static constinit std::atomic<bool> init_done = false;
|
||||
static constinit absl::once_flag init_flag;
|
||||
|
||||
if (!init_done.load(std::memory_order_acquire)) {
|
||||
Py_BEGIN_ALLOW_THREADS // releases GIL
|
||||
absl::call_once(init_flag, [&]() {
|
||||
PyGILState_STATE s = PyGILState_Ensure(); // acquires GIL
|
||||
impl = CreateWidget();
|
||||
PyGILState_Release(s); // releases GIL
|
||||
init_done.store(true, std::memory_order_release);
|
||||
});
|
||||
Py_END_ALLOW_THREADS // acquires GIL
|
||||
}
|
||||
|
||||
return PyObject_CallOneArg(impl, self);
|
||||
}
|
||||
```
|
||||
|
||||
The lock order is now always guard mutex first, GIL second. Unfortunately we
|
||||
have to duplicate the “double-checked done flag”, effectively
|
||||
leading to triple checking, because the flag state inside the `absl::once_flag`
|
||||
is not accessible to the user. In other words, we cannot ask `init_flag` whether
|
||||
it has been used yet.
|
||||
|
||||
However, we can perform one last, minor optimisation: since we assume that the
|
||||
GIL is held on entry, and again when the initializing operation returns, the GIL
|
||||
actually serializes access to our done flag variable, which therefore does not
|
||||
need to be atomic. (The difference to the previous, atomic code may be small,
|
||||
depending on the architecture. For example, on x86-64, acquire/release on a bool
|
||||
is nearly free ([demo](https://godbolt.org/z/P9vYWf4fE)).)
|
||||
|
||||
```c++
|
||||
// CPython callback, assumes that the GIL is held on entry, and indeed anywhere
|
||||
// directly in this function (i.e. the GIL can be released inside CreateWidget,
|
||||
// but must be reaqcuired when that call returns).
|
||||
PyObject* InvokeWidget(PyObject* self) {
|
||||
static constinit PyObject* impl = nullptr;
|
||||
static constinit bool init_done = false; // guarded by GIL
|
||||
static constinit absl::once_flag init_flag;
|
||||
|
||||
if (!init_done) {
|
||||
Py_BEGIN_ALLOW_THREADS // releases GIL
|
||||
// (multiple threads may enter here)
|
||||
absl::call_once(init_flag, [&]() {
|
||||
// (only one thread enters here)
|
||||
PyGILState_STATE s = PyGILState_Ensure(); // acquires GIL
|
||||
impl = CreateWidget();
|
||||
init_done = true; // (GIL is held)
|
||||
PyGILState_Release(s); // releases GIL
|
||||
});
|
||||
|
||||
Py_END_ALLOW_THREADS // acquires GIL
|
||||
}
|
||||
|
||||
return PyObject_CallOneArg(impl, self);
|
||||
}
|
||||
```
|
||||
|
||||
## Debugging tips
|
||||
|
||||
* Build with symbols.
|
||||
* <kbd>Ctrl</kbd>-<kbd>C</kbd> sends `SIGINT`, <kbd>Ctrl</kbd>-<kbd>\\</kbd>
|
||||
sends `SIGQUIT`. Both have their uses.
|
||||
* Useful `gdb` commands:
|
||||
* `py-bt` prints a Python backtrace if you are in a Python frame.
|
||||
* `thread apply all bt 10` prints the top-10 frames for each thread. A
|
||||
full backtrace can be prohibitively expensive, and the top few frames
|
||||
are often good enough.
|
||||
* `p PyGILState_Check()` shows whether a thread is holding the GIL. For
|
||||
all threads, run `thread apply all p PyGILState_Check()` to find out
|
||||
which thread is holding the GIL.
|
||||
* The `static` variable guard mutex is accessed with functions like
|
||||
`cxa_guard_acquire` (though this depends on ABI details and can vary).
|
||||
The guard mutex itself contains information about which thread is
|
||||
currently holding it.
|
||||
|
||||
## Links
|
||||
|
||||
* Article on
|
||||
[double-checked locking](https://preshing.com/20130930/double-checked-locking-is-fixed-in-cpp11/)
|
||||
* [The Deadlock Empire](https://deadlockempire.github.io/), hands-on exercises
|
||||
to construct deadlocks
|
|
@ -18,7 +18,7 @@ information, see :doc:`/compiling`.
|
|||
|
||||
.. code-block:: cmake
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.5...3.29)
|
||||
project(example)
|
||||
|
||||
find_package(pybind11 REQUIRED) # or `add_subdirectory(pybind11)`
|
||||
|
|
|
@ -368,7 +368,8 @@ Should they throw or fail to catch any exceptions in their call graph,
|
|||
the C++ runtime calls ``std::terminate()`` to abort immediately.
|
||||
|
||||
Similarly, Python exceptions raised in a class's ``__del__`` method do not
|
||||
propagate, but ``sys.unraisablehook()`` `is triggered
|
||||
propagate, but are logged by Python as an unraisable error. In Python 3.8+, a
|
||||
`system hook is triggered
|
||||
<https://docs.python.org/3/library/sys.html#sys.unraisablehook>`_
|
||||
and an auditing event is logged.
|
||||
|
||||
|
|
|
@ -81,11 +81,9 @@ The following table provides an overview of available policies:
|
|||
| | it is no longer used. Warning: undefined behavior will ensue when the C++ |
|
||||
| | side deletes an object that is still referenced and used by Python. |
|
||||
+--------------------------------------------------+----------------------------------------------------------------------------+
|
||||
| :enum:`return_value_policy::reference_internal` | If the return value is an lvalue reference or a pointer, the parent object |
|
||||
| | (the implicit ``this``, or ``self`` argument of the called method or |
|
||||
| | property) is kept alive for at least the lifespan of the return value. |
|
||||
| | **Otherwise this policy falls back to :enum:`return_value_policy::move` |
|
||||
| | (see #5528).** Internally, this policy works just like |
|
||||
| :enum:`return_value_policy::reference_internal` | Indicates that the lifetime of the return value is tied to the lifetime |
|
||||
| | of a parent object, namely the implicit ``this``, or ``self`` argument of |
|
||||
| | the called method or property. Internally, this policy works just like |
|
||||
| | :enum:`return_value_policy::reference` but additionally applies a |
|
||||
| | ``keep_alive<0, 1>`` *call policy* (described in the next section) that |
|
||||
| | prevents the parent object from being garbage collected as long as the |
|
||||
|
|
|
@ -62,11 +62,7 @@ will acquire the GIL before calling the Python callback. Similarly, the
|
|||
back into Python.
|
||||
|
||||
When writing C++ code that is called from other C++ code, if that code accesses
|
||||
Python state, it must explicitly acquire and release the GIL. A separate
|
||||
document on deadlocks [#f8]_ elaborates on a particularly subtle interaction
|
||||
with C++'s block-scope static variable initializer guard mutexes.
|
||||
|
||||
.. [#f8] See docs/advanced/deadlock.md
|
||||
Python state, it must explicitly acquire and release the GIL.
|
||||
|
||||
The classes :class:`gil_scoped_release` and :class:`gil_scoped_acquire` can be
|
||||
used to acquire and release the global interpreter lock in the body of a C++
|
||||
|
@ -80,7 +76,7 @@ could be realized as follows (important changes highlighted):
|
|||
.. code-block:: cpp
|
||||
:emphasize-lines: 8,30,31
|
||||
|
||||
class PyAnimal : public Animal, py::trampoline_self_life_support {
|
||||
class PyAnimal : public Animal {
|
||||
public:
|
||||
/* Inherit the constructors */
|
||||
using Animal::Animal;
|
||||
|
@ -98,12 +94,12 @@ could be realized as follows (important changes highlighted):
|
|||
};
|
||||
|
||||
PYBIND11_MODULE(example, m) {
|
||||
py::class_<Animal, PyAnimal, py::smart_holder> animal(m, "Animal");
|
||||
py::class_<Animal, PyAnimal> animal(m, "Animal");
|
||||
animal
|
||||
.def(py::init<>())
|
||||
.def("go", &Animal::go);
|
||||
|
||||
py::class_<Dog, py::smart_holder>(m, "Dog", animal)
|
||||
py::class_<Dog>(m, "Dog", animal)
|
||||
.def(py::init<>());
|
||||
|
||||
m.def("call_go", [](Animal *animal) -> std::string {
|
||||
|
@ -146,9 +142,6 @@ following checklist.
|
|||
destructors can sometimes get invoked in weird and unexpected circumstances as a result
|
||||
of exceptions.
|
||||
|
||||
- C++ static block-scope variable initialization that calls back into Python can
|
||||
cause deadlocks; see [#f8]_ for a detailed discussion.
|
||||
|
||||
- You should try running your code in a debug build. That will enable additional assertions
|
||||
within pybind11 that will throw exceptions on certain GIL handling errors
|
||||
(reference counting operations).
|
||||
|
@ -188,7 +181,7 @@ from Section :ref:`inheritance`.
|
|||
Suppose now that ``Pet`` bindings are defined in a module named ``basic``,
|
||||
whereas the ``Dog`` bindings are defined somewhere else. The challenge is of
|
||||
course that the variable ``pet`` is not available anymore though it is needed
|
||||
to indicate the inheritance relationship to the constructor of ``py::class_<Dog>``.
|
||||
to indicate the inheritance relationship to the constructor of ``class_<Dog>``.
|
||||
However, it can be acquired as follows:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
@ -200,7 +193,7 @@ However, it can be acquired as follows:
|
|||
.def("bark", &Dog::bark);
|
||||
|
||||
Alternatively, you can specify the base class as a template parameter option to
|
||||
``py::class_``, which performs an automated lookup of the corresponding Python
|
||||
``class_``, which performs an automated lookup of the corresponding Python
|
||||
type. Like the above code, however, this also requires invoking the ``import``
|
||||
function once to ensure that the pybind11 binding code of the module ``basic``
|
||||
has been executed:
|
||||
|
|
|
@ -1,70 +1,11 @@
|
|||
Smart pointers & ``py::class_``
|
||||
###############################
|
||||
Smart pointers
|
||||
##############
|
||||
|
||||
The binding generator for classes, ``py::class_``, can be passed a template
|
||||
type that denotes a special *holder* type that is used to manage references to
|
||||
the object. If no such holder type template argument is given, the default for
|
||||
a type ``T`` is ``std::unique_ptr<T>``.
|
||||
std::unique_ptr
|
||||
===============
|
||||
|
||||
.. note::
|
||||
|
||||
A ``py::class_`` for a given C++ type ``T`` — and all its derived types —
|
||||
can only use a single holder type.
|
||||
|
||||
|
||||
.. _smart_holder:
|
||||
|
||||
``py::smart_holder``
|
||||
====================
|
||||
|
||||
Starting with pybind11v3, ``py::smart_holder`` is built into pybind11. It is
|
||||
the recommended ``py::class_`` holder for most situations. However, for
|
||||
backward compatibility it is **not** the default holder, and there are no
|
||||
plans to make it the default holder in the future.
|
||||
|
||||
It is extremely easy to use the safer and more versatile ``py::smart_holder``:
|
||||
simply add ``py::smart_holder`` to ``py::class_``:
|
||||
|
||||
* ``py::class_<T>`` to
|
||||
|
||||
* ``py::class_<T, py::smart_holder>``.
|
||||
|
||||
.. note::
|
||||
|
||||
A shorthand, ``py::classh<T>``, is provided for
|
||||
``py::class_<T, py::smart_holder>``. The ``h`` in ``py::classh`` stands
|
||||
for **smart_holder** but is shortened for brevity, ensuring it has the
|
||||
same number of characters as ``py::class_``. This design choice facilitates
|
||||
easy experimentation with ``py::smart_holder`` without introducing
|
||||
distracting whitespace noise in diffs.
|
||||
|
||||
The ``py::smart_holder`` functionality includes the following:
|
||||
|
||||
* Support for **two-way** Python/C++ conversions for both
|
||||
``std::unique_ptr<T>`` and ``std::shared_ptr<T>`` **simultaneously**.
|
||||
|
||||
* Passing a Python object back to C++ via ``std::unique_ptr<T>``, safely
|
||||
**disowning** the Python object.
|
||||
|
||||
* Safely passing "trampoline" objects (objects with C++ virtual function
|
||||
overrides implemented in Python, see :ref:`overriding_virtuals`) via
|
||||
``std::unique_ptr<T>`` or ``std::shared_ptr<T>`` back to C++:
|
||||
associated Python objects are automatically kept alive for the lifetime
|
||||
of the smart-pointer.
|
||||
|
||||
* Full support for ``std::enable_shared_from_this`` (`cppreference
|
||||
<http://en.cppreference.com/w/cpp/memory/enable_shared_from_this>`_).
|
||||
|
||||
|
||||
``std::unique_ptr``
|
||||
===================
|
||||
|
||||
This is the default ``py::class_`` holder and works as expected in
|
||||
most situations. However, handling base-and-derived classes involves a
|
||||
``reinterpret_cast``, which is, strictly speaking, undefined behavior.
|
||||
Also note that the ``std::unique_ptr`` holder only supports passing a
|
||||
``std::unique_ptr`` from C++ to Python, but not the other way around.
|
||||
For example, the following code works as expected with ``py::class_<Example>``:
|
||||
Given a class ``Example`` with Python bindings, it's possible to return
|
||||
instances wrapped in C++11 unique pointers, like so
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
|
@ -74,50 +15,112 @@ For example, the following code works as expected with ``py::class_<Example>``:
|
|||
|
||||
m.def("create_example", &create_example);
|
||||
|
||||
However, this will fail with ``py::class_<Example>`` (but works with
|
||||
``py::class_<Example, py::smart_holder>``):
|
||||
In other words, there is nothing special that needs to be done. While returning
|
||||
unique pointers in this way is allowed, it is *illegal* to use them as function
|
||||
arguments. For instance, the following function signature cannot be processed
|
||||
by pybind11.
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
void do_something_with_example(std::unique_ptr<Example> ex) { ... }
|
||||
|
||||
.. note::
|
||||
The above signature would imply that Python needs to give up ownership of an
|
||||
object that is passed to this function, which is generally not possible (for
|
||||
instance, the object might be referenced elsewhere).
|
||||
|
||||
The ``reinterpret_cast`` mentioned above is `here
|
||||
<https://github.com/pybind/pybind11/blob/30eb39ed79d1e2eeff15219ac00773034300a5e6/include/pybind11/cast.h#L235>`_.
|
||||
For completeness: The same cast is also applied to ``py::smart_holder``,
|
||||
but that is safe, because ``py::smart_holder`` is not templated.
|
||||
std::shared_ptr
|
||||
===============
|
||||
|
||||
The binding generator for classes, :class:`class_`, can be passed a template
|
||||
type that denotes a special *holder* type that is used to manage references to
|
||||
the object. If no such holder type template argument is given, the default for
|
||||
a type named ``Type`` is ``std::unique_ptr<Type>``, which means that the object
|
||||
is deallocated when Python's reference count goes to zero.
|
||||
|
||||
``std::shared_ptr``
|
||||
===================
|
||||
|
||||
It is possible to use ``std::shared_ptr`` as the holder, for example:
|
||||
It is possible to switch to other types of reference counting wrappers or smart
|
||||
pointers, which is useful in codebases that rely on them. For instance, the
|
||||
following snippet causes ``std::shared_ptr`` to be used instead.
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
py::class_<Example, std::shared_ptr<Example> /* <- holder type */>(m, "Example");
|
||||
py::class_<Example, std::shared_ptr<Example> /* <- holder type */> obj(m, "Example");
|
||||
|
||||
Compared to using ``py::class_<Example, py::smart_holder>``, there are two noteworthy disadvantages:
|
||||
Note that any particular class can only be associated with a single holder type.
|
||||
|
||||
* Because a ``py::class_`` for a given C++ type ``T`` can only use a
|
||||
single holder type, ``std::unique_ptr<T>`` cannot even be passed from C++
|
||||
to Python. This will become apparent only at runtime, often through a
|
||||
segmentation fault.
|
||||
One potential stumbling block when using holder types is that they need to be
|
||||
applied consistently. Can you guess what's broken about the following binding
|
||||
code?
|
||||
|
||||
* Similar to the ``std::unique_ptr`` holder, the handling of base-and-derived
|
||||
classes involves a ``reinterpret_cast`` that has strictly speaking undefined
|
||||
behavior, although it works as expected in most situations.
|
||||
.. code-block:: cpp
|
||||
|
||||
class Child { };
|
||||
|
||||
class Parent {
|
||||
public:
|
||||
Parent() : child(std::make_shared<Child>()) { }
|
||||
Child *get_child() { return child.get(); } /* Hint: ** DON'T DO THIS ** */
|
||||
private:
|
||||
std::shared_ptr<Child> child;
|
||||
};
|
||||
|
||||
PYBIND11_MODULE(example, m) {
|
||||
py::class_<Child, std::shared_ptr<Child>>(m, "Child");
|
||||
|
||||
py::class_<Parent, std::shared_ptr<Parent>>(m, "Parent")
|
||||
.def(py::init<>())
|
||||
.def("get_child", &Parent::get_child);
|
||||
}
|
||||
|
||||
The following Python code will cause undefined behavior (and likely a
|
||||
segmentation fault).
|
||||
|
||||
.. code-block:: python
|
||||
|
||||
from example import Parent
|
||||
|
||||
print(Parent().get_child())
|
||||
|
||||
The problem is that ``Parent::get_child()`` returns a pointer to an instance of
|
||||
``Child``, but the fact that this instance is already managed by
|
||||
``std::shared_ptr<...>`` is lost when passing raw pointers. In this case,
|
||||
pybind11 will create a second independent ``std::shared_ptr<...>`` that also
|
||||
claims ownership of the pointer. In the end, the object will be freed **twice**
|
||||
since these shared pointers have no way of knowing about each other.
|
||||
|
||||
There are two ways to resolve this issue:
|
||||
|
||||
1. For types that are managed by a smart pointer class, never use raw pointers
|
||||
in function arguments or return values. In other words: always consistently
|
||||
wrap pointers into their designated holder types (such as
|
||||
``std::shared_ptr<...>``). In this case, the signature of ``get_child()``
|
||||
should be modified as follows:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
std::shared_ptr<Child> get_child() { return child; }
|
||||
|
||||
2. Adjust the definition of ``Child`` by specifying
|
||||
``std::enable_shared_from_this<T>`` (see cppreference_ for details) as a
|
||||
base class. This adds a small bit of information to ``Child`` that allows
|
||||
pybind11 to realize that there is already an existing
|
||||
``std::shared_ptr<...>`` and communicate with it. In this case, the
|
||||
declaration of ``Child`` should look as follows:
|
||||
|
||||
.. _cppreference: http://en.cppreference.com/w/cpp/memory/enable_shared_from_this
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
class Child : public std::enable_shared_from_this<Child> { };
|
||||
|
||||
.. _smart_pointers:
|
||||
|
||||
Custom smart pointers
|
||||
=====================
|
||||
|
||||
For custom smart pointers (e.g. ``c10::intrusive_ptr`` in pytorch), transparent
|
||||
conversions can be enabled using a macro invocation similar to the following.
|
||||
It must be declared at the top namespace level before any binding code:
|
||||
pybind11 supports ``std::unique_ptr`` and ``std::shared_ptr`` right out of the
|
||||
box. For any other custom smart pointer, transparent conversions can be enabled
|
||||
using a macro invocation similar to the following. It must be declared at the
|
||||
top namespace level before any binding code:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
|
@ -164,70 +167,8 @@ specialized:
|
|||
The above specialization informs pybind11 that the custom ``SmartPtr`` class
|
||||
provides ``.get()`` functionality via ``.getPointer()``.
|
||||
|
||||
.. note::
|
||||
|
||||
The two noteworthy disadvantages mentioned under the ``std::shared_ptr``
|
||||
section apply similarly to custom smart pointer holders, but there is no
|
||||
established safe alternative in this case.
|
||||
|
||||
.. seealso::
|
||||
|
||||
The file :file:`tests/test_smart_ptr.cpp` contains a complete example
|
||||
that demonstrates how to work with custom reference-counting holder types
|
||||
in more detail.
|
||||
|
||||
|
||||
Be careful not to accidentally undermine automatic lifetime management
|
||||
======================================================================
|
||||
|
||||
``py::class_``-wrapped objects automatically manage the lifetime of the
|
||||
wrapped C++ object, in collaboration with the chosen holder type.
|
||||
When wrapping C++ functions involving raw pointers, care needs to be taken
|
||||
to not inadvertently transfer ownership, resulting in multiple Python
|
||||
objects acting as owners, causing heap-use-after-free or double-free errors.
|
||||
For example:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
class Child { };
|
||||
|
||||
class Parent {
|
||||
public:
|
||||
Parent() : child(std::make_shared<Child>()) { }
|
||||
Child *get_child() { return child.get(); } /* DANGER */
|
||||
private:
|
||||
std::shared_ptr<Child> child;
|
||||
};
|
||||
|
||||
PYBIND11_MODULE(example, m) {
|
||||
py::class_<Child, std::shared_ptr<Child>>(m, "Child");
|
||||
|
||||
py::class_<Parent, std::shared_ptr<Parent>>(m, "Parent")
|
||||
.def(py::init<>())
|
||||
.def("get_child", &Parent::get_child); /* PROBLEM */
|
||||
}
|
||||
|
||||
The following Python code leads to undefined behavior, likely resulting in
|
||||
a segmentation fault.
|
||||
|
||||
.. code-block:: python
|
||||
|
||||
from example import Parent
|
||||
|
||||
print(Parent().get_child())
|
||||
|
||||
Part of the ``/* PROBLEM */`` here is that pybind11 falls back to using
|
||||
``return_value_policy::take_ownership`` as the default (see
|
||||
:ref:`return_value_policies`). The fact that the ``Child`` instance is
|
||||
already managed by ``std::shared_ptr<Child>`` is lost. Therefore pybind11
|
||||
will create a second independent ``std::shared_ptr<Child>`` that also
|
||||
claims ownership of the pointer, eventually leading to heap-use-after-free
|
||||
or double-free errors.
|
||||
|
||||
There are various ways to resolve this issue, either by changing
|
||||
the ``Child`` or ``Parent`` C++ implementations (e.g. using
|
||||
``std::enable_shared_from_this<Child>`` as a base class for
|
||||
``Child``, or adding a member function to ``Parent`` that returns
|
||||
``std::shared_ptr<Child>``), or if that is not feasible, by using
|
||||
``return_value_policy::reference_internal``. What is the best approach
|
||||
depends on the exact situation.
|
||||
|
|
|
@ -142,7 +142,7 @@ On Linux, the above example can be compiled using the following command:
|
|||
|
||||
.. code-block:: bash
|
||||
|
||||
$ c++ -O3 -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) example.cpp -o example$(python3 -m pybind11 --extension-suffix)
|
||||
$ c++ -O3 -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) example.cpp -o example$(python3-config --extension-suffix)
|
||||
|
||||
.. note::
|
||||
|
||||
|
|
|
@ -48,7 +48,7 @@ def generate_dummy_code_boost(nclasses=10):
|
|||
decl += "\n"
|
||||
|
||||
for cl in range(nclasses):
|
||||
decl += f"class cl{cl:03} {{\n"
|
||||
decl += "class cl%03i {\n" % cl
|
||||
decl += "public:\n"
|
||||
bindings += f' py::class_<cl{cl:03}>("cl{cl:03}")\n'
|
||||
for fn in range(nfns):
|
||||
|
@ -85,5 +85,5 @@ for codegen in [generate_dummy_code_pybind11, generate_dummy_code_boost]:
|
|||
n2 = dt.datetime.now()
|
||||
elapsed = (n2 - n1).total_seconds()
|
||||
size = os.stat("test.so").st_size
|
||||
print(f" {{{nclasses * nfns}, {elapsed:.6f}, {size}}},")
|
||||
print(" {%i, %f, %i}," % (nclasses * nfns, elapsed, size))
|
||||
print("}")
|
||||
|
|
|
@ -34,18 +34,11 @@ The binding code for ``Pet`` looks as follows:
|
|||
.def("getName", &Pet::getName);
|
||||
}
|
||||
|
||||
``py::class_`` creates bindings for a C++ *class* or *struct*-style data
|
||||
:class:`class_` creates bindings for a C++ *class* or *struct*-style data
|
||||
structure. :func:`init` is a convenience function that takes the types of a
|
||||
constructor's parameters as template arguments and wraps the corresponding
|
||||
constructor (see the :ref:`custom_constructors` section for details).
|
||||
|
||||
.. note::
|
||||
|
||||
Starting with pybind11v3, it is recommended to include `py::smart_holder`
|
||||
in most situations for safety, especially if you plan to support conversions
|
||||
to C++ smart pointers. See :ref:`smart_holder` for more information.
|
||||
|
||||
An interactive Python session demonstrating this example is shown below:
|
||||
constructor (see the :ref:`custom_constructors` section for details). An
|
||||
interactive Python session demonstrating this example is shown below:
|
||||
|
||||
.. code-block:: pycon
|
||||
|
||||
|
@ -265,7 +258,7 @@ inheritance relationship:
|
|||
|
||||
There are two different ways of indicating a hierarchical relationship to
|
||||
pybind11: the first specifies the C++ base class as an extra template
|
||||
parameter of the ``py::class_``:
|
||||
parameter of the :class:`class_`:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
|
@ -279,7 +272,7 @@ parameter of the ``py::class_``:
|
|||
.def("bark", &Dog::bark);
|
||||
|
||||
Alternatively, we can also assign a name to the previously bound ``Pet``
|
||||
``py::class_`` object and reference it when binding the ``Dog`` class:
|
||||
:class:`class_` object and reference it when binding the ``Dog`` class:
|
||||
|
||||
.. code-block:: cpp
|
||||
|
||||
|
@ -505,7 +498,7 @@ The binding code for this example looks as follows:
|
|||
|
||||
|
||||
To ensure that the nested types ``Kind`` and ``Attributes`` are created within the scope of ``Pet``, the
|
||||
``pet`` ``py::class_`` instance must be supplied to the :class:`enum_` and ``py::class_``
|
||||
``pet`` :class:`class_` instance must be supplied to the :class:`enum_` and :class:`class_`
|
||||
constructor. The :func:`enum_::export_values` function exports the enum entries
|
||||
into the parent scope, which should be skipped for newer C++11-style strongly
|
||||
typed enums.
|
||||
|
|
|
@ -18,7 +18,7 @@ A Python extension module can be created with just a few lines of code:
|
|||
|
||||
.. code-block:: cmake
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.15...3.29)
|
||||
project(example LANGUAGES CXX)
|
||||
|
||||
set(PYBIND11_FINDPYTHON ON)
|
||||
|
@ -319,11 +319,11 @@ Building with CMake
|
|||
|
||||
For C++ codebases that have an existing CMake-based build system, a Python
|
||||
extension module can be created with just a few lines of code, as seen above in
|
||||
the module section. Pybind11 currently defaults to the old mechanism, though be
|
||||
aware that CMake 3.27 removed the old mechanism, so pybind11 will automatically
|
||||
switch if the old mechanism is not available. Please opt into the new mechanism
|
||||
if at all possible. Our default may change in future versions. This is the
|
||||
minimum required:
|
||||
the module section. Pybind11 currently supports a lower minimum if you don't
|
||||
use the modern FindPython, though be aware that CMake 3.27 removed the old
|
||||
mechanism, so pybind11 will automatically switch if the old mechanism is not
|
||||
available. Please opt into the new mechanism if at all possible. Our default
|
||||
may change in future versions. This is the minimum required:
|
||||
|
||||
|
||||
|
||||
|
@ -333,9 +333,6 @@ minimum required:
|
|||
.. versionchanged:: 2.11
|
||||
CMake 3.5+ is required.
|
||||
|
||||
.. versionchanged:: 2.14
|
||||
CMake 3.15+ is required.
|
||||
|
||||
|
||||
Further information can be found at :doc:`cmake/index`.
|
||||
|
||||
|
@ -429,7 +426,7 @@ with ``PYTHON_EXECUTABLE``. For example:
|
|||
|
||||
.. code-block:: bash
|
||||
|
||||
cmake -DPYBIND11_PYTHON_VERSION=3.8 ..
|
||||
cmake -DPYBIND11_PYTHON_VERSION=3.7 ..
|
||||
|
||||
# Another method:
|
||||
cmake -DPYTHON_EXECUTABLE=/path/to/python ..
|
||||
|
@ -447,7 +444,7 @@ See the `Config file`_ docstring for details of relevant CMake variables.
|
|||
|
||||
.. code-block:: cmake
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.4...3.18)
|
||||
project(example LANGUAGES CXX)
|
||||
|
||||
find_package(pybind11 REQUIRED)
|
||||
|
@ -486,16 +483,17 @@ can refer to the same [cmake_example]_ repository for a full sample project
|
|||
FindPython mode
|
||||
---------------
|
||||
|
||||
Modern CMake (3.18.2+ ideal) added a new module called FindPython that had a
|
||||
highly improved search algorithm and modern targets and tools. If you use
|
||||
FindPython, pybind11 will detect this and use the existing targets instead:
|
||||
CMake 3.12+ (3.15+ recommended, 3.18.2+ ideal) added a new module called
|
||||
FindPython that had a highly improved search algorithm and modern targets
|
||||
and tools. If you use FindPython, pybind11 will detect this and use the
|
||||
existing targets instead:
|
||||
|
||||
.. code-block:: cmake
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.15...3.22)
|
||||
project(example LANGUAGES CXX)
|
||||
|
||||
find_package(Python 3.8 COMPONENTS Interpreter Development REQUIRED)
|
||||
find_package(Python 3.7 COMPONENTS Interpreter Development REQUIRED)
|
||||
find_package(pybind11 CONFIG REQUIRED)
|
||||
# or add_subdirectory(pybind11)
|
||||
|
||||
|
@ -543,7 +541,7 @@ available in all modes. The targets provided are:
|
|||
Just the "linking" part of pybind11:module
|
||||
|
||||
``pybind11::module``
|
||||
Everything for extension modules - ``pybind11::pybind11`` + ``Python::Module`` (FindPython) or ``pybind11::python_link_helper``
|
||||
Everything for extension modules - ``pybind11::pybind11`` + ``Python::Module`` (FindPython CMake 3.15+) or ``pybind11::python_link_helper``
|
||||
|
||||
``pybind11::embed``
|
||||
Everything for embedding the Python interpreter - ``pybind11::pybind11`` + ``Python::Python`` (FindPython) or Python libs
|
||||
|
@ -570,7 +568,7 @@ You can use these targets to build complex applications. For example, the
|
|||
|
||||
.. code-block:: cmake
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.5...3.29)
|
||||
project(example LANGUAGES CXX)
|
||||
|
||||
find_package(pybind11 REQUIRED) # or add_subdirectory(pybind11)
|
||||
|
@ -628,7 +626,7 @@ information about usage in C++, see :doc:`/advanced/embedding`.
|
|||
|
||||
.. code-block:: cmake
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.5...3.29)
|
||||
project(example LANGUAGES CXX)
|
||||
|
||||
find_package(pybind11 REQUIRED) # or add_subdirectory(pybind11)
|
||||
|
|
|
@ -302,9 +302,9 @@ CMake configure line. (Replace ``$(which python)`` with a path to python if
|
|||
your prefer.)
|
||||
|
||||
You can alternatively try ``-DPYBIND11_FINDPYTHON=ON``, which will activate the
|
||||
new CMake FindPython support instead of pybind11's custom search. Newer CMake,
|
||||
like, 3.18.2+, is recommended. You can set this in your ``CMakeLists.txt``
|
||||
before adding or finding pybind11, as well.
|
||||
new CMake FindPython support instead of pybind11's custom search. Requires
|
||||
CMake 3.12+, and 3.15+ or 3.18.2+ are even better. You can set this in your
|
||||
``CMakeLists.txt`` before adding or finding pybind11, as well.
|
||||
|
||||
Inconsistent detection of Python version in CMake and pybind11
|
||||
==============================================================
|
||||
|
@ -325,11 +325,11 @@ There are three possible solutions:
|
|||
from CMake and rely on pybind11 in detecting Python version. If this is not
|
||||
possible, the CMake machinery should be called *before* including pybind11.
|
||||
2. Set ``PYBIND11_FINDPYTHON`` to ``True`` or use ``find_package(Python
|
||||
COMPONENTS Interpreter Development)`` on modern CMake ( 3.18.2+ best).
|
||||
Pybind11 in these cases uses the new CMake FindPython instead of the old,
|
||||
deprecated search tools, and these modules are much better at finding the
|
||||
correct Python. If FindPythonLibs/Interp are not available (CMake 3.27+),
|
||||
then this will be ignored and FindPython will be used.
|
||||
COMPONENTS Interpreter Development)`` on modern CMake (3.12+, 3.15+ better,
|
||||
3.18.2+ best). Pybind11 in these cases uses the new CMake FindPython instead
|
||||
of the old, deprecated search tools, and these modules are much better at
|
||||
finding the correct Python. If FindPythonLibs/Interp are not available
|
||||
(CMake 3.27+), then this will be ignored and FindPython will be used.
|
||||
3. Set ``PYBIND11_NOPYTHON`` to ``TRUE``. Pybind11 will not search for Python.
|
||||
However, you will have to use the target-based system, and do more setup
|
||||
yourself, because it does not know about or include things that depend on
|
||||
|
|
|
@ -0,0 +1,105 @@
|
|||
.. _installing:
|
||||
|
||||
Installing the library
|
||||
######################
|
||||
|
||||
There are several ways to get the pybind11 source, which lives at
|
||||
`pybind/pybind11 on GitHub <https://github.com/pybind/pybind11>`_. The pybind11
|
||||
developers recommend one of the first three ways listed here, submodule, PyPI,
|
||||
or conda-forge, for obtaining pybind11.
|
||||
|
||||
.. _include_as_a_submodule:
|
||||
|
||||
Include as a submodule
|
||||
======================
|
||||
|
||||
When you are working on a project in Git, you can use the pybind11 repository
|
||||
as a submodule. From your git repository, use:
|
||||
|
||||
.. code-block:: bash
|
||||
|
||||
git submodule add -b stable ../../pybind/pybind11 extern/pybind11
|
||||
git submodule update --init
|
||||
|
||||
This assumes you are placing your dependencies in ``extern/``, and that you are
|
||||
using GitHub; if you are not using GitHub, use the full https or ssh URL
|
||||
instead of the relative URL ``../../pybind/pybind11`` above. Some other servers
|
||||
also require the ``.git`` extension (GitHub does not).
|
||||
|
||||
From here, you can now include ``extern/pybind11/include``, or you can use
|
||||
the various integration tools (see :ref:`compiling`) pybind11 provides directly
|
||||
from the local folder.
|
||||
|
||||
Include with PyPI
|
||||
=================
|
||||
|
||||
You can download the sources and CMake files as a Python package from PyPI
|
||||
using Pip. Just use:
|
||||
|
||||
.. code-block:: bash
|
||||
|
||||
pip install pybind11
|
||||
|
||||
This will provide pybind11 in a standard Python package format. If you want
|
||||
pybind11 available directly in your environment root, you can use:
|
||||
|
||||
.. code-block:: bash
|
||||
|
||||
pip install "pybind11[global]"
|
||||
|
||||
This is not recommended if you are installing with your system Python, as it
|
||||
will add files to ``/usr/local/include/pybind11`` and
|
||||
``/usr/local/share/cmake/pybind11``, so unless that is what you want, it is
|
||||
recommended only for use in virtual environments or your ``pyproject.toml``
|
||||
file (see :ref:`compiling`).
|
||||
|
||||
Include with conda-forge
|
||||
========================
|
||||
|
||||
You can use pybind11 with conda packaging via `conda-forge
|
||||
<https://github.com/conda-forge/pybind11-feedstock>`_:
|
||||
|
||||
.. code-block:: bash
|
||||
|
||||
conda install -c conda-forge pybind11
|
||||
|
||||
|
||||
Include with vcpkg
|
||||
==================
|
||||
You can download and install pybind11 using the Microsoft `vcpkg
|
||||
<https://github.com/Microsoft/vcpkg/>`_ dependency manager:
|
||||
|
||||
.. code-block:: bash
|
||||
|
||||
git clone https://github.com/Microsoft/vcpkg.git
|
||||
cd vcpkg
|
||||
./bootstrap-vcpkg.sh
|
||||
./vcpkg integrate install
|
||||
vcpkg install pybind11
|
||||
|
||||
The pybind11 port in vcpkg is kept up to date by Microsoft team members and
|
||||
community contributors. If the version is out of date, please `create an issue
|
||||
or pull request <https://github.com/Microsoft/vcpkg/>`_ on the vcpkg
|
||||
repository.
|
||||
|
||||
Global install with brew
|
||||
========================
|
||||
|
||||
The brew package manager (Homebrew on macOS, or Linuxbrew on Linux) has a
|
||||
`pybind11 package
|
||||
<https://github.com/Homebrew/homebrew-core/blob/master/Formula/pybind11.rb>`_.
|
||||
To install:
|
||||
|
||||
.. code-block:: bash
|
||||
|
||||
brew install pybind11
|
||||
|
||||
.. We should list Conan, and possibly a few other C++ package managers (hunter,
|
||||
.. perhaps). Conan has a very clean CMake integration that would be good to show.
|
||||
|
||||
Other options
|
||||
=============
|
||||
|
||||
Other locations you can find pybind11 are `listed here
|
||||
<https://repology.org/project/python:pybind11/versions>`_; these are maintained
|
||||
by various packagers and the community.
|
|
@ -68,8 +68,8 @@ Convenience functions converting to Python types
|
|||
|
||||
.. _extras:
|
||||
|
||||
Passing extra arguments to ``def`` or ``py::class_``
|
||||
====================================================
|
||||
Passing extra arguments to ``def`` or ``class_``
|
||||
================================================
|
||||
|
||||
.. doxygengroup:: annotations
|
||||
:members:
|
||||
|
|
|
@ -130,9 +130,9 @@ imagesize==1.4.1 \
|
|||
--hash=sha256:0d8d18d08f840c19d0ee7ca1fd82490fdc3729b7ac93f49870406ddde8ef8d8b \
|
||||
--hash=sha256:69150444affb9cb0d5cc5a92b3676f0b2fb7cd9ae39e947a5e11a36b4497cd4a
|
||||
# via sphinx
|
||||
jinja2==3.1.6 \
|
||||
--hash=sha256:0137fb05990d35f1275a587e9aee6d56da821fc83491a0fb838183be43f66d6d \
|
||||
--hash=sha256:85ece4451f492d0c13c5dd7c13a64681a86afae63a5f347908daf103ce6d2f67
|
||||
jinja2==3.1.4 \
|
||||
--hash=sha256:4a3aee7acbbe7303aede8e9648d13b8bf88a429282aa6122a993f0ac800cb369 \
|
||||
--hash=sha256:bc5dd2abb727a5319567b7a813e6a2e7318c39f4f487cfe6c89c6f9c7d25197d
|
||||
# via sphinx
|
||||
markupsafe==2.1.5 \
|
||||
--hash=sha256:00e046b6dd71aa03a41079792f8473dc494d564611a8f89bbbd7cb93295ebdcf \
|
||||
|
|
|
@ -24,8 +24,7 @@ changes are that:
|
|||
function is not available anymore.
|
||||
|
||||
Due to NumPy changes, you may experience difficulties updating to NumPy 2.
|
||||
Please see the `NumPy 2 migration guide <https://numpy.org/devdocs/numpy_2_0_migration_guide.html>`_
|
||||
for details.
|
||||
Please see the [NumPy 2 migration guide](https://numpy.org/devdocs/numpy_2_0_migration_guide.html) for details.
|
||||
For example, a more direct change could be that the default integer ``"int_"``
|
||||
(and ``"uint"``) is now ``ssize_t`` and not ``long`` (affects 64bit windows).
|
||||
|
||||
|
|
|
@ -81,10 +81,6 @@ struct dynamic_attr {};
|
|||
/// Annotation which enables the buffer protocol for a type
|
||||
struct buffer_protocol {};
|
||||
|
||||
/// Annotation which enables releasing the GIL before calling the C++ destructor of wrapped
|
||||
/// instances (pybind/pybind11#1446).
|
||||
struct release_gil_before_calling_cpp_dtor {};
|
||||
|
||||
/// Annotation which requests that a special metaclass is created for a type
|
||||
struct metaclass {
|
||||
handle value;
|
||||
|
@ -276,7 +272,7 @@ struct function_record {
|
|||
struct type_record {
|
||||
PYBIND11_NOINLINE type_record()
|
||||
: multiple_inheritance(false), dynamic_attr(false), buffer_protocol(false),
|
||||
module_local(false), is_final(false), release_gil_before_calling_cpp_dtor(false) {}
|
||||
default_holder(true), module_local(false), is_final(false) {}
|
||||
|
||||
/// Handle to the parent scope
|
||||
handle scope;
|
||||
|
@ -326,17 +322,15 @@ struct type_record {
|
|||
/// Does the class implement the buffer protocol?
|
||||
bool buffer_protocol : 1;
|
||||
|
||||
/// Is the default (unique_ptr) holder type used?
|
||||
bool default_holder : 1;
|
||||
|
||||
/// Is the class definition local to the module shared object?
|
||||
bool module_local : 1;
|
||||
|
||||
/// Is the class inheritable from python classes?
|
||||
bool is_final : 1;
|
||||
|
||||
/// Solves pybind/pybind11#1446
|
||||
bool release_gil_before_calling_cpp_dtor : 1;
|
||||
|
||||
holder_enum_t holder_enum_v = holder_enum_t::undefined;
|
||||
|
||||
PYBIND11_NOINLINE void add_base(const std::type_info &base, void *(*caster)(void *) ) {
|
||||
auto *base_info = detail::get_type_info(base, false);
|
||||
if (!base_info) {
|
||||
|
@ -346,22 +340,18 @@ struct type_record {
|
|||
+ "\" referenced unknown base type \"" + tname + "\"");
|
||||
}
|
||||
|
||||
// SMART_HOLDER_BAKEIN_FOLLOW_ON: Refine holder compatibility checks.
|
||||
bool this_has_unique_ptr_holder = (holder_enum_v == holder_enum_t::std_unique_ptr);
|
||||
bool base_has_unique_ptr_holder
|
||||
= (base_info->holder_enum_v == holder_enum_t::std_unique_ptr);
|
||||
if (this_has_unique_ptr_holder != base_has_unique_ptr_holder) {
|
||||
if (default_holder != base_info->default_holder) {
|
||||
std::string tname(base.name());
|
||||
detail::clean_type_id(tname);
|
||||
pybind11_fail("generic_type: type \"" + std::string(name) + "\" "
|
||||
+ (this_has_unique_ptr_holder ? "does not have" : "has")
|
||||
+ (default_holder ? "does not have" : "has")
|
||||
+ " a non-default holder type while its base \"" + tname + "\" "
|
||||
+ (base_has_unique_ptr_holder ? "does not" : "does"));
|
||||
+ (base_info->default_holder ? "does not" : "does"));
|
||||
}
|
||||
|
||||
bases.append((PyObject *) base_info->type);
|
||||
|
||||
#ifdef PYBIND11_BACKWARD_COMPATIBILITY_TP_DICTOFFSET
|
||||
#if PY_VERSION_HEX < 0x030B0000
|
||||
dynamic_attr |= base_info->type->tp_dictoffset != 0;
|
||||
#else
|
||||
dynamic_attr |= (base_info->type->tp_flags & Py_TPFLAGS_MANAGED_DICT) != 0;
|
||||
|
@ -613,14 +603,6 @@ struct process_attribute<module_local> : process_attribute_default<module_local>
|
|||
static void init(const module_local &l, type_record *r) { r->module_local = l.value; }
|
||||
};
|
||||
|
||||
template <>
|
||||
struct process_attribute<release_gil_before_calling_cpp_dtor>
|
||||
: process_attribute_default<release_gil_before_calling_cpp_dtor> {
|
||||
static void init(const release_gil_before_calling_cpp_dtor &, type_record *r) {
|
||||
r->release_gil_before_calling_cpp_dtor = true;
|
||||
}
|
||||
};
|
||||
|
||||
/// Process a 'prepend' attribute, putting this at the beginning of the overload chain
|
||||
template <>
|
||||
struct process_attribute<prepend> : process_attribute_default<prepend> {
|
||||
|
|
|
@ -158,7 +158,7 @@ public:
|
|||
} else {
|
||||
handle src_or_index = src;
|
||||
// PyPy: 7.3.7's 3.8 does not implement PyLong_*'s __index__ calls.
|
||||
#if defined(PYPY_VERSION)
|
||||
#if PY_VERSION_HEX < 0x03080000 || defined(PYPY_VERSION)
|
||||
object index;
|
||||
if (!PYBIND11_LONG_CHECK(src.ptr())) { // So: index_check(src.ptr())
|
||||
index = reinterpret_steal<object>(PyNumber_Index(src.ptr()));
|
||||
|
@ -343,7 +343,7 @@ public:
|
|||
#else
|
||||
// Alternate approach for CPython: this does the same as the above, but optimized
|
||||
// using the CPython API so as to avoid an unneeded attribute lookup.
|
||||
else if (auto *tp_as_number = Py_TYPE(src.ptr())->tp_as_number) {
|
||||
else if (auto *tp_as_number = src.ptr()->ob_type->tp_as_number) {
|
||||
if (PYBIND11_NB_BOOL(tp_as_number)) {
|
||||
res = (*PYBIND11_NB_BOOL(tp_as_number))(src.ptr());
|
||||
}
|
||||
|
@ -754,7 +754,6 @@ struct holder_helper {
|
|||
static auto get(const T &p) -> decltype(p.get()) { return p.get(); }
|
||||
};
|
||||
|
||||
// SMART_HOLDER_BAKEIN_FOLLOW_ON: Rewrite comment, with reference to shared_ptr specialization.
|
||||
/// Type caster for holder types like std::shared_ptr, etc.
|
||||
/// The SFINAE hook is provided to help work around the current lack of support
|
||||
/// for smart-pointer interoperability. Please consider it an implementation
|
||||
|
@ -790,10 +789,7 @@ public:
|
|||
protected:
|
||||
friend class type_caster_generic;
|
||||
void check_holder_compat() {
|
||||
// SMART_HOLDER_BAKEIN_FOLLOW_ON: Refine holder compatibility checks.
|
||||
bool inst_has_unique_ptr_holder
|
||||
= (typeinfo->holder_enum_v == holder_enum_t::std_unique_ptr);
|
||||
if (inst_has_unique_ptr_holder) {
|
||||
if (typeinfo->default_holder) {
|
||||
throw cast_error("Unable to load a custom holder type from a default-holder instance");
|
||||
}
|
||||
}
|
||||
|
@ -839,144 +835,10 @@ protected:
|
|||
holder_type holder;
|
||||
};
|
||||
|
||||
template <typename, typename SFINAE = void>
|
||||
struct copyable_holder_caster_shared_ptr_with_smart_holder_support_enabled : std::true_type {};
|
||||
|
||||
// SMART_HOLDER_BAKEIN_FOLLOW_ON: Refactor copyable_holder_caster to reduce code duplication.
|
||||
template <typename type>
|
||||
struct copyable_holder_caster<
|
||||
type,
|
||||
std::shared_ptr<type>,
|
||||
enable_if_t<copyable_holder_caster_shared_ptr_with_smart_holder_support_enabled<type>::value>>
|
||||
: public type_caster_base<type> {
|
||||
public:
|
||||
using base = type_caster_base<type>;
|
||||
static_assert(std::is_base_of<base, type_caster<type>>::value,
|
||||
"Holder classes are only supported for custom types");
|
||||
using base::base;
|
||||
using base::cast;
|
||||
using base::typeinfo;
|
||||
using base::value;
|
||||
|
||||
bool load(handle src, bool convert) {
|
||||
if (base::template load_impl<copyable_holder_caster<type, std::shared_ptr<type>>>(
|
||||
src, convert)) {
|
||||
sh_load_helper.maybe_set_python_instance_is_alias(src);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
explicit operator std::shared_ptr<type> *() {
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
pybind11_fail("Passing `std::shared_ptr<T> *` from Python to C++ is not supported "
|
||||
"(inherently unsafe).");
|
||||
}
|
||||
return std::addressof(shared_ptr_storage);
|
||||
}
|
||||
|
||||
explicit operator std::shared_ptr<type> &() {
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
shared_ptr_storage = sh_load_helper.load_as_shared_ptr(value);
|
||||
}
|
||||
return shared_ptr_storage;
|
||||
}
|
||||
|
||||
static handle
|
||||
cast(const std::shared_ptr<type> &src, return_value_policy policy, handle parent) {
|
||||
const auto *ptr = src.get();
|
||||
auto st = type_caster_base<type>::src_and_type(ptr);
|
||||
if (st.second == nullptr) {
|
||||
return handle(); // no type info: error will be set already
|
||||
}
|
||||
if (st.second->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
return smart_holder_type_caster_support::smart_holder_from_shared_ptr(
|
||||
src, policy, parent, st);
|
||||
}
|
||||
return type_caster_base<type>::cast_holder(ptr, &src);
|
||||
}
|
||||
|
||||
// This function will succeed even if the `responsible_parent` does not own the
|
||||
// wrapped C++ object directly.
|
||||
// It is the responsibility of the caller to ensure that the `responsible_parent`
|
||||
// has a `keep_alive` relationship with the owner of the wrapped C++ object, or
|
||||
// that the wrapped C++ object lives for the duration of the process.
|
||||
static std::shared_ptr<type> shared_ptr_with_responsible_parent(handle responsible_parent) {
|
||||
copyable_holder_caster loader;
|
||||
loader.load(responsible_parent, /*convert=*/false);
|
||||
assert(loader.typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder);
|
||||
return loader.sh_load_helper.load_as_shared_ptr(loader.value, responsible_parent);
|
||||
}
|
||||
|
||||
protected:
|
||||
friend class type_caster_generic;
|
||||
void check_holder_compat() {
|
||||
// SMART_HOLDER_BAKEIN_FOLLOW_ON: Refine holder compatibility checks.
|
||||
bool inst_has_unique_ptr_holder
|
||||
= (typeinfo->holder_enum_v == holder_enum_t::std_unique_ptr);
|
||||
if (inst_has_unique_ptr_holder) {
|
||||
throw cast_error("Unable to load a custom holder type from a default-holder instance");
|
||||
}
|
||||
}
|
||||
|
||||
void load_value(value_and_holder &&v_h) {
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
sh_load_helper.loaded_v_h = v_h;
|
||||
sh_load_helper.was_populated = true;
|
||||
value = sh_load_helper.get_void_ptr_or_nullptr();
|
||||
return;
|
||||
}
|
||||
if (v_h.holder_constructed()) {
|
||||
value = v_h.value_ptr();
|
||||
shared_ptr_storage = v_h.template holder<std::shared_ptr<type>>();
|
||||
return;
|
||||
}
|
||||
throw cast_error("Unable to cast from non-held to held instance (T& to Holder<T>) "
|
||||
#if !defined(PYBIND11_DETAILED_ERROR_MESSAGES)
|
||||
"(#define PYBIND11_DETAILED_ERROR_MESSAGES or compile in debug mode for "
|
||||
"type information)");
|
||||
#else
|
||||
"of type '"
|
||||
+ type_id<std::shared_ptr<type>>() + "''");
|
||||
#endif
|
||||
}
|
||||
|
||||
template <typename T = std::shared_ptr<type>,
|
||||
detail::enable_if_t<!std::is_constructible<T, const T &, type *>::value, int> = 0>
|
||||
bool try_implicit_casts(handle, bool) {
|
||||
return false;
|
||||
}
|
||||
|
||||
template <typename T = std::shared_ptr<type>,
|
||||
detail::enable_if_t<std::is_constructible<T, const T &, type *>::value, int> = 0>
|
||||
bool try_implicit_casts(handle src, bool convert) {
|
||||
for (auto &cast : typeinfo->implicit_casts) {
|
||||
copyable_holder_caster sub_caster(*cast.first);
|
||||
if (sub_caster.load(src, convert)) {
|
||||
value = cast.second(sub_caster.value);
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
sh_load_helper.loaded_v_h = sub_caster.sh_load_helper.loaded_v_h;
|
||||
} else {
|
||||
shared_ptr_storage
|
||||
= std::shared_ptr<type>(sub_caster.shared_ptr_storage, (type *) value);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool try_direct_conversions(handle) { return false; }
|
||||
|
||||
smart_holder_type_caster_support::load_helper<remove_cv_t<type>> sh_load_helper; // Const2Mutbl
|
||||
std::shared_ptr<type> shared_ptr_storage;
|
||||
};
|
||||
|
||||
/// Specialize for the common std::shared_ptr, so users don't need to
|
||||
template <typename T>
|
||||
class type_caster<std::shared_ptr<T>> : public copyable_holder_caster<T, std::shared_ptr<T>> {};
|
||||
|
||||
// SMART_HOLDER_BAKEIN_FOLLOW_ON: Rewrite comment, with reference to unique_ptr specialization.
|
||||
/// Type caster for holder types like std::unique_ptr.
|
||||
/// Please consider the SFINAE hook an implementation detail, as explained
|
||||
/// in the comment for the copyable_holder_caster.
|
||||
|
@ -992,143 +854,6 @@ struct move_only_holder_caster {
|
|||
static constexpr auto name = type_caster_base<type>::name;
|
||||
};
|
||||
|
||||
template <typename, typename SFINAE = void>
|
||||
struct move_only_holder_caster_unique_ptr_with_smart_holder_support_enabled : std::true_type {};
|
||||
|
||||
// SMART_HOLDER_BAKEIN_FOLLOW_ON: Refactor move_only_holder_caster to reduce code duplication.
|
||||
template <typename type, typename deleter>
|
||||
struct move_only_holder_caster<
|
||||
type,
|
||||
std::unique_ptr<type, deleter>,
|
||||
enable_if_t<move_only_holder_caster_unique_ptr_with_smart_holder_support_enabled<type>::value>>
|
||||
: public type_caster_base<type> {
|
||||
public:
|
||||
using base = type_caster_base<type>;
|
||||
static_assert(std::is_base_of<base, type_caster<type>>::value,
|
||||
"Holder classes are only supported for custom types");
|
||||
using base::base;
|
||||
using base::cast;
|
||||
using base::typeinfo;
|
||||
using base::value;
|
||||
|
||||
static handle
|
||||
cast(std::unique_ptr<type, deleter> &&src, return_value_policy policy, handle parent) {
|
||||
auto *ptr = src.get();
|
||||
auto st = type_caster_base<type>::src_and_type(ptr);
|
||||
if (st.second == nullptr) {
|
||||
return handle(); // no type info: error will be set already
|
||||
}
|
||||
if (st.second->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
return smart_holder_type_caster_support::smart_holder_from_unique_ptr(
|
||||
std::move(src), policy, parent, st);
|
||||
}
|
||||
return type_caster_generic::cast(st.first,
|
||||
return_value_policy::take_ownership,
|
||||
{},
|
||||
st.second,
|
||||
nullptr,
|
||||
nullptr,
|
||||
std::addressof(src));
|
||||
}
|
||||
|
||||
static handle
|
||||
cast(const std::unique_ptr<type, deleter> &src, return_value_policy policy, handle parent) {
|
||||
if (!src) {
|
||||
return none().release();
|
||||
}
|
||||
if (policy == return_value_policy::automatic) {
|
||||
policy = return_value_policy::reference_internal;
|
||||
}
|
||||
if (policy != return_value_policy::reference_internal) {
|
||||
throw cast_error("Invalid return_value_policy for const unique_ptr&");
|
||||
}
|
||||
return type_caster_base<type>::cast(src.get(), policy, parent);
|
||||
}
|
||||
|
||||
bool load(handle src, bool convert) {
|
||||
if (base::template load_impl<
|
||||
move_only_holder_caster<type, std::unique_ptr<type, deleter>>>(src, convert)) {
|
||||
sh_load_helper.maybe_set_python_instance_is_alias(src);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void load_value(value_and_holder &&v_h) {
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
sh_load_helper.loaded_v_h = v_h;
|
||||
sh_load_helper.loaded_v_h.type = typeinfo;
|
||||
sh_load_helper.was_populated = true;
|
||||
value = sh_load_helper.get_void_ptr_or_nullptr();
|
||||
return;
|
||||
}
|
||||
pybind11_fail("Passing `std::unique_ptr<T>` from Python to C++ requires `py::class_<T, "
|
||||
"py::smart_holder>` (with T = "
|
||||
+ clean_type_id(typeinfo->cpptype->name()) + ")");
|
||||
}
|
||||
|
||||
template <typename T_>
|
||||
using cast_op_type
|
||||
= conditional_t<std::is_same<typename std::remove_volatile<T_>::type,
|
||||
const std::unique_ptr<type, deleter> &>::value
|
||||
|| std::is_same<typename std::remove_volatile<T_>::type,
|
||||
const std::unique_ptr<const type, deleter> &>::value,
|
||||
const std::unique_ptr<type, deleter> &,
|
||||
std::unique_ptr<type, deleter>>;
|
||||
|
||||
explicit operator std::unique_ptr<type, deleter>() {
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
return sh_load_helper.template load_as_unique_ptr<deleter>(value);
|
||||
}
|
||||
pybind11_fail("Expected to be UNREACHABLE: " __FILE__ ":" PYBIND11_TOSTRING(__LINE__));
|
||||
}
|
||||
|
||||
explicit operator const std::unique_ptr<type, deleter> &() {
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
// Get shared_ptr to ensure that the Python object is not disowned elsewhere.
|
||||
shared_ptr_storage = sh_load_helper.load_as_shared_ptr(value);
|
||||
// Build a temporary unique_ptr that is meant to never expire.
|
||||
unique_ptr_storage = std::shared_ptr<std::unique_ptr<type, deleter>>(
|
||||
new std::unique_ptr<type, deleter>{
|
||||
sh_load_helper.template load_as_const_unique_ptr<deleter>(
|
||||
shared_ptr_storage.get())},
|
||||
[](std::unique_ptr<type, deleter> *ptr) {
|
||||
if (!ptr) {
|
||||
pybind11_fail("FATAL: `const std::unique_ptr<T, D> &` was disowned "
|
||||
"(EXPECT UNDEFINED BEHAVIOR).");
|
||||
}
|
||||
(void) ptr->release();
|
||||
delete ptr;
|
||||
});
|
||||
return *unique_ptr_storage;
|
||||
}
|
||||
pybind11_fail("Expected to be UNREACHABLE: " __FILE__ ":" PYBIND11_TOSTRING(__LINE__));
|
||||
}
|
||||
|
||||
bool try_implicit_casts(handle src, bool convert) {
|
||||
for (auto &cast : typeinfo->implicit_casts) {
|
||||
move_only_holder_caster sub_caster(*cast.first);
|
||||
if (sub_caster.load(src, convert)) {
|
||||
value = cast.second(sub_caster.value);
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
sh_load_helper.loaded_v_h = sub_caster.sh_load_helper.loaded_v_h;
|
||||
} else {
|
||||
pybind11_fail("Expected to be UNREACHABLE: " __FILE__
|
||||
":" PYBIND11_TOSTRING(__LINE__));
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool try_direct_conversions(handle) { return false; }
|
||||
|
||||
smart_holder_type_caster_support::load_helper<remove_cv_t<type>> sh_load_helper; // Const2Mutbl
|
||||
std::shared_ptr<type> shared_ptr_storage; // Serves as a pseudo lock.
|
||||
std::shared_ptr<std::unique_ptr<type, deleter>> unique_ptr_storage;
|
||||
};
|
||||
|
||||
template <typename type, typename deleter>
|
||||
class type_caster<std::unique_ptr<type, deleter>>
|
||||
: public move_only_holder_caster<type, std::unique_ptr<type, deleter>> {};
|
||||
|
@ -1138,20 +863,18 @@ using type_caster_holder = conditional_t<is_copy_constructible<holder_type>::val
|
|||
copyable_holder_caster<type, holder_type>,
|
||||
move_only_holder_caster<type, holder_type>>;
|
||||
|
||||
template <bool Value = false>
|
||||
struct always_construct_holder_value {
|
||||
template <typename T, bool Value = false>
|
||||
struct always_construct_holder {
|
||||
static constexpr bool value = Value;
|
||||
};
|
||||
|
||||
template <typename T, bool Value = false>
|
||||
struct always_construct_holder : always_construct_holder_value<Value> {};
|
||||
|
||||
/// Create a specialization for custom holder types (silently ignores std::shared_ptr)
|
||||
#define PYBIND11_DECLARE_HOLDER_TYPE(type, holder_type, ...) \
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) \
|
||||
namespace detail { \
|
||||
template <typename type> \
|
||||
struct always_construct_holder<holder_type> : always_construct_holder_value<__VA_ARGS__> {}; \
|
||||
struct always_construct_holder<holder_type> : always_construct_holder<void, ##__VA_ARGS__> { \
|
||||
}; \
|
||||
template <typename type> \
|
||||
class type_caster<holder_type, enable_if_t<!is_shared_ptr<holder_type>::value>> \
|
||||
: public type_caster_holder<type, holder_type> {}; \
|
||||
|
@ -1162,14 +885,10 @@ struct always_construct_holder : always_construct_holder_value<Value> {};
|
|||
template <typename base, typename holder>
|
||||
struct is_holder_type
|
||||
: std::is_base_of<detail::type_caster_holder<base, holder>, detail::type_caster<holder>> {};
|
||||
|
||||
// Specializations for always-supported holders:
|
||||
// Specialization for always-supported unique_ptr holders:
|
||||
template <typename base, typename deleter>
|
||||
struct is_holder_type<base, std::unique_ptr<base, deleter>> : std::true_type {};
|
||||
|
||||
template <typename base>
|
||||
struct is_holder_type<base, smart_holder> : std::true_type {};
|
||||
|
||||
#ifdef PYBIND11_DISABLE_HANDLE_TYPE_NAME_DEFAULT_IMPLEMENTATION // See PR #4888
|
||||
|
||||
// This leads to compilation errors if a specialization is missing.
|
||||
|
@ -1293,18 +1012,10 @@ template <>
|
|||
struct handle_type_name<args> {
|
||||
static constexpr auto name = const_name("*args");
|
||||
};
|
||||
template <typename T>
|
||||
struct handle_type_name<Args<T>> {
|
||||
static constexpr auto name = const_name("*args: ") + make_caster<T>::name;
|
||||
};
|
||||
template <>
|
||||
struct handle_type_name<kwargs> {
|
||||
static constexpr auto name = const_name("**kwargs");
|
||||
};
|
||||
template <typename T>
|
||||
struct handle_type_name<KWArgs<T>> {
|
||||
static constexpr auto name = const_name("**kwargs: ") + make_caster<T>::name;
|
||||
};
|
||||
template <>
|
||||
struct handle_type_name<obj_attr_accessor> {
|
||||
static constexpr auto name = const_name<obj_attr_accessor>();
|
||||
|
@ -1610,31 +1321,6 @@ object object_or_cast(T &&o) {
|
|||
return pybind11::cast(std::forward<T>(o));
|
||||
}
|
||||
|
||||
// Declared in pytypes.h:
|
||||
// Implemented here so that make_caster<T> can be used.
|
||||
template <typename D>
|
||||
template <typename T>
|
||||
str_attr_accessor object_api<D>::attr_with_type_hint(const char *key) const {
|
||||
#if !defined(__cpp_inline_variables)
|
||||
static_assert(always_false<T>::value,
|
||||
"C++17 feature __cpp_inline_variables not available: "
|
||||
"https://en.cppreference.com/w/cpp/language/static#Static_data_members");
|
||||
#endif
|
||||
object ann = annotations();
|
||||
if (ann.contains(key)) {
|
||||
throw std::runtime_error("__annotations__[\"" + std::string(key) + "\"] was set already.");
|
||||
}
|
||||
ann[key] = make_caster<T>::name.text;
|
||||
return {derived(), key};
|
||||
}
|
||||
|
||||
template <typename D>
|
||||
template <typename T>
|
||||
obj_attr_accessor object_api<D>::attr_with_type_hint(handle key) const {
|
||||
(void) attr_with_type_hint<T>(key.cast<std::string>().c_str());
|
||||
return {derived(), reinterpret_borrow<object>(key)};
|
||||
}
|
||||
|
||||
// Placeholder type for the unneeded (and dead code) static variable in the
|
||||
// PYBIND11_OVERRIDE_OVERRIDE macro
|
||||
struct override_unused {};
|
||||
|
@ -1817,7 +1503,7 @@ struct kw_only {};
|
|||
|
||||
/// \ingroup annotations
|
||||
/// Annotation indicating that all previous arguments are positional-only; the is the equivalent of
|
||||
/// an unnamed '/' argument
|
||||
/// an unnamed '/' argument (in Python 3.8)
|
||||
struct pos_only {};
|
||||
|
||||
template <typename T>
|
||||
|
@ -1878,24 +1564,15 @@ struct function_call {
|
|||
handle init_self;
|
||||
};
|
||||
|
||||
// See PR #5396 for the discussion that led to this
|
||||
template <typename Base, typename Derived, typename = void>
|
||||
struct is_same_or_base_of : std::is_same<Base, Derived> {};
|
||||
|
||||
// Only evaluate is_base_of if Derived is complete.
|
||||
// is_base_of raises a compiler error if Derived is incomplete.
|
||||
template <typename Base, typename Derived>
|
||||
struct is_same_or_base_of<Base, Derived, decltype(void(sizeof(Derived)))>
|
||||
: any_of<std::is_same<Base, Derived>, std::is_base_of<Base, Derived>> {};
|
||||
|
||||
/// Helper class which loads arguments for C++ functions called from Python
|
||||
template <typename... Args>
|
||||
class argument_loader {
|
||||
using indices = make_index_sequence<sizeof...(Args)>;
|
||||
|
||||
template <typename Arg>
|
||||
using argument_is_args = is_same_or_base_of<args, intrinsic_t<Arg>>;
|
||||
using argument_is_args = std::is_same<intrinsic_t<Arg>, args>;
|
||||
template <typename Arg>
|
||||
using argument_is_kwargs = is_same_or_base_of<kwargs, intrinsic_t<Arg>>;
|
||||
using argument_is_kwargs = std::is_same<intrinsic_t<Arg>, kwargs>;
|
||||
// Get kwargs argument position, or -1 if not present:
|
||||
static constexpr auto kwargs_pos = constexpr_last<argument_is_kwargs, Args...>();
|
||||
|
||||
|
|
|
@ -1,15 +0,0 @@
|
|||
NOTE
|
||||
----
|
||||
|
||||
The C++ code here
|
||||
|
||||
** only depends on <Python.h> **
|
||||
|
||||
and nothing else.
|
||||
|
||||
DO NOT ADD CODE WITH OTHER EXTERNAL DEPENDENCIES TO THIS DIRECTORY.
|
||||
|
||||
Read on:
|
||||
|
||||
pybind11_conduit_v1.h — Type-safe interoperability between different
|
||||
independent Python/C++ bindings systems.
|
|
@ -1,111 +0,0 @@
|
|||
// Copyright (c) 2024 The pybind Community.
|
||||
|
||||
/* The pybind11_conduit_v1 feature enables type-safe interoperability between
|
||||
|
||||
* different independent Python/C++ bindings systems,
|
||||
|
||||
* including pybind11 versions with different PYBIND11_INTERNALS_VERSION's.
|
||||
|
||||
The naming of the feature is a bit misleading:
|
||||
|
||||
* The feature is in no way tied to pybind11 internals.
|
||||
|
||||
* It just happens to originate from pybind11 and currently still lives there.
|
||||
|
||||
* The only external dependency is <Python.h>.
|
||||
|
||||
The implementation is a VERY light-weight dependency. It is designed to be
|
||||
compatible with any ISO C++11 (or higher) compiler, and does NOT require
|
||||
C++ Exception Handling to be enabled.
|
||||
|
||||
Please see https://github.com/pybind/pybind11/pull/5296 for more background.
|
||||
|
||||
The implementation involves a
|
||||
|
||||
def _pybind11_conduit_v1_(
|
||||
self,
|
||||
pybind11_platform_abi_id: bytes,
|
||||
cpp_type_info_capsule: capsule,
|
||||
pointer_kind: bytes) -> capsule
|
||||
|
||||
method that is meant to be added to Python objects wrapping C++ objects
|
||||
(e.g. pybind11::class_-wrapped types).
|
||||
|
||||
The design of the _pybind11_conduit_v1_ feature provides two layers of
|
||||
protection against C++ ABI mismatches:
|
||||
|
||||
* The first and most important layer is that the pybind11_platform_abi_id's
|
||||
must match between extensions. — This will never be perfect, but is the same
|
||||
pragmatic approach used in pybind11 since 2017
|
||||
(https://github.com/pybind/pybind11/commit/96997a4b9d4ec3d389a570604394af5d5eee2557,
|
||||
PYBIND11_INTERNALS_ID).
|
||||
|
||||
* The second layer is that the typeid(std::type_info).name()'s must match
|
||||
between extensions.
|
||||
|
||||
The implementation below (which is shorter than this comment!), serves as a
|
||||
battle-tested specification. The main API is this one function:
|
||||
|
||||
auto *cpp_pointer = pybind11_conduit_v1::get_type_pointer_ephemeral<YourType>(py_obj);
|
||||
|
||||
It is meant to be a minimalistic reference implementation, intentionally
|
||||
without comprehensive error reporting. It is expected that major bindings
|
||||
systems will roll their own, compatible implementations, potentially with
|
||||
system-specific error reporting. The essential specifications all bindings
|
||||
systems need to agree on are merely:
|
||||
|
||||
* PYBIND11_PLATFORM_ABI_ID (const char* literal).
|
||||
|
||||
* The cpp_type_info capsule (see below: a void *ptr and a const char *name).
|
||||
|
||||
* The cpp_conduit capsule (see below: a void *ptr and a const char *name).
|
||||
|
||||
* "raw_pointer_ephemeral" means: the lifetime of the pointer is the lifetime
|
||||
of the py_obj.
|
||||
|
||||
*/
|
||||
|
||||
// THIS MUST STAY AT THE TOP!
|
||||
#include "pybind11_platform_abi_id.h"
|
||||
|
||||
#include <Python.h>
|
||||
#include <typeinfo>
|
||||
|
||||
namespace pybind11_conduit_v1 {
|
||||
|
||||
inline void *get_raw_pointer_ephemeral(PyObject *py_obj, const std::type_info *cpp_type_info) {
|
||||
PyObject *cpp_type_info_capsule
|
||||
= PyCapsule_New(const_cast<void *>(static_cast<const void *>(cpp_type_info)),
|
||||
typeid(std::type_info).name(),
|
||||
nullptr);
|
||||
if (cpp_type_info_capsule == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
PyObject *cpp_conduit = PyObject_CallMethod(py_obj,
|
||||
"_pybind11_conduit_v1_",
|
||||
"yOy",
|
||||
PYBIND11_PLATFORM_ABI_ID,
|
||||
cpp_type_info_capsule,
|
||||
"raw_pointer_ephemeral");
|
||||
Py_DECREF(cpp_type_info_capsule);
|
||||
if (cpp_conduit == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
void *raw_ptr = PyCapsule_GetPointer(cpp_conduit, cpp_type_info->name());
|
||||
Py_DECREF(cpp_conduit);
|
||||
if (PyErr_Occurred()) {
|
||||
return nullptr;
|
||||
}
|
||||
return raw_ptr;
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
T *get_type_pointer_ephemeral(PyObject *py_obj) {
|
||||
void *raw_ptr = get_raw_pointer_ephemeral(py_obj, &typeid(T));
|
||||
if (raw_ptr == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
return static_cast<T *>(raw_ptr);
|
||||
}
|
||||
|
||||
} // namespace pybind11_conduit_v1
|
|
@ -1,87 +0,0 @@
|
|||
#pragma once
|
||||
|
||||
// Copyright (c) 2024 The pybind Community.
|
||||
|
||||
// To maximize reusability:
|
||||
// DO NOT ADD CODE THAT REQUIRES C++ EXCEPTION HANDLING.
|
||||
|
||||
#include "wrap_include_python_h.h"
|
||||
|
||||
// Implementation details. DO NOT USE ELSEWHERE. (Unfortunately we cannot #undef them.)
|
||||
// This is duplicated here to maximize portability.
|
||||
#define PYBIND11_PLATFORM_ABI_ID_STRINGIFY(x) #x
|
||||
#define PYBIND11_PLATFORM_ABI_ID_TOSTRING(x) PYBIND11_PLATFORM_ABI_ID_STRINGIFY(x)
|
||||
|
||||
#ifdef PYBIND11_COMPILER_TYPE
|
||||
// // To maintain backward compatibility (see PR #5439).
|
||||
# define PYBIND11_COMPILER_TYPE_LEADING_UNDERSCORE ""
|
||||
#else
|
||||
# define PYBIND11_COMPILER_TYPE_LEADING_UNDERSCORE "_"
|
||||
# if defined(__MINGW32__)
|
||||
# define PYBIND11_COMPILER_TYPE "mingw"
|
||||
# elif defined(__CYGWIN__)
|
||||
# define PYBIND11_COMPILER_TYPE "gcc_cygwin"
|
||||
# elif defined(_MSC_VER)
|
||||
# define PYBIND11_COMPILER_TYPE "msvc"
|
||||
# elif defined(__clang__) || defined(__GNUC__)
|
||||
# define PYBIND11_COMPILER_TYPE "system" // Assumed compatible with system compiler.
|
||||
# else
|
||||
# error "Unknown PYBIND11_COMPILER_TYPE: PLEASE REVISE THIS CODE."
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// PR #5439 made this macro obsolete. However, there are many manipulations of this macro in the
|
||||
// wild. Therefore, to maintain backward compatibility, it is kept around.
|
||||
#ifndef PYBIND11_STDLIB
|
||||
# define PYBIND11_STDLIB ""
|
||||
#endif
|
||||
|
||||
#ifndef PYBIND11_BUILD_ABI
|
||||
# if defined(_MSC_VER) // See PR #4953.
|
||||
# if defined(_MT) && defined(_DLL) // Corresponding to CL command line options /MD or /MDd.
|
||||
# if (_MSC_VER) / 100 == 19
|
||||
# define PYBIND11_BUILD_ABI "_md_mscver19"
|
||||
# else
|
||||
# error "Unknown major version for MSC_VER: PLEASE REVISE THIS CODE."
|
||||
# endif
|
||||
# elif defined(_MT) // Corresponding to CL command line options /MT or /MTd.
|
||||
# define PYBIND11_BUILD_ABI "_mt_mscver" PYBIND11_PLATFORM_ABI_ID_TOSTRING(_MSC_VER)
|
||||
# else
|
||||
# if (_MSC_VER) / 100 == 19
|
||||
# define PYBIND11_BUILD_ABI "_none_mscver19"
|
||||
# else
|
||||
# error "Unknown major version for MSC_VER: PLEASE REVISE THIS CODE."
|
||||
# endif
|
||||
# endif
|
||||
# elif defined(_LIBCPP_ABI_VERSION) // https://libcxx.llvm.org/DesignDocs/ABIVersioning.html
|
||||
# define PYBIND11_BUILD_ABI \
|
||||
"_libcpp_abi" PYBIND11_PLATFORM_ABI_ID_TOSTRING(_LIBCPP_ABI_VERSION)
|
||||
# elif defined(_GLIBCXX_USE_CXX11_ABI) // See PR #5439.
|
||||
# if defined(__NVCOMPILER)
|
||||
// // Assume that NVHPC is in the 1xxx ABI family.
|
||||
// // THIS ASSUMPTION IS NOT FUTURE PROOF but apparently the best we can do.
|
||||
// // Please let us know if there is a way to validate the assumption here.
|
||||
# elif !defined(__GXX_ABI_VERSION)
|
||||
# error \
|
||||
"Unknown platform or compiler (_GLIBCXX_USE_CXX11_ABI): PLEASE REVISE THIS CODE."
|
||||
# endif
|
||||
# if defined(__GXX_ABI_VERSION) && __GXX_ABI_VERSION < 1002 || __GXX_ABI_VERSION >= 2000
|
||||
# error "Unknown platform or compiler (__GXX_ABI_VERSION): PLEASE REVISE THIS CODE."
|
||||
# endif
|
||||
# define PYBIND11_BUILD_ABI \
|
||||
"_libstdcpp_gxx_abi_1xxx_use_cxx11_abi_" PYBIND11_PLATFORM_ABI_ID_TOSTRING( \
|
||||
_GLIBCXX_USE_CXX11_ABI)
|
||||
# else
|
||||
# error "Unknown platform or compiler: PLEASE REVISE THIS CODE."
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// On MSVC, debug and release builds are not ABI-compatible!
|
||||
#if defined(_MSC_VER) && defined(_DEBUG)
|
||||
# define PYBIND11_BUILD_TYPE "_debug"
|
||||
#else
|
||||
# define PYBIND11_BUILD_TYPE ""
|
||||
#endif
|
||||
|
||||
#define PYBIND11_PLATFORM_ABI_ID \
|
||||
PYBIND11_COMPILER_TYPE PYBIND11_STDLIB PYBIND11_BUILD_ABI PYBIND11_BUILD_TYPE
|
|
@ -1,72 +0,0 @@
|
|||
#pragma once
|
||||
|
||||
// Copyright (c) 2024 The pybind Community.
|
||||
|
||||
// STRONG REQUIREMENT:
|
||||
// This header is a wrapper around `#include <Python.h>`, therefore it
|
||||
// MUST BE INCLUDED BEFORE ANY STANDARD HEADERS are included.
|
||||
// See also:
|
||||
// https://docs.python.org/3/c-api/intro.html#include-files
|
||||
// Quoting from there:
|
||||
// Note: Since Python may define some pre-processor definitions which affect
|
||||
// the standard headers on some systems, you must include Python.h before
|
||||
// any standard headers are included.
|
||||
|
||||
// To maximize reusability:
|
||||
// DO NOT ADD CODE THAT REQUIRES C++ EXCEPTION HANDLING.
|
||||
|
||||
// Disable linking to pythonX_d.lib on Windows in debug mode.
|
||||
#if defined(_MSC_VER) && defined(_DEBUG) && !defined(Py_DEBUG)
|
||||
// Workaround for a VS 2022 issue.
|
||||
// See https://github.com/pybind/pybind11/pull/3497 for full context.
|
||||
// NOTE: This workaround knowingly violates the Python.h include order
|
||||
// requirement (see above).
|
||||
# include <yvals.h>
|
||||
# if _MSVC_STL_VERSION >= 143
|
||||
# include <crtdefs.h>
|
||||
# endif
|
||||
# define PYBIND11_DEBUG_MARKER
|
||||
# undef _DEBUG
|
||||
#endif
|
||||
|
||||
// Don't let Python.h #define (v)snprintf as macro because they are implemented
|
||||
// properly in Visual Studio since 2015.
|
||||
#if defined(_MSC_VER)
|
||||
# define HAVE_SNPRINTF 1
|
||||
#endif
|
||||
|
||||
#if defined(_MSC_VER)
|
||||
# pragma warning(push)
|
||||
# pragma warning(disable : 4505)
|
||||
// C4505: 'PySlice_GetIndicesEx': unreferenced local function has been removed
|
||||
#endif
|
||||
|
||||
#include <Python.h>
|
||||
#include <frameobject.h>
|
||||
#include <pythread.h>
|
||||
|
||||
#if defined(_MSC_VER)
|
||||
# pragma warning(pop)
|
||||
#endif
|
||||
|
||||
#if defined(PYBIND11_DEBUG_MARKER)
|
||||
# define _DEBUG
|
||||
# undef PYBIND11_DEBUG_MARKER
|
||||
#endif
|
||||
|
||||
// Python #defines overrides on all sorts of core functions, which
|
||||
// tends to wreak havok in C++ codebases that expect these to work
|
||||
// like regular functions (potentially with several overloads).
|
||||
#if defined(isalnum)
|
||||
# undef isalnum
|
||||
# undef isalpha
|
||||
# undef islower
|
||||
# undef isspace
|
||||
# undef isupper
|
||||
# undef tolower
|
||||
# undef toupper
|
||||
#endif
|
||||
|
||||
#if defined(copysign)
|
||||
# undef copysign
|
||||
#endif
|
|
@ -312,31 +312,7 @@ inline void traverse_offset_bases(void *valueptr,
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef Py_GIL_DISABLED
|
||||
inline void enable_try_inc_ref(PyObject *obj) {
|
||||
// TODO: Replace with PyUnstable_Object_EnableTryIncRef when available.
|
||||
// See https://github.com/python/cpython/issues/128844
|
||||
if (_Py_IsImmortal(obj)) {
|
||||
return;
|
||||
}
|
||||
for (;;) {
|
||||
Py_ssize_t shared = _Py_atomic_load_ssize_relaxed(&obj->ob_ref_shared);
|
||||
if ((shared & _Py_REF_SHARED_FLAG_MASK) != 0) {
|
||||
// Nothing to do if it's in WEAKREFS, QUEUED, or MERGED states.
|
||||
return;
|
||||
}
|
||||
if (_Py_atomic_compare_exchange_ssize(
|
||||
&obj->ob_ref_shared, &shared, shared | _Py_REF_MAYBE_WEAKREF)) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
inline bool register_instance_impl(void *ptr, instance *self) {
|
||||
#ifdef Py_GIL_DISABLED
|
||||
enable_try_inc_ref(reinterpret_cast<PyObject *>(self));
|
||||
#endif
|
||||
with_instance_map(ptr, [&](instance_map &instances) { instances.emplace(ptr, self); });
|
||||
return true; // unused, but gives the same signature as the deregister func
|
||||
}
|
||||
|
@ -457,8 +433,6 @@ inline void clear_instance(PyObject *self) {
|
|||
if (instance->owned || v_h.holder_constructed()) {
|
||||
v_h.type->dealloc(v_h);
|
||||
}
|
||||
} else if (v_h.holder_constructed()) {
|
||||
v_h.type->dealloc(v_h); // Disowned instance.
|
||||
}
|
||||
}
|
||||
// Deallocate the value/holder layout internals:
|
||||
|
@ -494,9 +468,19 @@ extern "C" inline void pybind11_object_dealloc(PyObject *self) {
|
|||
|
||||
type->tp_free(self);
|
||||
|
||||
#if PY_VERSION_HEX < 0x03080000
|
||||
// `type->tp_dealloc != pybind11_object_dealloc` means that we're being called
|
||||
// as part of a derived type's dealloc, in which case we're not allowed to decref
|
||||
// the type here. For cross-module compatibility, we shouldn't compare directly
|
||||
// with `pybind11_object_dealloc`, but with the common one stashed in internals.
|
||||
auto pybind11_object_type = (PyTypeObject *) get_internals().instance_base;
|
||||
if (type->tp_dealloc == pybind11_object_type->tp_dealloc)
|
||||
Py_DECREF(type);
|
||||
#else
|
||||
// This was not needed before Python 3.8 (Python issue 35810)
|
||||
// https://github.com/pybind/pybind11/issues/1946
|
||||
Py_DECREF(type);
|
||||
#endif
|
||||
}
|
||||
|
||||
std::string error_string();
|
||||
|
@ -576,7 +560,7 @@ extern "C" inline int pybind11_clear(PyObject *self) {
|
|||
inline void enable_dynamic_attributes(PyHeapTypeObject *heap_type) {
|
||||
auto *type = &heap_type->ht_type;
|
||||
type->tp_flags |= Py_TPFLAGS_HAVE_GC;
|
||||
#ifdef PYBIND11_BACKWARD_COMPATIBILITY_TP_DICTOFFSET
|
||||
#if PY_VERSION_HEX < 0x030B0000
|
||||
type->tp_dictoffset = type->tp_basicsize; // place dict at the end
|
||||
type->tp_basicsize += (ssize_t) sizeof(PyObject *); // and allocate enough space for it
|
||||
#else
|
||||
|
@ -609,9 +593,9 @@ extern "C" inline int pybind11_getbuffer(PyObject *obj, Py_buffer *view, int fla
|
|||
return -1;
|
||||
}
|
||||
std::memset(view, 0, sizeof(Py_buffer));
|
||||
std::unique_ptr<buffer_info> info = nullptr;
|
||||
buffer_info *info = nullptr;
|
||||
try {
|
||||
info.reset(tinfo->get_buffer(obj, tinfo->get_buffer_data));
|
||||
info = tinfo->get_buffer(obj, tinfo->get_buffer_data);
|
||||
} catch (...) {
|
||||
try_translate_exceptions();
|
||||
raise_from(PyExc_BufferError, "Error getting buffer");
|
||||
|
@ -622,72 +606,29 @@ extern "C" inline int pybind11_getbuffer(PyObject *obj, Py_buffer *view, int fla
|
|||
}
|
||||
|
||||
if ((flags & PyBUF_WRITABLE) == PyBUF_WRITABLE && info->readonly) {
|
||||
delete info;
|
||||
// view->obj = nullptr; // Was just memset to 0, so not necessary
|
||||
set_error(PyExc_BufferError, "Writable buffer requested for readonly storage");
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Fill in all the information, and then downgrade as requested by the caller, or raise an
|
||||
// error if that's not possible.
|
||||
view->obj = obj;
|
||||
view->ndim = 1;
|
||||
view->internal = info;
|
||||
view->buf = info->ptr;
|
||||
view->itemsize = info->itemsize;
|
||||
view->len = view->itemsize;
|
||||
for (auto s : info->shape) {
|
||||
view->len *= s;
|
||||
}
|
||||
view->ndim = static_cast<int>(info->ndim);
|
||||
view->shape = info->shape.data();
|
||||
view->strides = info->strides.data();
|
||||
view->readonly = static_cast<int>(info->readonly);
|
||||
if ((flags & PyBUF_FORMAT) == PyBUF_FORMAT) {
|
||||
view->format = const_cast<char *>(info->format.c_str());
|
||||
}
|
||||
|
||||
// Note, all contiguity flags imply PyBUF_STRIDES and lower.
|
||||
if ((flags & PyBUF_C_CONTIGUOUS) == PyBUF_C_CONTIGUOUS) {
|
||||
if (PyBuffer_IsContiguous(view, 'C') == 0) {
|
||||
std::memset(view, 0, sizeof(Py_buffer));
|
||||
set_error(PyExc_BufferError,
|
||||
"C-contiguous buffer requested for discontiguous storage");
|
||||
return -1;
|
||||
}
|
||||
} else if ((flags & PyBUF_F_CONTIGUOUS) == PyBUF_F_CONTIGUOUS) {
|
||||
if (PyBuffer_IsContiguous(view, 'F') == 0) {
|
||||
std::memset(view, 0, sizeof(Py_buffer));
|
||||
set_error(PyExc_BufferError,
|
||||
"Fortran-contiguous buffer requested for discontiguous storage");
|
||||
return -1;
|
||||
}
|
||||
} else if ((flags & PyBUF_ANY_CONTIGUOUS) == PyBUF_ANY_CONTIGUOUS) {
|
||||
if (PyBuffer_IsContiguous(view, 'A') == 0) {
|
||||
std::memset(view, 0, sizeof(Py_buffer));
|
||||
set_error(PyExc_BufferError, "Contiguous buffer requested for discontiguous storage");
|
||||
return -1;
|
||||
}
|
||||
|
||||
} else if ((flags & PyBUF_STRIDES) != PyBUF_STRIDES) {
|
||||
// If no strides are requested, the buffer must be C-contiguous.
|
||||
// https://docs.python.org/3/c-api/buffer.html#contiguity-requests
|
||||
if (PyBuffer_IsContiguous(view, 'C') == 0) {
|
||||
std::memset(view, 0, sizeof(Py_buffer));
|
||||
set_error(PyExc_BufferError,
|
||||
"C-contiguous buffer requested for discontiguous storage");
|
||||
return -1;
|
||||
}
|
||||
|
||||
view->strides = nullptr;
|
||||
|
||||
// Since this is a contiguous buffer, it can also pretend to be 1D.
|
||||
if ((flags & PyBUF_ND) != PyBUF_ND) {
|
||||
view->shape = nullptr;
|
||||
view->ndim = 0;
|
||||
}
|
||||
if ((flags & PyBUF_STRIDES) == PyBUF_STRIDES) {
|
||||
view->ndim = (int) info->ndim;
|
||||
view->strides = info->strides.data();
|
||||
view->shape = info->shape.data();
|
||||
}
|
||||
|
||||
// Set these after all checks so they don't leak out into the caller, and can be automatically
|
||||
// cleaned up on error.
|
||||
view->buf = info->ptr;
|
||||
view->internal = info.release();
|
||||
view->obj = obj;
|
||||
Py_INCREF(view->obj);
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -9,18 +9,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <pybind11/conduit/wrap_include_python_h.h>
|
||||
#if PY_VERSION_HEX < 0x03080000
|
||||
# error "PYTHON < 3.8 IS UNSUPPORTED. pybind11 v2.13 was the last to support Python 3.7."
|
||||
#endif
|
||||
|
||||
#define PYBIND11_VERSION_MAJOR 3
|
||||
#define PYBIND11_VERSION_MINOR 0
|
||||
#define PYBIND11_VERSION_PATCH 0.dev1
|
||||
#define PYBIND11_VERSION_MAJOR 2
|
||||
#define PYBIND11_VERSION_MINOR 13
|
||||
#define PYBIND11_VERSION_PATCH 6
|
||||
|
||||
// Similar to Python's convention: https://docs.python.org/3/c-api/apiabiversion.html
|
||||
// Additional convention: 0xD = dev
|
||||
#define PYBIND11_VERSION_HEX 0x030000D1
|
||||
#define PYBIND11_VERSION_HEX 0x020D0600
|
||||
|
||||
// Define some generic pybind11 helper macros for warning management.
|
||||
//
|
||||
|
@ -46,7 +41,7 @@
|
|||
# define PYBIND11_COMPILER_CLANG
|
||||
# define PYBIND11_PRAGMA(...) _Pragma(#__VA_ARGS__)
|
||||
# define PYBIND11_WARNING_PUSH PYBIND11_PRAGMA(clang diagnostic push)
|
||||
# define PYBIND11_WARNING_POP PYBIND11_PRAGMA(clang diagnostic pop)
|
||||
# define PYBIND11_WARNING_POP PYBIND11_PRAGMA(clang diagnostic push)
|
||||
#elif defined(__GNUC__)
|
||||
# define PYBIND11_COMPILER_GCC
|
||||
# define PYBIND11_PRAGMA(...) _Pragma(#__VA_ARGS__)
|
||||
|
@ -169,6 +164,14 @@
|
|||
# endif
|
||||
#endif
|
||||
|
||||
#if !defined(PYBIND11_EXPORT_EXCEPTION)
|
||||
# if defined(__apple_build_version__)
|
||||
# define PYBIND11_EXPORT_EXCEPTION PYBIND11_EXPORT
|
||||
# else
|
||||
# define PYBIND11_EXPORT_EXCEPTION
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// For CUDA, GCC7, GCC8:
|
||||
// PYBIND11_NOINLINE_FORCED is incompatible with `-Wattributes -Werror`.
|
||||
// When defining PYBIND11_NOINLINE_FORCED, it is best to also use `-Wno-attributes`.
|
||||
|
@ -209,6 +212,31 @@
|
|||
# define PYBIND11_MAYBE_UNUSED __attribute__((__unused__))
|
||||
#endif
|
||||
|
||||
/* Don't let Python.h #define (v)snprintf as macro because they are implemented
|
||||
properly in Visual Studio since 2015. */
|
||||
#if defined(_MSC_VER)
|
||||
# define HAVE_SNPRINTF 1
|
||||
#endif
|
||||
|
||||
/// Include Python header, disable linking to pythonX_d.lib on Windows in debug mode
|
||||
#if defined(_MSC_VER)
|
||||
PYBIND11_WARNING_PUSH
|
||||
PYBIND11_WARNING_DISABLE_MSVC(4505)
|
||||
// C4505: 'PySlice_GetIndicesEx': unreferenced local function has been removed (PyPy only)
|
||||
# if defined(_DEBUG) && !defined(Py_DEBUG)
|
||||
// Workaround for a VS 2022 issue.
|
||||
// NOTE: This workaround knowingly violates the Python.h include order requirement:
|
||||
// https://docs.python.org/3/c-api/intro.html#include-files
|
||||
// See https://github.com/pybind/pybind11/pull/3497 for full context.
|
||||
# include <yvals.h>
|
||||
# if _MSVC_STL_VERSION >= 143
|
||||
# include <crtdefs.h>
|
||||
# endif
|
||||
# define PYBIND11_DEBUG_MARKER
|
||||
# undef _DEBUG
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// https://en.cppreference.com/w/c/chrono/localtime
|
||||
#if defined(__STDC_LIB_EXT1__) && !defined(__STDC_WANT_LIB_EXT1__)
|
||||
# define __STDC_WANT_LIB_EXT1__
|
||||
|
@ -243,14 +271,46 @@
|
|||
# endif
|
||||
#endif
|
||||
|
||||
#include <Python.h>
|
||||
#if PY_VERSION_HEX < 0x03070000
|
||||
# error "PYTHON < 3.7 IS UNSUPPORTED. pybind11 v2.12 was the last to support Python 3.6."
|
||||
#endif
|
||||
#include <frameobject.h>
|
||||
#include <pythread.h>
|
||||
|
||||
/* Python #defines overrides on all sorts of core functions, which
|
||||
tends to weak havok in C++ codebases that expect these to work
|
||||
like regular functions (potentially with several overloads) */
|
||||
#if defined(isalnum)
|
||||
# undef isalnum
|
||||
# undef isalpha
|
||||
# undef islower
|
||||
# undef isspace
|
||||
# undef isupper
|
||||
# undef tolower
|
||||
# undef toupper
|
||||
#endif
|
||||
|
||||
#if defined(copysign)
|
||||
# undef copysign
|
||||
#endif
|
||||
|
||||
#if defined(PYBIND11_NUMPY_1_ONLY)
|
||||
# define PYBIND11_INTERNAL_NUMPY_1_ONLY_DETECTED
|
||||
#endif
|
||||
|
||||
#if (defined(PYPY_VERSION) || defined(GRAALVM_PYTHON)) && !defined(PYBIND11_SIMPLE_GIL_MANAGEMENT)
|
||||
#if defined(PYPY_VERSION) && !defined(PYBIND11_SIMPLE_GIL_MANAGEMENT)
|
||||
# define PYBIND11_SIMPLE_GIL_MANAGEMENT
|
||||
#endif
|
||||
|
||||
#if defined(_MSC_VER)
|
||||
# if defined(PYBIND11_DEBUG_MARKER)
|
||||
# define _DEBUG
|
||||
# undef PYBIND11_DEBUG_MARKER
|
||||
# endif
|
||||
PYBIND11_WARNING_POP
|
||||
#endif
|
||||
|
||||
#include <cstddef>
|
||||
#include <cstring>
|
||||
#include <exception>
|
||||
|
@ -269,17 +329,6 @@
|
|||
# endif
|
||||
#endif
|
||||
|
||||
// For libc++, the exceptions should be exported,
|
||||
// otherwise, the exception translation would be incorrect.
|
||||
// IMPORTANT: This code block must stay BELOW the #include <exception> above (see PR #5390).
|
||||
#if !defined(PYBIND11_EXPORT_EXCEPTION)
|
||||
# if defined(_LIBCPP_EXCEPTION)
|
||||
# define PYBIND11_EXPORT_EXCEPTION PYBIND11_EXPORT
|
||||
# else
|
||||
# define PYBIND11_EXPORT_EXCEPTION
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// Must be after including <version> or one of the other headers specified by the standard
|
||||
#if defined(__cpp_lib_char8_t) && __cpp_lib_char8_t >= 201811L
|
||||
# define PYBIND11_HAS_U8STRING
|
||||
|
@ -338,20 +387,6 @@
|
|||
#define PYBIND11_CONCAT(first, second) first##second
|
||||
#define PYBIND11_ENSURE_INTERNALS_READY pybind11::detail::get_internals();
|
||||
|
||||
#if !defined(GRAALVM_PYTHON)
|
||||
# define PYBIND11_PYCFUNCTION_GET_DOC(func) ((func)->m_ml->ml_doc)
|
||||
# define PYBIND11_PYCFUNCTION_SET_DOC(func, doc) \
|
||||
do { \
|
||||
(func)->m_ml->ml_doc = (doc); \
|
||||
} while (0)
|
||||
#else
|
||||
# define PYBIND11_PYCFUNCTION_GET_DOC(func) (GraalPyCFunction_GetDoc((PyObject *) (func)))
|
||||
# define PYBIND11_PYCFUNCTION_SET_DOC(func, doc) \
|
||||
do { \
|
||||
GraalPyCFunction_SetDoc((PyObject *) (func), (doc)); \
|
||||
} while (0)
|
||||
#endif
|
||||
|
||||
#define PYBIND11_CHECK_PYTHON_VERSION \
|
||||
{ \
|
||||
const char *compiled_ver \
|
||||
|
@ -605,8 +640,6 @@ struct instance {
|
|||
bool simple_instance_registered : 1;
|
||||
/// If true, get_internals().patients has an entry for this object
|
||||
bool has_patients : 1;
|
||||
/// If true, this Python object needs to be kept alive for the lifetime of the C++ value.
|
||||
bool is_alias : 1;
|
||||
|
||||
/// Initializes all of the above type/values/holders data (but not the instance values
|
||||
/// themselves)
|
||||
|
@ -629,14 +662,6 @@ struct instance {
|
|||
static_assert(std::is_standard_layout<instance>::value,
|
||||
"Internal error: `pybind11::detail::instance` is not standard layout!");
|
||||
|
||||
// Some older compilers (e.g. gcc 9.4.0) require
|
||||
// static_assert(always_false<T>::value, "...");
|
||||
// instead of
|
||||
// static_assert(false, "...");
|
||||
// to trigger the static_assert() in a template only if it is actually instantiated.
|
||||
template <typename>
|
||||
struct always_false : std::false_type {};
|
||||
|
||||
/// from __cpp_future__ import (convenient aliases from C++14/17)
|
||||
#if defined(PYBIND11_CPP14)
|
||||
using std::conditional_t;
|
||||
|
@ -1103,14 +1128,14 @@ struct overload_cast_impl {
|
|||
}
|
||||
|
||||
template <typename Return, typename Class>
|
||||
constexpr auto operator()(Return (Class::*pmf)(Args...), std::false_type = {}) const noexcept
|
||||
-> decltype(pmf) {
|
||||
constexpr auto operator()(Return (Class::*pmf)(Args...),
|
||||
std::false_type = {}) const noexcept -> decltype(pmf) {
|
||||
return pmf;
|
||||
}
|
||||
|
||||
template <typename Return, typename Class>
|
||||
constexpr auto operator()(Return (Class::*pmf)(Args...) const, std::true_type) const noexcept
|
||||
-> decltype(pmf) {
|
||||
constexpr auto operator()(Return (Class::*pmf)(Args...) const,
|
||||
std::true_type) const noexcept -> decltype(pmf) {
|
||||
return pmf;
|
||||
}
|
||||
};
|
||||
|
@ -1258,10 +1283,5 @@ constexpr
|
|||
# define PYBIND11_DETAILED_ERROR_MESSAGES
|
||||
#endif
|
||||
|
||||
// CPython 3.11+ provides Py_TPFLAGS_MANAGED_DICT, but PyPy3.11 does not, see PR #5508.
|
||||
#if PY_VERSION_HEX < 0x030B0000 || defined(PYPY_VERSION)
|
||||
# define PYBIND11_BACKWARD_COMPATIBILITY_TP_DICTOFFSET
|
||||
#endif
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE)
|
||||
|
|
|
@ -99,13 +99,6 @@ constexpr descr<1, Type> const_name() {
|
|||
return {'%'};
|
||||
}
|
||||
|
||||
// Use a different name based on whether the parameter is used as input or output
|
||||
template <size_t N1, size_t N2>
|
||||
constexpr descr<N1 + N2 + 1> io_name(char const (&text1)[N1], char const (&text2)[N2]) {
|
||||
return const_name("@") + const_name(text1) + const_name("@") + const_name(text2)
|
||||
+ const_name("@");
|
||||
}
|
||||
|
||||
// If "_" is defined as a macro, py::detail::_ cannot be provided.
|
||||
// It is therefore best to use py::detail::const_name universally.
|
||||
// This block is for backward compatibility only.
|
||||
|
@ -163,8 +156,9 @@ constexpr auto concat(const descr<N, Ts...> &d, const Args &...args) {
|
|||
}
|
||||
#else
|
||||
template <size_t N, typename... Ts, typename... Args>
|
||||
constexpr auto concat(const descr<N, Ts...> &d, const Args &...args)
|
||||
-> decltype(std::declval<descr<N + 2, Ts...>>() + concat(args...)) {
|
||||
constexpr auto concat(const descr<N, Ts...> &d,
|
||||
const Args &...args) -> decltype(std::declval<descr<N + 2, Ts...>>()
|
||||
+ concat(args...)) {
|
||||
return d + const_name(", ") + concat(args...);
|
||||
}
|
||||
#endif
|
||||
|
@ -174,15 +168,5 @@ constexpr descr<N + 2, Ts...> type_descr(const descr<N, Ts...> &descr) {
|
|||
return const_name("{") + descr + const_name("}");
|
||||
}
|
||||
|
||||
template <size_t N, typename... Ts>
|
||||
constexpr descr<N + 4, Ts...> arg_descr(const descr<N, Ts...> &descr) {
|
||||
return const_name("@^") + descr + const_name("@!");
|
||||
}
|
||||
|
||||
template <size_t N, typename... Ts>
|
||||
constexpr descr<N + 4, Ts...> return_descr(const descr<N, Ts...> &descr) {
|
||||
return const_name("@$") + descr + const_name("@!");
|
||||
}
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE)
|
||||
|
|
|
@ -1,39 +0,0 @@
|
|||
// Copyright (c) 2021 The Pybind Development Team.
|
||||
// All rights reserved. Use of this source code is governed by a
|
||||
// BSD-style license that can be found in the LICENSE file.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common.h"
|
||||
|
||||
#include <type_traits>
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
|
||||
template <typename To, typename From, typename SFINAE = void>
|
||||
struct dynamic_raw_ptr_cast_is_possible : std::false_type {};
|
||||
|
||||
template <typename To, typename From>
|
||||
struct dynamic_raw_ptr_cast_is_possible<
|
||||
To,
|
||||
From,
|
||||
detail::enable_if_t<!std::is_same<To, void>::value && std::is_polymorphic<From>::value>>
|
||||
: std::true_type {};
|
||||
|
||||
template <typename To,
|
||||
typename From,
|
||||
detail::enable_if_t<!dynamic_raw_ptr_cast_is_possible<To, From>::value, int> = 0>
|
||||
To *dynamic_raw_ptr_cast_if_possible(From * /*ptr*/) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
template <typename To,
|
||||
typename From,
|
||||
detail::enable_if_t<dynamic_raw_ptr_cast_is_possible<To, From>::value, int> = 0>
|
||||
To *dynamic_raw_ptr_cast_if_possible(From *ptr) {
|
||||
return dynamic_cast<To *>(ptr);
|
||||
}
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE)
|
|
@ -50,17 +50,17 @@ inline void try_translate_exceptions() {
|
|||
- delegate translation to the next translator by throwing a new type of exception.
|
||||
*/
|
||||
|
||||
bool handled = with_exception_translators(
|
||||
[&](std::forward_list<ExceptionTranslator> &exception_translators,
|
||||
std::forward_list<ExceptionTranslator> &local_exception_translators) {
|
||||
if (detail::apply_exception_translators(local_exception_translators)) {
|
||||
return true;
|
||||
}
|
||||
if (detail::apply_exception_translators(exception_translators)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
});
|
||||
bool handled = with_internals([&](internals &internals) {
|
||||
auto &local_exception_translators = get_local_internals().registered_exception_translators;
|
||||
if (detail::apply_exception_translators(local_exception_translators)) {
|
||||
return true;
|
||||
}
|
||||
auto &exception_translators = internals.registered_exception_translators;
|
||||
if (detail::apply_exception_translators(exception_translators)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
});
|
||||
|
||||
if (!handled) {
|
||||
set_error(PyExc_SystemError, "Exception escaped from default exception translator!");
|
||||
|
|
|
@ -10,7 +10,6 @@
|
|||
#pragma once
|
||||
|
||||
#include "class.h"
|
||||
#include "using_smart_holder.h"
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
|
||||
|
@ -156,7 +155,7 @@ void construct(value_and_holder &v_h, Alias<Class> *alias_ptr, bool) {
|
|||
// holder. This also handles types like std::shared_ptr<T> and std::unique_ptr<T> where T is a
|
||||
// derived type (through those holder's implicit conversion from derived class holder
|
||||
// constructors).
|
||||
template <typename Class, detail::enable_if_t<!is_smart_holder<Holder<Class>>::value, int> = 0>
|
||||
template <typename Class>
|
||||
void construct(value_and_holder &v_h, Holder<Class> holder, bool need_alias) {
|
||||
PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(need_alias);
|
||||
auto *ptr = holder_helper<Holder<Class>>::get(holder);
|
||||
|
@ -198,74 +197,6 @@ void construct(value_and_holder &v_h, Alias<Class> &&result, bool) {
|
|||
v_h.value_ptr() = new Alias<Class>(std::move(result));
|
||||
}
|
||||
|
||||
template <typename T, typename D>
|
||||
smart_holder init_smart_holder_from_unique_ptr(std::unique_ptr<T, D> &&unq_ptr,
|
||||
bool void_cast_raw_ptr) {
|
||||
void *void_ptr = void_cast_raw_ptr ? static_cast<void *>(unq_ptr.get()) : nullptr;
|
||||
return smart_holder::from_unique_ptr(std::move(unq_ptr), void_ptr);
|
||||
}
|
||||
|
||||
template <typename Class,
|
||||
typename D = std::default_delete<Cpp<Class>>,
|
||||
detail::enable_if_t<is_smart_holder<Holder<Class>>::value, int> = 0>
|
||||
void construct(value_and_holder &v_h, std::unique_ptr<Cpp<Class>, D> &&unq_ptr, bool need_alias) {
|
||||
PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(need_alias);
|
||||
auto *ptr = unq_ptr.get();
|
||||
no_nullptr(ptr);
|
||||
if (Class::has_alias && need_alias && !is_alias<Class>(ptr)) {
|
||||
throw type_error("pybind11::init(): construction failed: returned std::unique_ptr pointee "
|
||||
"is not an alias instance");
|
||||
}
|
||||
// Here and below: if the new object is a trampoline, the shared_from_this mechanism needs
|
||||
// to be prevented from accessing the smart_holder vptr, because it does not keep the
|
||||
// trampoline Python object alive. For types that don't inherit from enable_shared_from_this
|
||||
// it does not matter if void_cast_raw_ptr is true or false, therefore it's not necessary
|
||||
// to also inspect the type.
|
||||
auto smhldr = init_smart_holder_from_unique_ptr(
|
||||
std::move(unq_ptr), /*void_cast_raw_ptr*/ Class::has_alias && is_alias<Class>(ptr));
|
||||
v_h.value_ptr() = ptr;
|
||||
v_h.type->init_instance(v_h.inst, &smhldr);
|
||||
}
|
||||
|
||||
template <typename Class,
|
||||
typename D = std::default_delete<Alias<Class>>,
|
||||
detail::enable_if_t<is_smart_holder<Holder<Class>>::value, int> = 0>
|
||||
void construct(value_and_holder &v_h,
|
||||
std::unique_ptr<Alias<Class>, D> &&unq_ptr,
|
||||
bool /*need_alias*/) {
|
||||
auto *ptr = unq_ptr.get();
|
||||
no_nullptr(ptr);
|
||||
auto smhldr
|
||||
= init_smart_holder_from_unique_ptr(std::move(unq_ptr), /*void_cast_raw_ptr*/ true);
|
||||
v_h.value_ptr() = ptr;
|
||||
v_h.type->init_instance(v_h.inst, &smhldr);
|
||||
}
|
||||
|
||||
template <typename Class, detail::enable_if_t<is_smart_holder<Holder<Class>>::value, int> = 0>
|
||||
void construct(value_and_holder &v_h, std::shared_ptr<Cpp<Class>> &&shd_ptr, bool need_alias) {
|
||||
PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(need_alias);
|
||||
auto *ptr = shd_ptr.get();
|
||||
no_nullptr(ptr);
|
||||
if (Class::has_alias && need_alias && !is_alias<Class>(ptr)) {
|
||||
throw type_error("pybind11::init(): construction failed: returned std::shared_ptr pointee "
|
||||
"is not an alias instance");
|
||||
}
|
||||
auto smhldr = smart_holder::from_shared_ptr(shd_ptr);
|
||||
v_h.value_ptr() = ptr;
|
||||
v_h.type->init_instance(v_h.inst, &smhldr);
|
||||
}
|
||||
|
||||
template <typename Class, detail::enable_if_t<is_smart_holder<Holder<Class>>::value, int> = 0>
|
||||
void construct(value_and_holder &v_h,
|
||||
std::shared_ptr<Alias<Class>> &&shd_ptr,
|
||||
bool /*need_alias*/) {
|
||||
auto *ptr = shd_ptr.get();
|
||||
no_nullptr(ptr);
|
||||
auto smhldr = smart_holder::from_shared_ptr(shd_ptr);
|
||||
v_h.value_ptr() = ptr;
|
||||
v_h.type->init_instance(v_h.inst, &smhldr);
|
||||
}
|
||||
|
||||
// Implementing class for py::init<...>()
|
||||
template <typename... Args>
|
||||
struct constructor {
|
||||
|
@ -479,7 +410,7 @@ struct pickle_factory<Get, Set, RetState(Self), NewInstance(ArgState)> {
|
|||
|
||||
template <typename Class, typename... Extra>
|
||||
void execute(Class &cl, const Extra &...extra) && {
|
||||
cl.def("__getstate__", std::move(get), pos_only());
|
||||
cl.def("__getstate__", std::move(get));
|
||||
|
||||
#if defined(PYBIND11_CPP14)
|
||||
cl.def(
|
||||
|
|
|
@ -15,7 +15,6 @@
|
|||
# include <pybind11/gil.h>
|
||||
#endif
|
||||
|
||||
#include <pybind11/conduit/pybind11_platform_abi_id.h>
|
||||
#include <pybind11/pytypes.h>
|
||||
|
||||
#include <exception>
|
||||
|
@ -37,12 +36,18 @@
|
|||
/// further ABI-incompatible changes may be made before the ABI is officially
|
||||
/// changed to the new version.
|
||||
#ifndef PYBIND11_INTERNALS_VERSION
|
||||
# define PYBIND11_INTERNALS_VERSION 7
|
||||
# if PY_VERSION_HEX >= 0x030C0000 || defined(_MSC_VER)
|
||||
// Version bump for Python 3.12+, before first 3.12 beta release.
|
||||
// Version bump for MSVC piggy-backed on PR #4779. See comments there.
|
||||
# define PYBIND11_INTERNALS_VERSION 5
|
||||
# else
|
||||
# define PYBIND11_INTERNALS_VERSION 4
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if PYBIND11_INTERNALS_VERSION < 7
|
||||
# error "PYBIND11_INTERNALS_VERSION 7 is the minimum for all platforms for pybind11v3."
|
||||
#endif
|
||||
// This requirement is mainly to reduce the support burden (see PR #4570).
|
||||
static_assert(PY_VERSION_HEX < 0x030C0000 || PYBIND11_INTERNALS_VERSION >= 5,
|
||||
"pybind11 ABI version 5 is the minimum for Python 3.12+");
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
|
||||
|
@ -61,29 +66,40 @@ inline PyObject *make_object_base_type(PyTypeObject *metaclass);
|
|||
// Thread Specific Storage (TSS) API.
|
||||
// Avoid unnecessary allocation of `Py_tss_t`, since we cannot use
|
||||
// `Py_LIMITED_API` anyway.
|
||||
#define PYBIND11_TLS_KEY_REF Py_tss_t &
|
||||
#if defined(__clang__)
|
||||
# define PYBIND11_TLS_KEY_INIT(var) \
|
||||
_Pragma("clang diagnostic push") /**/ \
|
||||
_Pragma("clang diagnostic ignored \"-Wmissing-field-initializers\"") /**/ \
|
||||
Py_tss_t var \
|
||||
= Py_tss_NEEDS_INIT; \
|
||||
_Pragma("clang diagnostic pop")
|
||||
#elif defined(__GNUC__) && !defined(__INTEL_COMPILER)
|
||||
# define PYBIND11_TLS_KEY_INIT(var) \
|
||||
_Pragma("GCC diagnostic push") /**/ \
|
||||
_Pragma("GCC diagnostic ignored \"-Wmissing-field-initializers\"") /**/ \
|
||||
Py_tss_t var \
|
||||
= Py_tss_NEEDS_INIT; \
|
||||
_Pragma("GCC diagnostic pop")
|
||||
#if PYBIND11_INTERNALS_VERSION > 4
|
||||
# define PYBIND11_TLS_KEY_REF Py_tss_t &
|
||||
# if defined(__clang__)
|
||||
# define PYBIND11_TLS_KEY_INIT(var) \
|
||||
_Pragma("clang diagnostic push") /**/ \
|
||||
_Pragma("clang diagnostic ignored \"-Wmissing-field-initializers\"") /**/ \
|
||||
Py_tss_t var \
|
||||
= Py_tss_NEEDS_INIT; \
|
||||
_Pragma("clang diagnostic pop")
|
||||
# elif defined(__GNUC__) && !defined(__INTEL_COMPILER)
|
||||
# define PYBIND11_TLS_KEY_INIT(var) \
|
||||
_Pragma("GCC diagnostic push") /**/ \
|
||||
_Pragma("GCC diagnostic ignored \"-Wmissing-field-initializers\"") /**/ \
|
||||
Py_tss_t var \
|
||||
= Py_tss_NEEDS_INIT; \
|
||||
_Pragma("GCC diagnostic pop")
|
||||
# else
|
||||
# define PYBIND11_TLS_KEY_INIT(var) Py_tss_t var = Py_tss_NEEDS_INIT;
|
||||
# endif
|
||||
# define PYBIND11_TLS_KEY_CREATE(var) (PyThread_tss_create(&(var)) == 0)
|
||||
# define PYBIND11_TLS_GET_VALUE(key) PyThread_tss_get(&(key))
|
||||
# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_tss_set(&(key), (value))
|
||||
# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_tss_set(&(key), nullptr)
|
||||
# define PYBIND11_TLS_FREE(key) PyThread_tss_delete(&(key))
|
||||
#else
|
||||
# define PYBIND11_TLS_KEY_INIT(var) Py_tss_t var = Py_tss_NEEDS_INIT;
|
||||
# define PYBIND11_TLS_KEY_REF Py_tss_t *
|
||||
# define PYBIND11_TLS_KEY_INIT(var) Py_tss_t *var = nullptr;
|
||||
# define PYBIND11_TLS_KEY_CREATE(var) \
|
||||
(((var) = PyThread_tss_alloc()) != nullptr && (PyThread_tss_create((var)) == 0))
|
||||
# define PYBIND11_TLS_GET_VALUE(key) PyThread_tss_get((key))
|
||||
# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_tss_set((key), (value))
|
||||
# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_tss_set((key), nullptr)
|
||||
# define PYBIND11_TLS_FREE(key) PyThread_tss_free(key)
|
||||
#endif
|
||||
#define PYBIND11_TLS_KEY_CREATE(var) (PyThread_tss_create(&(var)) == 0)
|
||||
#define PYBIND11_TLS_GET_VALUE(key) PyThread_tss_get(&(key))
|
||||
#define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_tss_set(&(key), (value))
|
||||
#define PYBIND11_TLS_DELETE_VALUE(key) PyThread_tss_set(&(key), nullptr)
|
||||
#define PYBIND11_TLS_FREE(key) PyThread_tss_delete(&(key))
|
||||
|
||||
// Python loads modules by default with dlopen with the RTLD_LOCAL flag; under libc++ and possibly
|
||||
// other STLs, this means `typeid(A)` from one module won't equal `typeid(A)` from another module
|
||||
|
@ -91,7 +107,8 @@ inline PyObject *make_object_base_type(PyTypeObject *metaclass);
|
|||
// libstdc++, this doesn't happen: equality and the type_index hash are based on the type name,
|
||||
// which works. If not under a known-good stl, provide our own name-based hash and equality
|
||||
// functions that use the type name.
|
||||
#if !defined(_LIBCPP_VERSION)
|
||||
#if (PYBIND11_INTERNALS_VERSION <= 4 && defined(__GLIBCXX__)) \
|
||||
|| (PYBIND11_INTERNALS_VERSION >= 5 && !defined(_LIBCPP_VERSION))
|
||||
inline bool same_type(const std::type_info &lhs, const std::type_info &rhs) { return lhs == rhs; }
|
||||
using type_hash = std::hash<std::type_index>;
|
||||
using type_equal_to = std::equal_to<std::type_index>;
|
||||
|
@ -160,7 +177,6 @@ static_assert(sizeof(instance_map_shard) % 64 == 0,
|
|||
struct internals {
|
||||
#ifdef Py_GIL_DISABLED
|
||||
pymutex mutex;
|
||||
pymutex exception_translator_mutex;
|
||||
#endif
|
||||
// std::type_index -> pybind11's type information
|
||||
type_map<type_info *> registered_types_cpp;
|
||||
|
@ -179,26 +195,35 @@ struct internals {
|
|||
std::forward_list<ExceptionTranslator> registered_exception_translators;
|
||||
std::unordered_map<std::string, void *> shared_data; // Custom data to be shared across
|
||||
// extensions
|
||||
std::forward_list<std::string> static_strings; // Stores the std::strings backing
|
||||
// detail::c_str()
|
||||
#if PYBIND11_INTERNALS_VERSION == 4
|
||||
std::vector<PyObject *> unused_loader_patient_stack_remove_at_v5;
|
||||
#endif
|
||||
std::forward_list<std::string> static_strings; // Stores the std::strings backing
|
||||
// detail::c_str()
|
||||
PyTypeObject *static_property_type;
|
||||
PyTypeObject *default_metaclass;
|
||||
PyObject *instance_base;
|
||||
// Unused if PYBIND11_SIMPLE_GIL_MANAGEMENT is defined:
|
||||
PYBIND11_TLS_KEY_INIT(tstate)
|
||||
#if PYBIND11_INTERNALS_VERSION > 4
|
||||
PYBIND11_TLS_KEY_INIT(loader_life_support_tls_key)
|
||||
#endif // PYBIND11_INTERNALS_VERSION > 4
|
||||
// Unused if PYBIND11_SIMPLE_GIL_MANAGEMENT is defined:
|
||||
PyInterpreterState *istate = nullptr;
|
||||
|
||||
#if PYBIND11_INTERNALS_VERSION > 4
|
||||
// Note that we have to use a std::string to allocate memory to ensure a unique address
|
||||
// We want unique addresses since we use pointer equality to compare function records
|
||||
std::string function_record_capsule_name = internals_function_record_capsule_name;
|
||||
#endif
|
||||
|
||||
internals() = default;
|
||||
internals(const internals &other) = delete;
|
||||
internals &operator=(const internals &other) = delete;
|
||||
~internals() {
|
||||
#if PYBIND11_INTERNALS_VERSION > 4
|
||||
PYBIND11_TLS_FREE(loader_life_support_tls_key);
|
||||
#endif // PYBIND11_INTERNALS_VERSION > 4
|
||||
|
||||
// This destructor is called *after* Py_Finalize() in finalize_interpreter().
|
||||
// That *SHOULD BE* fine. The following details what happens when PyThread_tss_free is
|
||||
|
@ -211,17 +236,6 @@ struct internals {
|
|||
}
|
||||
};
|
||||
|
||||
// For backwards compatibility (i.e. #ifdef guards):
|
||||
#define PYBIND11_HAS_INTERNALS_WITH_SMART_HOLDER_SUPPORT
|
||||
|
||||
enum class holder_enum_t : uint8_t {
|
||||
undefined,
|
||||
std_unique_ptr, // Default, lacking interop with std::shared_ptr.
|
||||
std_shared_ptr, // Lacking interop with std::unique_ptr.
|
||||
smart_holder, // Full std::unique_ptr / std::shared_ptr interop.
|
||||
custom_holder,
|
||||
};
|
||||
|
||||
/// Additional type information which does not fit into the PyTypeObject.
|
||||
/// Changes to this struct also require bumping `PYBIND11_INTERNALS_VERSION`.
|
||||
struct type_info {
|
||||
|
@ -237,7 +251,6 @@ struct type_info {
|
|||
buffer_info *(*get_buffer)(PyObject *, void *) = nullptr;
|
||||
void *get_buffer_data = nullptr;
|
||||
void *(*module_local_load)(PyObject *, const type_info *) = nullptr;
|
||||
holder_enum_t holder_enum_v = holder_enum_t::undefined;
|
||||
/* A simple type never occurs as a (direct or indirect) parent
|
||||
* of a class that makes use of multiple inheritance.
|
||||
* A type can be simple even if it has non-simple ancestors as long as it has no descendants.
|
||||
|
@ -245,17 +258,80 @@ struct type_info {
|
|||
bool simple_type : 1;
|
||||
/* True if there is no multiple inheritance in this type's inheritance tree */
|
||||
bool simple_ancestors : 1;
|
||||
/* for base vs derived holder_type checks */
|
||||
bool default_holder : 1;
|
||||
/* true if this is a type registered with py::module_local */
|
||||
bool module_local : 1;
|
||||
};
|
||||
|
||||
/// On MSVC, debug and release builds are not ABI-compatible!
|
||||
#if defined(_MSC_VER) && defined(_DEBUG)
|
||||
# define PYBIND11_BUILD_TYPE "_debug"
|
||||
#else
|
||||
# define PYBIND11_BUILD_TYPE ""
|
||||
#endif
|
||||
|
||||
/// Let's assume that different compilers are ABI-incompatible.
|
||||
/// A user can manually set this string if they know their
|
||||
/// compiler is compatible.
|
||||
#ifndef PYBIND11_COMPILER_TYPE
|
||||
# if defined(_MSC_VER)
|
||||
# define PYBIND11_COMPILER_TYPE "_msvc"
|
||||
# elif defined(__INTEL_COMPILER)
|
||||
# define PYBIND11_COMPILER_TYPE "_icc"
|
||||
# elif defined(__clang__)
|
||||
# define PYBIND11_COMPILER_TYPE "_clang"
|
||||
# elif defined(__PGI)
|
||||
# define PYBIND11_COMPILER_TYPE "_pgi"
|
||||
# elif defined(__MINGW32__)
|
||||
# define PYBIND11_COMPILER_TYPE "_mingw"
|
||||
# elif defined(__CYGWIN__)
|
||||
# define PYBIND11_COMPILER_TYPE "_gcc_cygwin"
|
||||
# elif defined(__GNUC__)
|
||||
# define PYBIND11_COMPILER_TYPE "_gcc"
|
||||
# else
|
||||
# define PYBIND11_COMPILER_TYPE "_unknown"
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/// Also standard libs
|
||||
#ifndef PYBIND11_STDLIB
|
||||
# if defined(_LIBCPP_VERSION)
|
||||
# define PYBIND11_STDLIB "_libcpp"
|
||||
# elif defined(__GLIBCXX__) || defined(__GLIBCPP__)
|
||||
# define PYBIND11_STDLIB "_libstdcpp"
|
||||
# else
|
||||
# define PYBIND11_STDLIB ""
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/// On Linux/OSX, changes in __GXX_ABI_VERSION__ indicate ABI incompatibility.
|
||||
/// On MSVC, changes in _MSC_VER may indicate ABI incompatibility (#2898).
|
||||
#ifndef PYBIND11_BUILD_ABI
|
||||
# if defined(__GXX_ABI_VERSION)
|
||||
# define PYBIND11_BUILD_ABI "_cxxabi" PYBIND11_TOSTRING(__GXX_ABI_VERSION)
|
||||
# elif defined(_MSC_VER)
|
||||
# define PYBIND11_BUILD_ABI "_mscver" PYBIND11_TOSTRING(_MSC_VER)
|
||||
# else
|
||||
# define PYBIND11_BUILD_ABI ""
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#ifndef PYBIND11_INTERNALS_KIND
|
||||
# define PYBIND11_INTERNALS_KIND ""
|
||||
#endif
|
||||
|
||||
#define PYBIND11_PLATFORM_ABI_ID \
|
||||
PYBIND11_INTERNALS_KIND PYBIND11_COMPILER_TYPE PYBIND11_STDLIB PYBIND11_BUILD_ABI \
|
||||
PYBIND11_BUILD_TYPE
|
||||
|
||||
#define PYBIND11_INTERNALS_ID \
|
||||
"__pybind11_internals_v" PYBIND11_TOSTRING(PYBIND11_INTERNALS_VERSION) \
|
||||
PYBIND11_COMPILER_TYPE_LEADING_UNDERSCORE PYBIND11_PLATFORM_ABI_ID "__"
|
||||
PYBIND11_PLATFORM_ABI_ID "__"
|
||||
|
||||
#define PYBIND11_MODULE_LOCAL_ID \
|
||||
"__pybind11_module_local_v" PYBIND11_TOSTRING(PYBIND11_INTERNALS_VERSION) \
|
||||
PYBIND11_COMPILER_TYPE_LEADING_UNDERSCORE PYBIND11_PLATFORM_ABI_ID "__"
|
||||
PYBIND11_PLATFORM_ABI_ID "__"
|
||||
|
||||
/// Each module locally stores a pointer to the `internals` data. The data
|
||||
/// itself is shared among modules with the same `PYBIND11_INTERNALS_ID`.
|
||||
|
@ -373,7 +449,7 @@ inline void translate_local_exception(std::exception_ptr p) {
|
|||
|
||||
inline object get_python_state_dict() {
|
||||
object state_dict;
|
||||
#if defined(PYPY_VERSION) || defined(GRAALVM_PYTHON)
|
||||
#if PYBIND11_INTERNALS_VERSION <= 4 || PY_VERSION_HEX < 0x03080000 || defined(PYPY_VERSION)
|
||||
state_dict = reinterpret_borrow<object>(PyEval_GetBuiltins());
|
||||
#else
|
||||
# if PY_VERSION_HEX < 0x03090000
|
||||
|
@ -471,12 +547,13 @@ PYBIND11_NOINLINE internals &get_internals() {
|
|||
}
|
||||
PYBIND11_TLS_REPLACE_VALUE(internals_ptr->tstate, tstate);
|
||||
|
||||
#if PYBIND11_INTERNALS_VERSION > 4
|
||||
// NOLINTNEXTLINE(bugprone-assignment-in-if-condition)
|
||||
if (!PYBIND11_TLS_KEY_CREATE(internals_ptr->loader_life_support_tls_key)) {
|
||||
pybind11_fail("get_internals: could not successfully initialize the "
|
||||
"loader_life_support TSS key!");
|
||||
}
|
||||
|
||||
#endif
|
||||
internals_ptr->istate = tstate->interp;
|
||||
state_dict[PYBIND11_INTERNALS_ID] = capsule(reinterpret_cast<void *>(internals_pp));
|
||||
internals_ptr->registered_exception_translators.push_front(&translate_exception);
|
||||
|
@ -506,6 +583,40 @@ PYBIND11_NOINLINE internals &get_internals() {
|
|||
struct local_internals {
|
||||
type_map<type_info *> registered_types_cpp;
|
||||
std::forward_list<ExceptionTranslator> registered_exception_translators;
|
||||
#if PYBIND11_INTERNALS_VERSION == 4
|
||||
|
||||
// For ABI compatibility, we can't store the loader_life_support TLS key in
|
||||
// the `internals` struct directly. Instead, we store it in `shared_data` and
|
||||
// cache a copy in `local_internals`. If we allocated a separate TLS key for
|
||||
// each instance of `local_internals`, we could end up allocating hundreds of
|
||||
// TLS keys if hundreds of different pybind11 modules are loaded (which is a
|
||||
// plausible number).
|
||||
PYBIND11_TLS_KEY_INIT(loader_life_support_tls_key)
|
||||
|
||||
// Holds the shared TLS key for the loader_life_support stack.
|
||||
struct shared_loader_life_support_data {
|
||||
PYBIND11_TLS_KEY_INIT(loader_life_support_tls_key)
|
||||
shared_loader_life_support_data() {
|
||||
// NOLINTNEXTLINE(bugprone-assignment-in-if-condition)
|
||||
if (!PYBIND11_TLS_KEY_CREATE(loader_life_support_tls_key)) {
|
||||
pybind11_fail("local_internals: could not successfully initialize the "
|
||||
"loader_life_support TLS key!");
|
||||
}
|
||||
}
|
||||
// We can't help but leak the TLS key, because Python never unloads extension modules.
|
||||
};
|
||||
|
||||
local_internals() {
|
||||
auto &internals = get_internals();
|
||||
// Get or create the `loader_life_support_stack_key`.
|
||||
auto &ptr = internals.shared_data["_life_support"];
|
||||
if (!ptr) {
|
||||
ptr = new shared_loader_life_support_data;
|
||||
}
|
||||
loader_life_support_tls_key
|
||||
= static_cast<shared_loader_life_support_data *>(ptr)->loader_life_support_tls_key;
|
||||
}
|
||||
#endif // PYBIND11_INTERNALS_VERSION == 4
|
||||
};
|
||||
|
||||
/// Works like `get_internals`, but for things which are locally registered.
|
||||
|
@ -532,19 +643,6 @@ inline auto with_internals(const F &cb) -> decltype(cb(get_internals())) {
|
|||
return cb(internals);
|
||||
}
|
||||
|
||||
template <typename F>
|
||||
inline auto with_exception_translators(const F &cb)
|
||||
-> decltype(cb(get_internals().registered_exception_translators,
|
||||
get_local_internals().registered_exception_translators)) {
|
||||
auto &internals = get_internals();
|
||||
#ifdef Py_GIL_DISABLED
|
||||
std::unique_lock<pymutex> lock((internals).exception_translator_mutex);
|
||||
#endif
|
||||
auto &local_internals = get_local_internals();
|
||||
return cb(internals.registered_exception_translators,
|
||||
local_internals.registered_exception_translators);
|
||||
}
|
||||
|
||||
inline std::uint64_t mix64(std::uint64_t z) {
|
||||
// David Stafford's variant 13 of the MurmurHash3 finalizer popularized
|
||||
// by the SplitMix PRNG.
|
||||
|
@ -555,8 +653,8 @@ inline std::uint64_t mix64(std::uint64_t z) {
|
|||
}
|
||||
|
||||
template <typename F>
|
||||
inline auto with_instance_map(const void *ptr, const F &cb)
|
||||
-> decltype(cb(std::declval<instance_map &>())) {
|
||||
inline auto with_instance_map(const void *ptr,
|
||||
const F &cb) -> decltype(cb(std::declval<instance_map &>())) {
|
||||
auto &internals = get_internals();
|
||||
|
||||
#ifdef Py_GIL_DISABLED
|
||||
|
@ -611,8 +709,7 @@ const char *c_str(Args &&...args) {
|
|||
}
|
||||
|
||||
inline const char *get_function_record_capsule_name() {
|
||||
// On GraalPy, pointer equality of the names is currently not guaranteed
|
||||
#if !defined(GRAALVM_PYTHON)
|
||||
#if PYBIND11_INTERNALS_VERSION > 4
|
||||
return get_internals().function_record_capsule_name.c_str();
|
||||
#else
|
||||
return nullptr;
|
||||
|
|
|
@ -1,349 +0,0 @@
|
|||
// Copyright (c) 2020-2024 The Pybind Development Team.
|
||||
// All rights reserved. Use of this source code is governed by a
|
||||
// BSD-style license that can be found in the LICENSE file.
|
||||
|
||||
/* Proof-of-Concept for smart pointer interoperability.
|
||||
|
||||
High-level aspects:
|
||||
|
||||
* Support all `unique_ptr`, `shared_ptr` interops that are feasible.
|
||||
|
||||
* Cleanly and clearly report all interops that are infeasible.
|
||||
|
||||
* Meant to fit into a `PyObject`, as a holder for C++ objects.
|
||||
|
||||
* Support a system design that makes it impossible to trigger
|
||||
C++ Undefined Behavior, especially from Python.
|
||||
|
||||
* Support a system design with clean runtime inheritance casting. From this
|
||||
it follows that the `smart_holder` needs to be type-erased (`void*`).
|
||||
|
||||
* Handling of RTTI for the type-erased held pointer is NOT implemented here.
|
||||
It is the responsibility of the caller to ensure that `static_cast<T *>`
|
||||
is well-formed when calling `as_*` member functions. Inheritance casting
|
||||
needs to be handled in a different layer (similar to the code organization
|
||||
in boost/python/object/inheritance.hpp).
|
||||
|
||||
Details:
|
||||
|
||||
* The "root holder" chosen here is a `shared_ptr<void>` (named `vptr` in this
|
||||
implementation). This choice is practically inevitable because `shared_ptr`
|
||||
has only very limited support for inspecting and accessing its deleter.
|
||||
|
||||
* If created from a raw pointer, or a `unique_ptr` without a custom deleter,
|
||||
`vptr` always uses a custom deleter, to support `unique_ptr`-like disowning.
|
||||
The custom deleters could be extended to included life-time management for
|
||||
external objects (e.g. `PyObject`).
|
||||
|
||||
* If created from an external `shared_ptr`, or a `unique_ptr` with a custom
|
||||
deleter, including life-time management for external objects is infeasible.
|
||||
|
||||
* By choice, the smart_holder is movable but not copyable, to keep the design
|
||||
simple, and to guard against accidental copying overhead.
|
||||
|
||||
* The `void_cast_raw_ptr` option is needed to make the `smart_holder` `vptr`
|
||||
member invisible to the `shared_from_this` mechanism, in case the lifetime
|
||||
of a `PyObject` is tied to the pointee.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <stdexcept>
|
||||
#include <string>
|
||||
#include <type_traits>
|
||||
#include <typeinfo>
|
||||
#include <utility>
|
||||
|
||||
// pybindit = Python Bindings Innovation Track.
|
||||
// Currently not in pybind11 namespace to signal that this POC does not depend
|
||||
// on any existing pybind11 functionality.
|
||||
namespace pybindit {
|
||||
namespace memory {
|
||||
|
||||
static constexpr bool type_has_shared_from_this(...) { return false; }
|
||||
|
||||
template <typename T>
|
||||
static constexpr bool type_has_shared_from_this(const std::enable_shared_from_this<T> *) {
|
||||
return true;
|
||||
}
|
||||
|
||||
struct guarded_delete {
|
||||
std::weak_ptr<void> released_ptr; // Trick to keep the smart_holder memory footprint small.
|
||||
std::function<void(void *)> del_fun; // Rare case.
|
||||
void (*del_ptr)(void *); // Common case.
|
||||
bool use_del_fun;
|
||||
bool armed_flag;
|
||||
guarded_delete(std::function<void(void *)> &&del_fun, bool armed_flag)
|
||||
: del_fun{std::move(del_fun)}, del_ptr{nullptr}, use_del_fun{true},
|
||||
armed_flag{armed_flag} {}
|
||||
guarded_delete(void (*del_ptr)(void *), bool armed_flag)
|
||||
: del_ptr{del_ptr}, use_del_fun{false}, armed_flag{armed_flag} {}
|
||||
void operator()(void *raw_ptr) const {
|
||||
if (armed_flag) {
|
||||
if (use_del_fun) {
|
||||
del_fun(raw_ptr);
|
||||
} else {
|
||||
del_ptr(raw_ptr);
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
template <typename T, typename std::enable_if<std::is_destructible<T>::value, int>::type = 0>
|
||||
inline void builtin_delete_if_destructible(void *raw_ptr) {
|
||||
std::default_delete<T>{}(static_cast<T *>(raw_ptr));
|
||||
}
|
||||
|
||||
template <typename T, typename std::enable_if<!std::is_destructible<T>::value, int>::type = 0>
|
||||
inline void builtin_delete_if_destructible(void *) {
|
||||
// This noop operator is needed to avoid a compilation error (for `delete raw_ptr;`), but
|
||||
// throwing an exception from a destructor will std::terminate the process. Therefore the
|
||||
// runtime check for lifetime-management correctness is implemented elsewhere (in
|
||||
// ensure_pointee_is_destructible()).
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
guarded_delete make_guarded_builtin_delete(bool armed_flag) {
|
||||
return guarded_delete(builtin_delete_if_destructible<T>, armed_flag);
|
||||
}
|
||||
|
||||
template <typename T, typename D>
|
||||
struct custom_deleter {
|
||||
D deleter;
|
||||
explicit custom_deleter(D &&deleter) : deleter{std::forward<D>(deleter)} {}
|
||||
void operator()(void *raw_ptr) { deleter(static_cast<T *>(raw_ptr)); }
|
||||
};
|
||||
|
||||
template <typename T, typename D>
|
||||
guarded_delete make_guarded_custom_deleter(D &&uqp_del, bool armed_flag) {
|
||||
return guarded_delete(
|
||||
std::function<void(void *)>(custom_deleter<T, D>(std::forward<D>(uqp_del))), armed_flag);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
inline bool is_std_default_delete(const std::type_info &rtti_deleter) {
|
||||
return rtti_deleter == typeid(std::default_delete<T>)
|
||||
|| rtti_deleter == typeid(std::default_delete<T const>);
|
||||
}
|
||||
|
||||
struct smart_holder {
|
||||
const std::type_info *rtti_uqp_del = nullptr;
|
||||
std::shared_ptr<void> vptr;
|
||||
bool vptr_is_using_noop_deleter : 1;
|
||||
bool vptr_is_using_builtin_delete : 1;
|
||||
bool vptr_is_external_shared_ptr : 1;
|
||||
bool is_populated : 1;
|
||||
bool is_disowned : 1;
|
||||
|
||||
// Design choice: smart_holder is movable but not copyable.
|
||||
smart_holder(smart_holder &&) = default;
|
||||
smart_holder(const smart_holder &) = delete;
|
||||
smart_holder &operator=(smart_holder &&) = delete;
|
||||
smart_holder &operator=(const smart_holder &) = delete;
|
||||
|
||||
smart_holder()
|
||||
: vptr_is_using_noop_deleter{false}, vptr_is_using_builtin_delete{false},
|
||||
vptr_is_external_shared_ptr{false}, is_populated{false}, is_disowned{false} {}
|
||||
|
||||
bool has_pointee() const { return vptr != nullptr; }
|
||||
|
||||
template <typename T>
|
||||
static void ensure_pointee_is_destructible(const char *context) {
|
||||
if (!std::is_destructible<T>::value) {
|
||||
throw std::invalid_argument(std::string("Pointee is not destructible (") + context
|
||||
+ ").");
|
||||
}
|
||||
}
|
||||
|
||||
void ensure_is_populated(const char *context) const {
|
||||
if (!is_populated) {
|
||||
throw std::runtime_error(std::string("Unpopulated holder (") + context + ").");
|
||||
}
|
||||
}
|
||||
void ensure_is_not_disowned(const char *context) const {
|
||||
if (is_disowned) {
|
||||
throw std::runtime_error(std::string("Holder was disowned already (") + context
|
||||
+ ").");
|
||||
}
|
||||
}
|
||||
|
||||
void ensure_vptr_is_using_builtin_delete(const char *context) const {
|
||||
if (vptr_is_external_shared_ptr) {
|
||||
throw std::invalid_argument(std::string("Cannot disown external shared_ptr (")
|
||||
+ context + ").");
|
||||
}
|
||||
if (vptr_is_using_noop_deleter) {
|
||||
throw std::invalid_argument(std::string("Cannot disown non-owning holder (") + context
|
||||
+ ").");
|
||||
}
|
||||
if (!vptr_is_using_builtin_delete) {
|
||||
throw std::invalid_argument(std::string("Cannot disown custom deleter (") + context
|
||||
+ ").");
|
||||
}
|
||||
}
|
||||
|
||||
template <typename T, typename D>
|
||||
void ensure_compatible_rtti_uqp_del(const char *context) const {
|
||||
const std::type_info *rtti_requested = &typeid(D);
|
||||
if (!rtti_uqp_del) {
|
||||
if (!is_std_default_delete<T>(*rtti_requested)) {
|
||||
throw std::invalid_argument(std::string("Missing unique_ptr deleter (") + context
|
||||
+ ").");
|
||||
}
|
||||
ensure_vptr_is_using_builtin_delete(context);
|
||||
} else if (!(*rtti_requested == *rtti_uqp_del)
|
||||
&& !(vptr_is_using_builtin_delete
|
||||
&& is_std_default_delete<T>(*rtti_requested))) {
|
||||
throw std::invalid_argument(std::string("Incompatible unique_ptr deleter (") + context
|
||||
+ ").");
|
||||
}
|
||||
}
|
||||
|
||||
void ensure_has_pointee(const char *context) const {
|
||||
if (!has_pointee()) {
|
||||
throw std::invalid_argument(std::string("Disowned holder (") + context + ").");
|
||||
}
|
||||
}
|
||||
|
||||
void ensure_use_count_1(const char *context) const {
|
||||
if (vptr == nullptr) {
|
||||
throw std::invalid_argument(std::string("Cannot disown nullptr (") + context + ").");
|
||||
}
|
||||
// In multithreaded environments accessing use_count can lead to
|
||||
// race conditions, but in the context of Python it is a bug (elsewhere)
|
||||
// if the Global Interpreter Lock (GIL) is not being held when this code
|
||||
// is reached.
|
||||
// PYBIND11:REMINDER: This may need to be protected by a mutex in free-threaded Python.
|
||||
if (vptr.use_count() != 1) {
|
||||
throw std::invalid_argument(std::string("Cannot disown use_count != 1 (") + context
|
||||
+ ").");
|
||||
}
|
||||
}
|
||||
|
||||
void reset_vptr_deleter_armed_flag(bool armed_flag) const {
|
||||
auto *vptr_del_ptr = std::get_deleter<guarded_delete>(vptr);
|
||||
if (vptr_del_ptr == nullptr) {
|
||||
throw std::runtime_error(
|
||||
"smart_holder::reset_vptr_deleter_armed_flag() called in an invalid context.");
|
||||
}
|
||||
vptr_del_ptr->armed_flag = armed_flag;
|
||||
}
|
||||
|
||||
// Caller is responsible for precondition: ensure_compatible_rtti_uqp_del<T, D>() must succeed.
|
||||
template <typename T, typename D>
|
||||
std::unique_ptr<D> extract_deleter(const char *context) const {
|
||||
const auto *gd = std::get_deleter<guarded_delete>(vptr);
|
||||
if (gd && gd->use_del_fun) {
|
||||
const auto &custom_deleter_ptr = gd->del_fun.template target<custom_deleter<T, D>>();
|
||||
if (custom_deleter_ptr == nullptr) {
|
||||
throw std::runtime_error(
|
||||
std::string("smart_holder::extract_deleter() precondition failure (") + context
|
||||
+ ").");
|
||||
}
|
||||
static_assert(std::is_copy_constructible<D>::value,
|
||||
"Required for compatibility with smart_holder functionality.");
|
||||
return std::unique_ptr<D>(new D(custom_deleter_ptr->deleter));
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
static smart_holder from_raw_ptr_unowned(void *raw_ptr) {
|
||||
smart_holder hld;
|
||||
hld.vptr.reset(raw_ptr, [](void *) {});
|
||||
hld.vptr_is_using_noop_deleter = true;
|
||||
hld.is_populated = true;
|
||||
return hld;
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
T *as_raw_ptr_unowned() const {
|
||||
return static_cast<T *>(vptr.get());
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static smart_holder from_raw_ptr_take_ownership(T *raw_ptr, bool void_cast_raw_ptr = false) {
|
||||
ensure_pointee_is_destructible<T>("from_raw_ptr_take_ownership");
|
||||
smart_holder hld;
|
||||
auto gd = make_guarded_builtin_delete<T>(true);
|
||||
if (void_cast_raw_ptr) {
|
||||
hld.vptr.reset(static_cast<void *>(raw_ptr), std::move(gd));
|
||||
} else {
|
||||
hld.vptr.reset(raw_ptr, std::move(gd));
|
||||
}
|
||||
hld.vptr_is_using_builtin_delete = true;
|
||||
hld.is_populated = true;
|
||||
return hld;
|
||||
}
|
||||
|
||||
// Caller is responsible for ensuring the complex preconditions
|
||||
// (see `smart_holder_type_caster_support::load_helper`).
|
||||
void disown() {
|
||||
reset_vptr_deleter_armed_flag(false);
|
||||
is_disowned = true;
|
||||
}
|
||||
|
||||
// Caller is responsible for ensuring the complex preconditions
|
||||
// (see `smart_holder_type_caster_support::load_helper`).
|
||||
void reclaim_disowned() {
|
||||
reset_vptr_deleter_armed_flag(true);
|
||||
is_disowned = false;
|
||||
}
|
||||
|
||||
// Caller is responsible for ensuring the complex preconditions
|
||||
// (see `smart_holder_type_caster_support::load_helper`).
|
||||
void release_disowned() { vptr.reset(); }
|
||||
|
||||
void ensure_can_release_ownership(const char *context = "ensure_can_release_ownership") const {
|
||||
ensure_is_not_disowned(context);
|
||||
ensure_vptr_is_using_builtin_delete(context);
|
||||
ensure_use_count_1(context);
|
||||
}
|
||||
|
||||
// Caller is responsible for ensuring the complex preconditions
|
||||
// (see `smart_holder_type_caster_support::load_helper`).
|
||||
void release_ownership() {
|
||||
reset_vptr_deleter_armed_flag(false);
|
||||
release_disowned();
|
||||
}
|
||||
|
||||
template <typename T, typename D>
|
||||
static smart_holder from_unique_ptr(std::unique_ptr<T, D> &&unq_ptr,
|
||||
void *void_ptr = nullptr) {
|
||||
smart_holder hld;
|
||||
hld.rtti_uqp_del = &typeid(D);
|
||||
hld.vptr_is_using_builtin_delete = is_std_default_delete<T>(*hld.rtti_uqp_del);
|
||||
guarded_delete gd{nullptr, false};
|
||||
if (hld.vptr_is_using_builtin_delete) {
|
||||
gd = make_guarded_builtin_delete<T>(true);
|
||||
} else {
|
||||
gd = make_guarded_custom_deleter<T, D>(std::move(unq_ptr.get_deleter()), true);
|
||||
}
|
||||
if (void_ptr != nullptr) {
|
||||
hld.vptr.reset(void_ptr, std::move(gd));
|
||||
} else {
|
||||
hld.vptr.reset(unq_ptr.get(), std::move(gd));
|
||||
}
|
||||
(void) unq_ptr.release();
|
||||
hld.is_populated = true;
|
||||
return hld;
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static smart_holder from_shared_ptr(std::shared_ptr<T> shd_ptr) {
|
||||
smart_holder hld;
|
||||
hld.vptr = std::static_pointer_cast<void>(shd_ptr);
|
||||
hld.vptr_is_external_shared_ptr = true;
|
||||
hld.is_populated = true;
|
||||
return hld;
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
std::shared_ptr<T> as_shared_ptr() const {
|
||||
return std::static_pointer_cast<T>(vptr);
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace memory
|
||||
} // namespace pybindit
|
|
@ -9,17 +9,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <pybind11/gil.h>
|
||||
#include <pybind11/pytypes.h>
|
||||
#include <pybind11/trampoline_self_life_support.h>
|
||||
|
||||
#include "common.h"
|
||||
#include "cpp_conduit.h"
|
||||
#include "descr.h"
|
||||
#include "dynamic_raw_ptr_cast_if_possible.h"
|
||||
#include "internals.h"
|
||||
#include "typeid.h"
|
||||
#include "using_smart_holder.h"
|
||||
#include "value_and_holder.h"
|
||||
|
||||
#include <cstdint>
|
||||
|
@ -47,7 +43,11 @@ private:
|
|||
|
||||
// Store stack pointer in thread-local storage.
|
||||
static PYBIND11_TLS_KEY_REF get_stack_tls_key() {
|
||||
#if PYBIND11_INTERNALS_VERSION == 4
|
||||
return get_local_internals().loader_life_support_tls_key;
|
||||
#else
|
||||
return get_internals().loader_life_support_tls_key;
|
||||
#endif
|
||||
}
|
||||
static loader_life_support *get_stack_top() {
|
||||
return static_cast<loader_life_support *>(PYBIND11_TLS_GET_VALUE(get_stack_tls_key()));
|
||||
|
@ -117,6 +117,7 @@ PYBIND11_NOINLINE void all_type_info_populate(PyTypeObject *t, std::vector<type_
|
|||
for (handle parent : reinterpret_borrow<tuple>(t->tp_bases)) {
|
||||
check.push_back((PyTypeObject *) parent.ptr());
|
||||
}
|
||||
|
||||
auto const &type_dict = get_internals().registered_types_py;
|
||||
for (size_t i = 0; i < check.size(); i++) {
|
||||
auto *type = check[i];
|
||||
|
@ -175,7 +176,13 @@ PYBIND11_NOINLINE void all_type_info_populate(PyTypeObject *t, std::vector<type_
|
|||
* The value is cached for the lifetime of the Python type.
|
||||
*/
|
||||
inline const std::vector<detail::type_info *> &all_type_info(PyTypeObject *type) {
|
||||
return all_type_info_get_cache(type).first->second;
|
||||
auto ins = all_type_info_get_cache(type);
|
||||
if (ins.second) {
|
||||
// New cache entry: populate it
|
||||
all_type_info_populate(type, ins.first->second);
|
||||
}
|
||||
|
||||
return ins.first->second;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -241,49 +248,6 @@ PYBIND11_NOINLINE handle get_type_handle(const std::type_info &tp, bool throw_if
|
|||
return handle(type_info ? ((PyObject *) type_info->type) : nullptr);
|
||||
}
|
||||
|
||||
inline bool try_incref(PyObject *obj) {
|
||||
// Tries to increment the reference count of an object if it's not zero.
|
||||
// TODO: Use PyUnstable_TryIncref when available.
|
||||
// See https://github.com/python/cpython/issues/128844
|
||||
#ifdef Py_GIL_DISABLED
|
||||
// See
|
||||
// https://github.com/python/cpython/blob/d05140f9f77d7dfc753dd1e5ac3a5962aaa03eff/Include/internal/pycore_object.h#L761
|
||||
uint32_t local = _Py_atomic_load_uint32_relaxed(&obj->ob_ref_local);
|
||||
local += 1;
|
||||
if (local == 0) {
|
||||
// immortal
|
||||
return true;
|
||||
}
|
||||
if (_Py_IsOwnedByCurrentThread(obj)) {
|
||||
_Py_atomic_store_uint32_relaxed(&obj->ob_ref_local, local);
|
||||
# ifdef Py_REF_DEBUG
|
||||
_Py_INCREF_IncRefTotal();
|
||||
# endif
|
||||
return true;
|
||||
}
|
||||
Py_ssize_t shared = _Py_atomic_load_ssize_relaxed(&obj->ob_ref_shared);
|
||||
for (;;) {
|
||||
// If the shared refcount is zero and the object is either merged
|
||||
// or may not have weak references, then we cannot incref it.
|
||||
if (shared == 0 || shared == _Py_REF_MERGED) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (_Py_atomic_compare_exchange_ssize(
|
||||
&obj->ob_ref_shared, &shared, shared + (1 << _Py_REF_SHARED_SHIFT))) {
|
||||
# ifdef Py_REF_DEBUG
|
||||
_Py_INCREF_IncRefTotal();
|
||||
# endif
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#else
|
||||
assert(Py_REFCNT(obj) > 0);
|
||||
Py_INCREF(obj);
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
// Searches the inheritance graph for a registered Python instance, using all_type_info().
|
||||
PYBIND11_NOINLINE handle find_registered_python_instance(void *src,
|
||||
const detail::type_info *tinfo) {
|
||||
|
@ -292,10 +256,7 @@ PYBIND11_NOINLINE handle find_registered_python_instance(void *src,
|
|||
for (auto it_i = it_instances.first; it_i != it_instances.second; ++it_i) {
|
||||
for (auto *instance_type : detail::all_type_info(Py_TYPE(it_i->second))) {
|
||||
if (instance_type && same_type(*instance_type->cpptype, *tinfo->cpptype)) {
|
||||
auto *wrapper = reinterpret_cast<PyObject *>(it_i->second);
|
||||
if (try_incref(wrapper)) {
|
||||
return handle(wrapper);
|
||||
}
|
||||
return handle((PyObject *) it_i->second).inc_ref();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -498,7 +459,7 @@ PYBIND11_NOINLINE handle get_object_handle(const void *ptr, const detail::type_i
|
|||
}
|
||||
|
||||
inline PyThreadState *get_thread_state_unchecked() {
|
||||
#if defined(PYPY_VERSION) || defined(GRAALVM_PYTHON)
|
||||
#if defined(PYPY_VERSION)
|
||||
return PyThreadState_GET();
|
||||
#elif PY_VERSION_HEX < 0x030D0000
|
||||
return _PyThreadState_UncheckedGet();
|
||||
|
@ -511,361 +472,6 @@ inline PyThreadState *get_thread_state_unchecked() {
|
|||
void keep_alive_impl(handle nurse, handle patient);
|
||||
inline PyObject *make_new_instance(PyTypeObject *type);
|
||||
|
||||
// PYBIND11:REMINDER: Needs refactoring of existing pybind11 code.
|
||||
inline bool deregister_instance(instance *self, void *valptr, const type_info *tinfo);
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(smart_holder_type_caster_support)
|
||||
|
||||
struct value_and_holder_helper {
|
||||
value_and_holder loaded_v_h;
|
||||
|
||||
bool have_holder() const {
|
||||
return loaded_v_h.vh != nullptr && loaded_v_h.holder_constructed();
|
||||
}
|
||||
|
||||
smart_holder &holder() const { return loaded_v_h.holder<smart_holder>(); }
|
||||
|
||||
void throw_if_uninitialized_or_disowned_holder(const char *typeid_name) const {
|
||||
static const std::string missing_value_msg = "Missing value for wrapped C++ type `";
|
||||
if (!holder().is_populated) {
|
||||
throw value_error(missing_value_msg + clean_type_id(typeid_name)
|
||||
+ "`: Python instance is uninitialized.");
|
||||
}
|
||||
if (!holder().has_pointee()) {
|
||||
throw value_error(missing_value_msg + clean_type_id(typeid_name)
|
||||
+ "`: Python instance was disowned.");
|
||||
}
|
||||
}
|
||||
|
||||
void throw_if_uninitialized_or_disowned_holder(const std::type_info &type_info) const {
|
||||
throw_if_uninitialized_or_disowned_holder(type_info.name());
|
||||
}
|
||||
|
||||
// have_holder() must be true or this function will fail.
|
||||
void throw_if_instance_is_currently_owned_by_shared_ptr() const {
|
||||
auto *vptr_gd_ptr = std::get_deleter<pybindit::memory::guarded_delete>(holder().vptr);
|
||||
if (vptr_gd_ptr != nullptr && !vptr_gd_ptr->released_ptr.expired()) {
|
||||
throw value_error("Python instance is currently owned by a std::shared_ptr.");
|
||||
}
|
||||
}
|
||||
|
||||
void *get_void_ptr_or_nullptr() const {
|
||||
if (have_holder()) {
|
||||
auto &hld = holder();
|
||||
if (hld.is_populated && hld.has_pointee()) {
|
||||
return hld.template as_raw_ptr_unowned<void>();
|
||||
}
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
};
|
||||
|
||||
template <typename T, typename D>
|
||||
handle smart_holder_from_unique_ptr(std::unique_ptr<T, D> &&src,
|
||||
return_value_policy policy,
|
||||
handle parent,
|
||||
const std::pair<const void *, const type_info *> &st) {
|
||||
if (policy == return_value_policy::copy) {
|
||||
throw cast_error("return_value_policy::copy is invalid for unique_ptr.");
|
||||
}
|
||||
if (!src) {
|
||||
return none().release();
|
||||
}
|
||||
void *src_raw_void_ptr = const_cast<void *>(st.first);
|
||||
assert(st.second != nullptr);
|
||||
const detail::type_info *tinfo = st.second;
|
||||
if (handle existing_inst = find_registered_python_instance(src_raw_void_ptr, tinfo)) {
|
||||
auto *self_life_support
|
||||
= dynamic_raw_ptr_cast_if_possible<trampoline_self_life_support>(src.get());
|
||||
if (self_life_support != nullptr) {
|
||||
value_and_holder &v_h = self_life_support->v_h;
|
||||
if (v_h.inst != nullptr && v_h.vh != nullptr) {
|
||||
auto &holder = v_h.holder<smart_holder>();
|
||||
if (!holder.is_disowned) {
|
||||
pybind11_fail("smart_holder_from_unique_ptr: unexpected "
|
||||
"smart_holder.is_disowned failure.");
|
||||
}
|
||||
// Critical transfer-of-ownership section. This must stay together.
|
||||
self_life_support->deactivate_life_support();
|
||||
holder.reclaim_disowned();
|
||||
(void) src.release();
|
||||
// Critical section end.
|
||||
return existing_inst;
|
||||
}
|
||||
}
|
||||
throw cast_error("Invalid unique_ptr: another instance owns this pointer already.");
|
||||
}
|
||||
|
||||
auto inst = reinterpret_steal<object>(make_new_instance(tinfo->type));
|
||||
auto *inst_raw_ptr = reinterpret_cast<instance *>(inst.ptr());
|
||||
inst_raw_ptr->owned = true;
|
||||
void *&valueptr = values_and_holders(inst_raw_ptr).begin()->value_ptr();
|
||||
valueptr = src_raw_void_ptr;
|
||||
|
||||
if (static_cast<void *>(src.get()) == src_raw_void_ptr) {
|
||||
// This is a multiple-inheritance situation that is incompatible with the current
|
||||
// shared_from_this handling (see PR #3023). Is there a better solution?
|
||||
src_raw_void_ptr = nullptr;
|
||||
}
|
||||
auto smhldr = smart_holder::from_unique_ptr(std::move(src), src_raw_void_ptr);
|
||||
tinfo->init_instance(inst_raw_ptr, static_cast<const void *>(&smhldr));
|
||||
|
||||
if (policy == return_value_policy::reference_internal) {
|
||||
keep_alive_impl(inst, parent);
|
||||
}
|
||||
|
||||
return inst.release();
|
||||
}
|
||||
|
||||
template <typename T, typename D>
|
||||
handle smart_holder_from_unique_ptr(std::unique_ptr<T const, D> &&src,
|
||||
return_value_policy policy,
|
||||
handle parent,
|
||||
const std::pair<const void *, const type_info *> &st) {
|
||||
return smart_holder_from_unique_ptr(
|
||||
std::unique_ptr<T, D>(const_cast<T *>(src.release()),
|
||||
std::move(src.get_deleter())), // Const2Mutbl
|
||||
policy,
|
||||
parent,
|
||||
st);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
handle smart_holder_from_shared_ptr(const std::shared_ptr<T> &src,
|
||||
return_value_policy policy,
|
||||
handle parent,
|
||||
const std::pair<const void *, const type_info *> &st) {
|
||||
switch (policy) {
|
||||
case return_value_policy::automatic:
|
||||
case return_value_policy::automatic_reference:
|
||||
break;
|
||||
case return_value_policy::take_ownership:
|
||||
throw cast_error("Invalid return_value_policy for shared_ptr (take_ownership).");
|
||||
case return_value_policy::copy:
|
||||
case return_value_policy::move:
|
||||
break;
|
||||
case return_value_policy::reference:
|
||||
throw cast_error("Invalid return_value_policy for shared_ptr (reference).");
|
||||
case return_value_policy::reference_internal:
|
||||
break;
|
||||
}
|
||||
if (!src) {
|
||||
return none().release();
|
||||
}
|
||||
|
||||
auto src_raw_ptr = src.get();
|
||||
assert(st.second != nullptr);
|
||||
void *src_raw_void_ptr = static_cast<void *>(src_raw_ptr);
|
||||
const detail::type_info *tinfo = st.second;
|
||||
if (handle existing_inst = find_registered_python_instance(src_raw_void_ptr, tinfo)) {
|
||||
// PYBIND11:REMINDER: MISSING: Enforcement of consistency with existing smart_holder.
|
||||
// PYBIND11:REMINDER: MISSING: keep_alive.
|
||||
return existing_inst;
|
||||
}
|
||||
|
||||
auto inst = reinterpret_steal<object>(make_new_instance(tinfo->type));
|
||||
auto *inst_raw_ptr = reinterpret_cast<instance *>(inst.ptr());
|
||||
inst_raw_ptr->owned = true;
|
||||
void *&valueptr = values_and_holders(inst_raw_ptr).begin()->value_ptr();
|
||||
valueptr = src_raw_void_ptr;
|
||||
|
||||
auto smhldr
|
||||
= smart_holder::from_shared_ptr(std::shared_ptr<void>(src, const_cast<void *>(st.first)));
|
||||
tinfo->init_instance(inst_raw_ptr, static_cast<const void *>(&smhldr));
|
||||
|
||||
if (policy == return_value_policy::reference_internal) {
|
||||
keep_alive_impl(inst, parent);
|
||||
}
|
||||
|
||||
return inst.release();
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
handle smart_holder_from_shared_ptr(const std::shared_ptr<T const> &src,
|
||||
return_value_policy policy,
|
||||
handle parent,
|
||||
const std::pair<const void *, const type_info *> &st) {
|
||||
return smart_holder_from_shared_ptr(std::const_pointer_cast<T>(src), // Const2Mutbl
|
||||
policy,
|
||||
parent,
|
||||
st);
|
||||
}
|
||||
|
||||
struct shared_ptr_parent_life_support {
|
||||
PyObject *parent;
|
||||
explicit shared_ptr_parent_life_support(PyObject *parent) : parent{parent} {
|
||||
Py_INCREF(parent);
|
||||
}
|
||||
// NOLINTNEXTLINE(readability-make-member-function-const)
|
||||
void operator()(void *) {
|
||||
gil_scoped_acquire gil;
|
||||
Py_DECREF(parent);
|
||||
}
|
||||
};
|
||||
|
||||
struct shared_ptr_trampoline_self_life_support {
|
||||
PyObject *self;
|
||||
explicit shared_ptr_trampoline_self_life_support(instance *inst)
|
||||
: self{reinterpret_cast<PyObject *>(inst)} {
|
||||
gil_scoped_acquire gil;
|
||||
Py_INCREF(self);
|
||||
}
|
||||
// NOLINTNEXTLINE(readability-make-member-function-const)
|
||||
void operator()(void *) {
|
||||
gil_scoped_acquire gil;
|
||||
Py_DECREF(self);
|
||||
}
|
||||
};
|
||||
|
||||
template <typename T,
|
||||
typename D,
|
||||
typename std::enable_if<std::is_default_constructible<D>::value, int>::type = 0>
|
||||
inline std::unique_ptr<T, D> unique_with_deleter(T *raw_ptr, std::unique_ptr<D> &&deleter) {
|
||||
if (deleter == nullptr) {
|
||||
return std::unique_ptr<T, D>(raw_ptr);
|
||||
}
|
||||
return std::unique_ptr<T, D>(raw_ptr, std::move(*deleter));
|
||||
}
|
||||
|
||||
template <typename T,
|
||||
typename D,
|
||||
typename std::enable_if<!std::is_default_constructible<D>::value, int>::type = 0>
|
||||
inline std::unique_ptr<T, D> unique_with_deleter(T *raw_ptr, std::unique_ptr<D> &&deleter) {
|
||||
if (deleter == nullptr) {
|
||||
pybind11_fail("smart_holder_type_casters: deleter is not default constructible and no"
|
||||
" instance available to return.");
|
||||
}
|
||||
return std::unique_ptr<T, D>(raw_ptr, std::move(*deleter));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
struct load_helper : value_and_holder_helper {
|
||||
bool was_populated = false;
|
||||
bool python_instance_is_alias = false;
|
||||
|
||||
void maybe_set_python_instance_is_alias(handle src) {
|
||||
if (was_populated) {
|
||||
python_instance_is_alias = reinterpret_cast<instance *>(src.ptr())->is_alias;
|
||||
}
|
||||
}
|
||||
|
||||
static std::shared_ptr<T> make_shared_ptr_with_responsible_parent(T *raw_ptr, handle parent) {
|
||||
return std::shared_ptr<T>(raw_ptr, shared_ptr_parent_life_support(parent.ptr()));
|
||||
}
|
||||
|
||||
std::shared_ptr<T> load_as_shared_ptr(void *void_raw_ptr,
|
||||
handle responsible_parent = nullptr) const {
|
||||
if (!have_holder()) {
|
||||
return nullptr;
|
||||
}
|
||||
throw_if_uninitialized_or_disowned_holder(typeid(T));
|
||||
smart_holder &hld = holder();
|
||||
hld.ensure_is_not_disowned("load_as_shared_ptr");
|
||||
if (hld.vptr_is_using_noop_deleter) {
|
||||
if (responsible_parent) {
|
||||
return make_shared_ptr_with_responsible_parent(static_cast<T *>(void_raw_ptr),
|
||||
responsible_parent);
|
||||
}
|
||||
throw std::runtime_error("Non-owning holder (load_as_shared_ptr).");
|
||||
}
|
||||
auto *type_raw_ptr = static_cast<T *>(void_raw_ptr);
|
||||
if (python_instance_is_alias) {
|
||||
auto *vptr_gd_ptr = std::get_deleter<pybindit::memory::guarded_delete>(hld.vptr);
|
||||
if (vptr_gd_ptr != nullptr) {
|
||||
std::shared_ptr<void> released_ptr = vptr_gd_ptr->released_ptr.lock();
|
||||
if (released_ptr) {
|
||||
return std::shared_ptr<T>(released_ptr, type_raw_ptr);
|
||||
}
|
||||
std::shared_ptr<T> to_be_released(
|
||||
type_raw_ptr, shared_ptr_trampoline_self_life_support(loaded_v_h.inst));
|
||||
vptr_gd_ptr->released_ptr = to_be_released;
|
||||
return to_be_released;
|
||||
}
|
||||
auto *sptsls_ptr = std::get_deleter<shared_ptr_trampoline_self_life_support>(hld.vptr);
|
||||
if (sptsls_ptr != nullptr) {
|
||||
// This code is reachable only if there are multiple registered_instances for the
|
||||
// same pointee.
|
||||
if (reinterpret_cast<PyObject *>(loaded_v_h.inst) == sptsls_ptr->self) {
|
||||
pybind11_fail("smart_holder_type_caster_support load_as_shared_ptr failure: "
|
||||
"loaded_v_h.inst == sptsls_ptr->self");
|
||||
}
|
||||
}
|
||||
if (sptsls_ptr != nullptr
|
||||
|| !pybindit::memory::type_has_shared_from_this(type_raw_ptr)) {
|
||||
return std::shared_ptr<T>(
|
||||
type_raw_ptr, shared_ptr_trampoline_self_life_support(loaded_v_h.inst));
|
||||
}
|
||||
if (hld.vptr_is_external_shared_ptr) {
|
||||
pybind11_fail("smart_holder_type_casters load_as_shared_ptr failure: not "
|
||||
"implemented: trampoline-self-life-support for external shared_ptr "
|
||||
"to type inheriting from std::enable_shared_from_this.");
|
||||
}
|
||||
pybind11_fail(
|
||||
"smart_holder_type_casters: load_as_shared_ptr failure: internal inconsistency.");
|
||||
}
|
||||
std::shared_ptr<void> void_shd_ptr = hld.template as_shared_ptr<void>();
|
||||
return std::shared_ptr<T>(void_shd_ptr, type_raw_ptr);
|
||||
}
|
||||
|
||||
template <typename D>
|
||||
std::unique_ptr<T, D> load_as_unique_ptr(void *raw_void_ptr,
|
||||
const char *context = "load_as_unique_ptr") {
|
||||
if (!have_holder()) {
|
||||
return unique_with_deleter<T, D>(nullptr, std::unique_ptr<D>());
|
||||
}
|
||||
throw_if_uninitialized_or_disowned_holder(typeid(T));
|
||||
throw_if_instance_is_currently_owned_by_shared_ptr();
|
||||
holder().ensure_is_not_disowned(context);
|
||||
holder().template ensure_compatible_rtti_uqp_del<T, D>(context);
|
||||
holder().ensure_use_count_1(context);
|
||||
|
||||
T *raw_type_ptr = static_cast<T *>(raw_void_ptr);
|
||||
|
||||
auto *self_life_support
|
||||
= dynamic_raw_ptr_cast_if_possible<trampoline_self_life_support>(raw_type_ptr);
|
||||
if (self_life_support == nullptr && python_instance_is_alias) {
|
||||
throw value_error("Alias class (also known as trampoline) does not inherit from "
|
||||
"py::trampoline_self_life_support, therefore the ownership of this "
|
||||
"instance cannot safely be transferred to C++.");
|
||||
}
|
||||
|
||||
std::unique_ptr<D> extracted_deleter = holder().template extract_deleter<T, D>(context);
|
||||
|
||||
// Critical transfer-of-ownership section. This must stay together.
|
||||
if (self_life_support != nullptr) {
|
||||
holder().disown();
|
||||
} else {
|
||||
holder().release_ownership();
|
||||
}
|
||||
auto result = unique_with_deleter<T, D>(raw_type_ptr, std::move(extracted_deleter));
|
||||
if (self_life_support != nullptr) {
|
||||
self_life_support->activate_life_support(loaded_v_h);
|
||||
} else {
|
||||
void *value_void_ptr = loaded_v_h.value_ptr();
|
||||
loaded_v_h.value_ptr() = nullptr;
|
||||
deregister_instance(loaded_v_h.inst, value_void_ptr, loaded_v_h.type);
|
||||
}
|
||||
// Critical section end.
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
// This assumes load_as_shared_ptr succeeded(), and the returned shared_ptr is still alive.
|
||||
// The returned unique_ptr is meant to never expire (the behavior is undefined otherwise).
|
||||
template <typename D>
|
||||
std::unique_ptr<T, D>
|
||||
load_as_const_unique_ptr(T *raw_type_ptr, const char *context = "load_as_const_unique_ptr") {
|
||||
if (!have_holder()) {
|
||||
return unique_with_deleter<T, D>(nullptr, std::unique_ptr<D>());
|
||||
}
|
||||
holder().template ensure_compatible_rtti_uqp_del<T, D>(context);
|
||||
return unique_with_deleter<T, D>(
|
||||
raw_type_ptr, std::move(holder().template extract_deleter<T, D>(context)));
|
||||
}
|
||||
};
|
||||
|
||||
PYBIND11_NAMESPACE_END(smart_holder_type_caster_support)
|
||||
|
||||
class type_caster_generic {
|
||||
public:
|
||||
PYBIND11_NOINLINE explicit type_caster_generic(const std::type_info &type_info)
|
||||
|
@ -970,15 +576,6 @@ public:
|
|||
|
||||
// Base methods for generic caster; there are overridden in copyable_holder_caster
|
||||
void load_value(value_and_holder &&v_h) {
|
||||
if (typeinfo->holder_enum_v == detail::holder_enum_t::smart_holder) {
|
||||
smart_holder_type_caster_support::value_and_holder_helper v_h_helper;
|
||||
v_h_helper.loaded_v_h = v_h;
|
||||
if (v_h_helper.have_holder()) {
|
||||
v_h_helper.throw_if_uninitialized_or_disowned_holder(cpptype->name());
|
||||
value = v_h_helper.holder().template as_raw_ptr_unowned<void>();
|
||||
return;
|
||||
}
|
||||
}
|
||||
auto *&vptr = v_h.value_ptr();
|
||||
// Lazy allocation for unallocated values:
|
||||
if (vptr == nullptr) {
|
||||
|
@ -1564,14 +1161,14 @@ protected:
|
|||
does not have a private operator new implementation. A comma operator is used in the
|
||||
decltype argument to apply SFINAE to the public copy/move constructors.*/
|
||||
template <typename T, typename = enable_if_t<is_copy_constructible<T>::value>>
|
||||
static auto make_copy_constructor(const T *)
|
||||
-> decltype(new T(std::declval<const T>()), Constructor{}) {
|
||||
static auto make_copy_constructor(const T *) -> decltype(new T(std::declval<const T>()),
|
||||
Constructor{}) {
|
||||
return [](const void *arg) -> void * { return new T(*reinterpret_cast<const T *>(arg)); };
|
||||
}
|
||||
|
||||
template <typename T, typename = enable_if_t<is_move_constructible<T>::value>>
|
||||
static auto make_move_constructor(const T *)
|
||||
-> decltype(new T(std::declval<T &&>()), Constructor{}) {
|
||||
static auto make_move_constructor(const T *) -> decltype(new T(std::declval<T &&>()),
|
||||
Constructor{}) {
|
||||
return [](const void *arg) -> void * {
|
||||
return new T(std::move(*const_cast<T *>(reinterpret_cast<const T *>(arg))));
|
||||
};
|
||||
|
|
|
@ -1,22 +0,0 @@
|
|||
// Copyright (c) 2024 The Pybind Development Team.
|
||||
// All rights reserved. Use of this source code is governed by a
|
||||
// BSD-style license that can be found in the LICENSE file.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common.h"
|
||||
#include "struct_smart_holder.h"
|
||||
|
||||
#include <type_traits>
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
|
||||
using pybindit::memory::smart_holder;
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
|
||||
template <typename H>
|
||||
using is_smart_holder = std::is_same<H, smart_holder>;
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE)
|
|
@ -7,7 +7,6 @@
|
|||
#include "common.h"
|
||||
|
||||
#include <cstddef>
|
||||
#include <cstdint>
|
||||
#include <typeinfo>
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
|
|
|
@ -225,22 +225,19 @@ struct EigenProps {
|
|||
= !show_c_contiguous && show_order && requires_col_major;
|
||||
|
||||
static constexpr auto descriptor
|
||||
= const_name("typing.Annotated[")
|
||||
+ io_name("numpy.typing.ArrayLike, ", "numpy.typing.NDArray[")
|
||||
+ npy_format_descriptor<Scalar>::name + io_name("", "]") + const_name(", \"[")
|
||||
= const_name("numpy.ndarray[") + npy_format_descriptor<Scalar>::name + const_name("[")
|
||||
+ const_name<fixed_rows>(const_name<(size_t) rows>(), const_name("m")) + const_name(", ")
|
||||
+ const_name<fixed_cols>(const_name<(size_t) cols>(), const_name("n"))
|
||||
+ const_name("]\"")
|
||||
+ const_name<fixed_cols>(const_name<(size_t) cols>(), const_name("n")) + const_name("]")
|
||||
+
|
||||
// For a reference type (e.g. Ref<MatrixXd>) we have other constraints that might need to
|
||||
// be satisfied: writeable=True (for a mutable reference), and, depending on the map's
|
||||
// stride options, possibly f_contiguous or c_contiguous. We include them in the
|
||||
// descriptor output to provide some hint as to why a TypeError is occurring (otherwise
|
||||
// it can be confusing to see that a function accepts a
|
||||
// 'typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3,2]"]' and an error message
|
||||
// that you *gave* a numpy.ndarray of the right type and dimensions.
|
||||
+ const_name<show_writeable>(", \"flags.writeable\"", "")
|
||||
+ const_name<show_c_contiguous>(", \"flags.c_contiguous\"", "")
|
||||
+ const_name<show_f_contiguous>(", \"flags.f_contiguous\"", "") + const_name("]");
|
||||
// it can be confusing to see that a function accepts a 'numpy.ndarray[float64[3,2]]' and
|
||||
// an error message that you *gave* a numpy.ndarray of the right type and dimensions.
|
||||
const_name<show_writeable>(", flags.writeable", "")
|
||||
+ const_name<show_c_contiguous>(", flags.c_contiguous", "")
|
||||
+ const_name<show_f_contiguous>(", flags.f_contiguous", "") + const_name("]");
|
||||
};
|
||||
|
||||
// Casts an Eigen type to numpy array. If given a base, the numpy array references the src data,
|
||||
|
@ -319,11 +316,8 @@ struct type_caster<Type, enable_if_t<is_eigen_dense_plain<Type>::value>> {
|
|||
return false;
|
||||
}
|
||||
|
||||
PYBIND11_WARNING_PUSH
|
||||
PYBIND11_WARNING_DISABLE_GCC("-Wmaybe-uninitialized") // See PR #5516
|
||||
// Allocate the new type, then build a numpy reference into it
|
||||
value = Type(fits.rows, fits.cols);
|
||||
PYBIND11_WARNING_POP
|
||||
auto ref = reinterpret_steal<array>(eigen_ref_array<props>(value));
|
||||
if (dims == 1) {
|
||||
ref = ref.squeeze();
|
||||
|
@ -444,9 +438,7 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
// return_descr forces the use of NDArray instead of ArrayLike in args
|
||||
// since Ref<...> args can only accept arrays.
|
||||
static constexpr auto name = return_descr(props::descriptor);
|
||||
static constexpr auto name = props::descriptor;
|
||||
|
||||
// Explicitly delete these: support python -> C++ conversion on these (i.e. these can be return
|
||||
// types but not bound arguments). We still provide them (with an explicitly delete) so that
|
||||
|
|
|
@ -124,16 +124,13 @@ struct eigen_tensor_helper<
|
|||
template <typename Type, bool ShowDetails, bool NeedsWriteable = false>
|
||||
struct get_tensor_descriptor {
|
||||
static constexpr auto details
|
||||
= const_name<NeedsWriteable>(", \"flags.writeable\"", "") + const_name
|
||||
< static_cast<int>(Type::Layout)
|
||||
== static_cast<int>(Eigen::RowMajor)
|
||||
> (", \"flags.c_contiguous\"", ", \"flags.f_contiguous\"");
|
||||
= const_name<NeedsWriteable>(", flags.writeable", "")
|
||||
+ const_name<static_cast<int>(Type::Layout) == static_cast<int>(Eigen::RowMajor)>(
|
||||
", flags.c_contiguous", ", flags.f_contiguous");
|
||||
static constexpr auto value
|
||||
= const_name("typing.Annotated[")
|
||||
+ io_name("numpy.typing.ArrayLike, ", "numpy.typing.NDArray[")
|
||||
+ npy_format_descriptor<typename Type::Scalar>::name + io_name("", "]")
|
||||
+ const_name(", \"[") + eigen_tensor_helper<remove_cv_t<Type>>::dimensions_descriptor
|
||||
+ const_name("]\"") + const_name<ShowDetails>(details, const_name("")) + const_name("]");
|
||||
= const_name("numpy.ndarray[") + npy_format_descriptor<typename Type::Scalar>::name
|
||||
+ const_name("[") + eigen_tensor_helper<remove_cv_t<Type>>::dimensions_descriptor
|
||||
+ const_name("]") + const_name<ShowDetails>(details, const_name("")) + const_name("]");
|
||||
};
|
||||
|
||||
// When EIGEN_AVOID_STL_ARRAY is defined, Eigen::DSizes<T, 0> does not have the begin() member
|
||||
|
@ -505,10 +502,7 @@ protected:
|
|||
std::unique_ptr<MapType> value;
|
||||
|
||||
public:
|
||||
// return_descr forces the use of NDArray instead of ArrayLike since refs can only reference
|
||||
// arrays
|
||||
static constexpr auto name
|
||||
= return_descr(get_tensor_descriptor<Type, true, needs_writeable>::value);
|
||||
static constexpr auto name = get_tensor_descriptor<Type, true, needs_writeable>::value;
|
||||
explicit operator MapType *() { return value.get(); }
|
||||
explicit operator MapType &() { return *value; }
|
||||
explicit operator MapType &&() && { return std::move(*value); }
|
||||
|
|
|
@ -104,13 +104,23 @@ inline void initialize_interpreter_pre_pyconfig(bool init_signal_handlers,
|
|||
detail::precheck_interpreter();
|
||||
Py_InitializeEx(init_signal_handlers ? 1 : 0);
|
||||
|
||||
// Before it was special-cased in python 3.8, passing an empty or null argv
|
||||
// caused a segfault, so we have to reimplement the special case ourselves.
|
||||
bool special_case = (argv == nullptr || argc <= 0);
|
||||
|
||||
const char *const empty_argv[]{"\0"};
|
||||
const char *const *safe_argv = special_case ? empty_argv : argv;
|
||||
if (special_case) {
|
||||
argc = 1;
|
||||
}
|
||||
|
||||
auto argv_size = static_cast<size_t>(argc);
|
||||
// SetArgv* on python 3 takes wchar_t, so we have to convert.
|
||||
std::unique_ptr<wchar_t *[]> widened_argv(new wchar_t *[argv_size]);
|
||||
std::vector<std::unique_ptr<wchar_t[], detail::wide_char_arg_deleter>> widened_argv_entries;
|
||||
widened_argv_entries.reserve(argv_size);
|
||||
for (size_t ii = 0; ii < argv_size; ++ii) {
|
||||
widened_argv_entries.emplace_back(detail::widen_chars(argv[ii]));
|
||||
widened_argv_entries.emplace_back(detail::widen_chars(safe_argv[ii]));
|
||||
if (!widened_argv_entries.back()) {
|
||||
// A null here indicates a character-encoding failure or the python
|
||||
// interpreter out of memory. Give up.
|
||||
|
|
|
@ -19,7 +19,7 @@ PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
|||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
|
||||
inline void ensure_builtins_in_globals(object &global) {
|
||||
#if defined(PYPY_VERSION)
|
||||
#if defined(PYPY_VERSION) || PY_VERSION_HEX < 0x03080000
|
||||
// Running exec and eval adds `builtins` module under `__builtins__` key to
|
||||
// globals if not yet present. Python 3.8 made PyRun_String behave
|
||||
// similarly. Let's also do that for older versions, for consistency. This
|
||||
|
@ -94,18 +94,18 @@ void exec(const char (&s)[N], object global = globals(), object local = object()
|
|||
eval<eval_statements>(s, std::move(global), std::move(local));
|
||||
}
|
||||
|
||||
#if defined(PYPY_VERSION) || defined(GRAALVM_PYTHON)
|
||||
#if defined(PYPY_VERSION)
|
||||
template <eval_mode mode = eval_statements>
|
||||
object eval_file(str, object, object) {
|
||||
pybind11_fail("eval_file not supported in this interpreter. Use eval");
|
||||
pybind11_fail("eval_file not supported in PyPy3. Use eval");
|
||||
}
|
||||
template <eval_mode mode = eval_statements>
|
||||
object eval_file(str, object) {
|
||||
pybind11_fail("eval_file not supported in this interpreter. Use eval");
|
||||
pybind11_fail("eval_file not supported in PyPy3. Use eval");
|
||||
}
|
||||
template <eval_mode mode = eval_statements>
|
||||
object eval_file(str) {
|
||||
pybind11_fail("eval_file not supported in this interpreter. Use eval");
|
||||
pybind11_fail("eval_file not supported in PyPy3. Use eval");
|
||||
}
|
||||
#else
|
||||
template <eval_mode mode = eval_statements>
|
||||
|
|
|
@ -147,7 +147,9 @@ public:
|
|||
// NOLINTNEXTLINE(cppcoreguidelines-prefer-member-initializer)
|
||||
tstate = PyEval_SaveThread();
|
||||
if (disassoc) {
|
||||
auto key = internals.tstate; // NOLINT(readability-qualified-auto)
|
||||
// Python >= 3.7 can remove this, it's an int before 3.7
|
||||
// NOLINTNEXTLINE(readability-qualified-auto)
|
||||
auto key = internals.tstate;
|
||||
PYBIND11_TLS_DELETE_VALUE(key);
|
||||
}
|
||||
}
|
||||
|
@ -171,7 +173,9 @@ public:
|
|||
PyEval_RestoreThread(tstate);
|
||||
}
|
||||
if (disassoc) {
|
||||
auto key = detail::get_internals().tstate; // NOLINT(readability-qualified-auto)
|
||||
// Python >= 3.7 can remove this, it's an int before 3.7
|
||||
// NOLINTNEXTLINE(readability-qualified-auto)
|
||||
auto key = detail::get_internals().tstate;
|
||||
PYBIND11_TLS_REPLACE_VALUE(key, tstate);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -46,8 +46,6 @@ PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
|||
// get processed only when it is the main thread's turn again and it is running
|
||||
// normal Python code. However, this will be unnoticeable for quick call-once
|
||||
// functions, which is usually the case.
|
||||
//
|
||||
// For in-depth background, see docs/advanced/deadlock.md
|
||||
template <typename T>
|
||||
class gil_safe_call_once_and_store {
|
||||
public:
|
||||
|
|
|
@ -175,6 +175,7 @@ inline numpy_internals &get_numpy_internals() {
|
|||
PYBIND11_NOINLINE module_ import_numpy_core_submodule(const char *submodule_name) {
|
||||
module_ numpy = module_::import("numpy");
|
||||
str version_string = numpy.attr("__version__");
|
||||
|
||||
module_ numpy_lib = module_::import("numpy.lib");
|
||||
object numpy_version = numpy_lib.attr("NumpyVersion")(version_string);
|
||||
int major_version = numpy_version.attr("major").cast<int>();
|
||||
|
@ -211,7 +212,6 @@ constexpr int platform_lookup(int I, Ints... Is) {
|
|||
}
|
||||
|
||||
struct npy_api {
|
||||
// If you change this code, please review `normalized_dtype_num` below.
|
||||
enum constants {
|
||||
NPY_ARRAY_C_CONTIGUOUS_ = 0x0001,
|
||||
NPY_ARRAY_F_CONTIGUOUS_ = 0x0002,
|
||||
|
@ -384,74 +384,6 @@ private:
|
|||
}
|
||||
};
|
||||
|
||||
// This table normalizes typenums by mapping NPY_INT_, NPY_LONG, ... to NPY_INT32_, NPY_INT64, ...
|
||||
// This is needed to correctly handle situations where multiple typenums map to the same type,
|
||||
// e.g. NPY_LONG_ may be equivalent to NPY_INT_ or NPY_LONGLONG_ despite having a different
|
||||
// typenum. The normalized typenum should always match the values used in npy_format_descriptor.
|
||||
// If you change this code, please review `enum constants` above.
|
||||
static constexpr int normalized_dtype_num[npy_api::NPY_VOID_ + 1] = {
|
||||
// NPY_BOOL_ =>
|
||||
npy_api::NPY_BOOL_,
|
||||
// NPY_BYTE_ =>
|
||||
npy_api::NPY_BYTE_,
|
||||
// NPY_UBYTE_ =>
|
||||
npy_api::NPY_UBYTE_,
|
||||
// NPY_SHORT_ =>
|
||||
npy_api::NPY_INT16_,
|
||||
// NPY_USHORT_ =>
|
||||
npy_api::NPY_UINT16_,
|
||||
// NPY_INT_ =>
|
||||
sizeof(int) == sizeof(std::int16_t) ? npy_api::NPY_INT16_
|
||||
: sizeof(int) == sizeof(std::int32_t) ? npy_api::NPY_INT32_
|
||||
: sizeof(int) == sizeof(std::int64_t) ? npy_api::NPY_INT64_
|
||||
: npy_api::NPY_INT_,
|
||||
// NPY_UINT_ =>
|
||||
sizeof(unsigned int) == sizeof(std::uint16_t) ? npy_api::NPY_UINT16_
|
||||
: sizeof(unsigned int) == sizeof(std::uint32_t) ? npy_api::NPY_UINT32_
|
||||
: sizeof(unsigned int) == sizeof(std::uint64_t) ? npy_api::NPY_UINT64_
|
||||
: npy_api::NPY_UINT_,
|
||||
// NPY_LONG_ =>
|
||||
sizeof(long) == sizeof(std::int16_t) ? npy_api::NPY_INT16_
|
||||
: sizeof(long) == sizeof(std::int32_t) ? npy_api::NPY_INT32_
|
||||
: sizeof(long) == sizeof(std::int64_t) ? npy_api::NPY_INT64_
|
||||
: npy_api::NPY_LONG_,
|
||||
// NPY_ULONG_ =>
|
||||
sizeof(unsigned long) == sizeof(std::uint16_t) ? npy_api::NPY_UINT16_
|
||||
: sizeof(unsigned long) == sizeof(std::uint32_t) ? npy_api::NPY_UINT32_
|
||||
: sizeof(unsigned long) == sizeof(std::uint64_t) ? npy_api::NPY_UINT64_
|
||||
: npy_api::NPY_ULONG_,
|
||||
// NPY_LONGLONG_ =>
|
||||
sizeof(long long) == sizeof(std::int16_t) ? npy_api::NPY_INT16_
|
||||
: sizeof(long long) == sizeof(std::int32_t) ? npy_api::NPY_INT32_
|
||||
: sizeof(long long) == sizeof(std::int64_t) ? npy_api::NPY_INT64_
|
||||
: npy_api::NPY_LONGLONG_,
|
||||
// NPY_ULONGLONG_ =>
|
||||
sizeof(unsigned long long) == sizeof(std::uint16_t) ? npy_api::NPY_UINT16_
|
||||
: sizeof(unsigned long long) == sizeof(std::uint32_t) ? npy_api::NPY_UINT32_
|
||||
: sizeof(unsigned long long) == sizeof(std::uint64_t) ? npy_api::NPY_UINT64_
|
||||
: npy_api::NPY_ULONGLONG_,
|
||||
// NPY_FLOAT_ =>
|
||||
npy_api::NPY_FLOAT_,
|
||||
// NPY_DOUBLE_ =>
|
||||
npy_api::NPY_DOUBLE_,
|
||||
// NPY_LONGDOUBLE_ =>
|
||||
npy_api::NPY_LONGDOUBLE_,
|
||||
// NPY_CFLOAT_ =>
|
||||
npy_api::NPY_CFLOAT_,
|
||||
// NPY_CDOUBLE_ =>
|
||||
npy_api::NPY_CDOUBLE_,
|
||||
// NPY_CLONGDOUBLE_ =>
|
||||
npy_api::NPY_CLONGDOUBLE_,
|
||||
// NPY_OBJECT_ =>
|
||||
npy_api::NPY_OBJECT_,
|
||||
// NPY_STRING_ =>
|
||||
npy_api::NPY_STRING_,
|
||||
// NPY_UNICODE_ =>
|
||||
npy_api::NPY_UNICODE_,
|
||||
// NPY_VOID_ =>
|
||||
npy_api::NPY_VOID_,
|
||||
};
|
||||
|
||||
inline PyArray_Proxy *array_proxy(void *ptr) { return reinterpret_cast<PyArray_Proxy *>(ptr); }
|
||||
|
||||
inline const PyArray_Proxy *array_proxy(const void *ptr) {
|
||||
|
@ -752,13 +684,6 @@ public:
|
|||
return detail::npy_format_descriptor<typename std::remove_cv<T>::type>::dtype();
|
||||
}
|
||||
|
||||
/// Return the type number associated with a C++ type.
|
||||
/// This is the constexpr equivalent of `dtype::of<T>().num()`.
|
||||
template <typename T>
|
||||
static constexpr int num_of() {
|
||||
return detail::npy_format_descriptor<typename std::remove_cv<T>::type>::value;
|
||||
}
|
||||
|
||||
/// Size of the data type in bytes.
|
||||
#ifdef PYBIND11_NUMPY_1_ONLY
|
||||
ssize_t itemsize() const { return detail::array_descriptor_proxy(m_ptr)->elsize; }
|
||||
|
@ -800,9 +725,7 @@ public:
|
|||
return detail::array_descriptor_proxy(m_ptr)->type;
|
||||
}
|
||||
|
||||
/// Type number of dtype. Note that different values may be returned for equivalent types,
|
||||
/// e.g. even though ``long`` may be equivalent to ``int`` or ``long long``, they still have
|
||||
/// different type numbers. Consider using `normalized_num` to avoid this.
|
||||
/// type number of dtype.
|
||||
int num() const {
|
||||
// Note: The signature, `dtype::num` follows the naming of NumPy's public
|
||||
// Python API (i.e., ``dtype.num``), rather than its internal
|
||||
|
@ -810,17 +733,6 @@ public:
|
|||
return detail::array_descriptor_proxy(m_ptr)->type_num;
|
||||
}
|
||||
|
||||
/// Type number of dtype, normalized to match the return value of `num_of` for equivalent
|
||||
/// types. This function can be used to write switch statements that correctly handle
|
||||
/// equivalent types with different type numbers.
|
||||
int normalized_num() const {
|
||||
int value = num();
|
||||
if (value >= 0 && value <= detail::npy_api::NPY_VOID_) {
|
||||
return detail::normalized_dtype_num[value];
|
||||
}
|
||||
return value;
|
||||
}
|
||||
|
||||
/// Single character for byteorder
|
||||
char byteorder() const { return detail::array_descriptor_proxy(m_ptr)->byteorder; }
|
||||
|
||||
|
@ -1516,11 +1428,7 @@ public:
|
|||
};
|
||||
|
||||
template <typename T>
|
||||
struct npy_format_descriptor<
|
||||
T,
|
||||
enable_if_t<is_same_ignoring_cvref<T, PyObject *>::value
|
||||
|| ((std::is_same<T, handle>::value || std::is_same<T, object>::value)
|
||||
&& sizeof(T) == sizeof(PyObject *))>> {
|
||||
struct npy_format_descriptor<T, enable_if_t<is_same_ignoring_cvref<T, PyObject *>::value>> {
|
||||
static constexpr auto name = const_name("object");
|
||||
|
||||
static constexpr int value = npy_api::NPY_OBJECT_;
|
||||
|
@ -2182,8 +2090,7 @@ vectorize_helper<Func, Return, Args...> vectorize_extractor(const Func &f, Retur
|
|||
template <typename T, int Flags>
|
||||
struct handle_type_name<array_t<T, Flags>> {
|
||||
static constexpr auto name
|
||||
= io_name("typing.Annotated[numpy.typing.ArrayLike, ", "numpy.typing.NDArray[")
|
||||
+ npy_format_descriptor<T>::name + const_name("]");
|
||||
= const_name("numpy.ndarray[") + npy_format_descriptor<T>::name + const_name("]");
|
||||
};
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
|
|
|
@ -10,10 +10,8 @@
|
|||
|
||||
#pragma once
|
||||
#include "detail/class.h"
|
||||
#include "detail/dynamic_raw_ptr_cast_if_possible.h"
|
||||
#include "detail/exception_translation.h"
|
||||
#include "detail/init.h"
|
||||
#include "detail/using_smart_holder.h"
|
||||
#include "attr.h"
|
||||
#include "gil.h"
|
||||
#include "gil_safe_call_once.h"
|
||||
|
@ -24,17 +22,10 @@
|
|||
#include <cstring>
|
||||
#include <memory>
|
||||
#include <new>
|
||||
#include <stack>
|
||||
#include <string>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
// See PR #5448. This warning suppression is needed for the PYBIND11_OVERRIDE macro family.
|
||||
// NOTE that this is NOT embedded in a push/pop pair because that is very difficult to achieve.
|
||||
#if defined(__clang_major__) && __clang_major__ < 14
|
||||
PYBIND11_WARNING_DISABLE_CLANG("-Wgnu-zero-variadic-macro-arguments")
|
||||
#endif
|
||||
|
||||
#if defined(__cpp_lib_launder) && !(defined(_MSC_VER) && (_MSC_VER < 1914))
|
||||
# define PYBIND11_STD_LAUNDER std::launder
|
||||
# define PYBIND11_HAS_STD_LAUNDER 1
|
||||
|
@ -310,20 +301,9 @@ protected:
|
|||
constexpr bool has_kw_only_args = any_of<std::is_same<kw_only, Extra>...>::value,
|
||||
has_pos_only_args = any_of<std::is_same<pos_only, Extra>...>::value,
|
||||
has_arg_annotations = any_of<is_keyword<Extra>...>::value;
|
||||
constexpr bool has_is_method = any_of<std::is_same<is_method, Extra>...>::value;
|
||||
// The implicit `self` argument is not present and not counted in method definitions.
|
||||
constexpr bool has_args = cast_in::args_pos >= 0;
|
||||
constexpr bool is_method_with_self_arg_only = has_is_method && !has_args;
|
||||
static_assert(has_arg_annotations || !has_kw_only_args,
|
||||
"py::kw_only requires the use of argument annotations");
|
||||
static_assert(((/* Need `py::arg("arg_name")` annotation in function/method. */
|
||||
has_arg_annotations)
|
||||
|| (/* Allow methods with no arguments `def method(self, /): ...`.
|
||||
* A method has at least one argument `self`. There can be no
|
||||
* `py::arg` annotation. E.g. `class.def("method", py::pos_only())`.
|
||||
*/
|
||||
is_method_with_self_arg_only))
|
||||
|| !has_pos_only_args,
|
||||
static_assert(has_arg_annotations || !has_pos_only_args,
|
||||
"py::pos_only requires the use of argument annotations (for docstrings "
|
||||
"and aligning the annotations to the argument)");
|
||||
|
||||
|
@ -443,13 +423,6 @@ protected:
|
|||
std::string signature;
|
||||
size_t type_index = 0, arg_index = 0;
|
||||
bool is_starred = false;
|
||||
// `is_return_value.top()` is true if we are currently inside the return type of the
|
||||
// signature. Using `@^`/`@$` we can force types to be arg/return types while `@!` pops
|
||||
// back to the previous state.
|
||||
std::stack<bool> is_return_value({false});
|
||||
// The following characters have special meaning in the signature parsing. Literals
|
||||
// containing these are escaped with `!`.
|
||||
std::string special_chars("!@%{}-");
|
||||
for (const auto *pc = text; *pc != '\0'; ++pc) {
|
||||
const auto c = *pc;
|
||||
|
||||
|
@ -503,57 +476,7 @@ protected:
|
|||
} else {
|
||||
signature += detail::quote_cpp_type_name(detail::clean_type_id(t->name()));
|
||||
}
|
||||
} else if (c == '!' && special_chars.find(*(pc + 1)) != std::string::npos) {
|
||||
// typing::Literal escapes special characters with !
|
||||
signature += *++pc;
|
||||
} else if (c == '@') {
|
||||
// `@^ ... @!` and `@$ ... @!` are used to force arg/return value type (see
|
||||
// typing::Callable/detail::arg_descr/detail::return_descr)
|
||||
if (*(pc + 1) == '^') {
|
||||
is_return_value.emplace(false);
|
||||
++pc;
|
||||
continue;
|
||||
}
|
||||
if (*(pc + 1) == '$') {
|
||||
is_return_value.emplace(true);
|
||||
++pc;
|
||||
continue;
|
||||
}
|
||||
if (*(pc + 1) == '!') {
|
||||
is_return_value.pop();
|
||||
++pc;
|
||||
continue;
|
||||
}
|
||||
// Handle types that differ depending on whether they appear
|
||||
// in an argument or a return value position (see io_name<text1, text2>).
|
||||
// For named arguments (py::arg()) with noconvert set, return value type is used.
|
||||
++pc;
|
||||
if (!is_return_value.top()
|
||||
&& !(arg_index < rec->args.size() && !rec->args[arg_index].convert)) {
|
||||
while (*pc != '\0' && *pc != '@') {
|
||||
signature += *pc++;
|
||||
}
|
||||
if (*pc == '@') {
|
||||
++pc;
|
||||
}
|
||||
while (*pc != '\0' && *pc != '@') {
|
||||
++pc;
|
||||
}
|
||||
} else {
|
||||
while (*pc != '\0' && *pc != '@') {
|
||||
++pc;
|
||||
}
|
||||
if (*pc == '@') {
|
||||
++pc;
|
||||
}
|
||||
while (*pc != '\0' && *pc != '@') {
|
||||
signature += *pc++;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (c == '-' && *(pc + 1) == '>') {
|
||||
is_return_value.emplace(true);
|
||||
}
|
||||
signature += c;
|
||||
}
|
||||
}
|
||||
|
@ -650,7 +573,8 @@ protected:
|
|||
// chain.
|
||||
chain_start = rec;
|
||||
rec->next = chain;
|
||||
auto rec_capsule = reinterpret_borrow<capsule>(PyCFunction_GET_SELF(m_ptr));
|
||||
auto rec_capsule
|
||||
= reinterpret_borrow<capsule>(((PyCFunctionObject *) m_ptr)->m_self);
|
||||
rec_capsule.set_pointer(unique_rec.release());
|
||||
guarded_strdup.release();
|
||||
} else {
|
||||
|
@ -710,11 +634,12 @@ protected:
|
|||
}
|
||||
}
|
||||
|
||||
/* Install docstring */
|
||||
auto *func = (PyCFunctionObject *) m_ptr;
|
||||
std::free(const_cast<char *>(func->m_ml->ml_doc));
|
||||
// Install docstring if it's non-empty (when at least one option is enabled)
|
||||
auto *doc = signatures.empty() ? nullptr : PYBIND11_COMPAT_STRDUP(signatures.c_str());
|
||||
std::free(const_cast<char *>(PYBIND11_PYCFUNCTION_GET_DOC(func)));
|
||||
PYBIND11_PYCFUNCTION_SET_DOC(func, doc);
|
||||
func->m_ml->ml_doc
|
||||
= signatures.empty() ? nullptr : PYBIND11_COMPAT_STRDUP(signatures.c_str());
|
||||
|
||||
if (rec->is_method) {
|
||||
m_ptr = PYBIND11_INSTANCE_METHOD_NEW(m_ptr, rec->scope.ptr());
|
||||
|
@ -1382,7 +1307,7 @@ PYBIND11_NAMESPACE_BEGIN(detail)
|
|||
|
||||
template <>
|
||||
struct handle_type_name<module_> {
|
||||
static constexpr auto name = const_name("types.ModuleType");
|
||||
static constexpr auto name = const_name("module");
|
||||
};
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
|
@ -1446,8 +1371,8 @@ protected:
|
|||
tinfo->dealloc = rec.dealloc;
|
||||
tinfo->simple_type = true;
|
||||
tinfo->simple_ancestors = true;
|
||||
tinfo->default_holder = rec.default_holder;
|
||||
tinfo->module_local = rec.module_local;
|
||||
tinfo->holder_enum_v = rec.holder_enum_v;
|
||||
|
||||
with_internals([&](internals &internals) {
|
||||
auto tindex = std::type_index(*rec.type);
|
||||
|
@ -1457,17 +1382,7 @@ protected:
|
|||
} else {
|
||||
internals.registered_types_cpp[tindex] = tinfo;
|
||||
}
|
||||
|
||||
PYBIND11_WARNING_PUSH
|
||||
#if defined(__GNUC__) && __GNUC__ == 12
|
||||
// When using GCC 12 these warnings are disabled as they trigger
|
||||
// false positive warnings. Discussed here:
|
||||
// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=115824.
|
||||
PYBIND11_WARNING_DISABLE_GCC("-Warray-bounds")
|
||||
PYBIND11_WARNING_DISABLE_GCC("-Wstringop-overread")
|
||||
#endif
|
||||
internals.registered_types_py[(PyTypeObject *) m_ptr] = {tinfo};
|
||||
PYBIND11_WARNING_POP
|
||||
});
|
||||
|
||||
if (rec.bases.size() > 1 || rec.multiple_inheritance) {
|
||||
|
@ -1620,239 +1535,6 @@ auto method_adaptor(Return (Class::*pmf)(Args...) const) -> Return (Derived::*)(
|
|||
return pmf;
|
||||
}
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
|
||||
// Helper for the property_cpp_function static member functions below.
|
||||
// The only purpose of these functions is to support .def_readonly & .def_readwrite.
|
||||
// In this context, the PM template parameter is certain to be a Pointer to a Member.
|
||||
// The main purpose of must_be_member_function_pointer is to make this obvious, and to guard
|
||||
// against accidents. As a side-effect, it also explains why the syntactical overhead for
|
||||
// perfect forwarding is not needed.
|
||||
template <typename PM>
|
||||
using must_be_member_function_pointer = enable_if_t<std::is_member_pointer<PM>::value, int>;
|
||||
|
||||
// Note that property_cpp_function is intentionally in the main pybind11 namespace,
|
||||
// because user-defined specializations could be useful.
|
||||
|
||||
// Classic (non-smart_holder) implementations for .def_readonly and .def_readwrite
|
||||
// getter and setter functions.
|
||||
// WARNING: This classic implementation can lead to dangling pointers for raw pointer members.
|
||||
// See test_ptr() in tests/test_class_sh_property.py
|
||||
// However, this implementation works as-is (and safely) for smart_holder std::shared_ptr members.
|
||||
template <typename T, typename D>
|
||||
struct property_cpp_function_classic {
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function readonly(PM pm, const handle &hdl) {
|
||||
return cpp_function([pm](const T &c) -> const D & { return c.*pm; }, is_method(hdl));
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function read(PM pm, const handle &hdl) {
|
||||
return readonly(pm, hdl);
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function write(PM pm, const handle &hdl) {
|
||||
return cpp_function([pm](T &c, const D &value) { c.*pm = value; }, is_method(hdl));
|
||||
}
|
||||
};
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
|
||||
template <typename T, typename D, typename SFINAE = void>
|
||||
struct property_cpp_function : detail::property_cpp_function_classic<T, D> {};
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
|
||||
template <typename T, typename D, typename SFINAE = void>
|
||||
struct both_t_and_d_use_type_caster_base : std::false_type {};
|
||||
|
||||
// `T` is assumed to be equivalent to `intrinsic_t<T>`.
|
||||
// `D` is may or may not be equivalent to `intrinsic_t<D>`.
|
||||
template <typename T, typename D>
|
||||
struct both_t_and_d_use_type_caster_base<
|
||||
T,
|
||||
D,
|
||||
enable_if_t<all_of<std::is_base_of<type_caster_base<T>, type_caster<T>>,
|
||||
std::is_base_of<type_caster_base<intrinsic_t<D>>, make_caster<D>>>::value>>
|
||||
: std::true_type {};
|
||||
|
||||
// Specialization for raw pointer members, using smart_holder if that is the class_ holder,
|
||||
// or falling back to the classic implementation if not.
|
||||
// WARNING: Like the classic implementation, this implementation can lead to dangling pointers.
|
||||
// See test_ptr() in tests/test_class_sh_property.py
|
||||
// However, the read functions return a shared_ptr to the member, emulating the PyCLIF approach:
|
||||
// https://github.com/google/clif/blob/c371a6d4b28d25d53a16e6d2a6d97305fb1be25a/clif/python/instance.h#L233
|
||||
// This prevents disowning of the Python object owning the raw pointer member.
|
||||
template <typename T, typename D>
|
||||
struct property_cpp_function_sh_raw_ptr_member {
|
||||
using drp = typename std::remove_pointer<D>::type;
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function readonly(PM pm, const handle &hdl) {
|
||||
type_info *tinfo = get_type_info(typeid(T), /*throw_if_missing=*/true);
|
||||
if (tinfo->holder_enum_v == holder_enum_t::smart_holder) {
|
||||
return cpp_function(
|
||||
[pm](handle c_hdl) -> std::shared_ptr<drp> {
|
||||
std::shared_ptr<T> c_sp
|
||||
= type_caster<std::shared_ptr<T>>::shared_ptr_with_responsible_parent(
|
||||
c_hdl);
|
||||
D ptr = (*c_sp).*pm;
|
||||
return std::shared_ptr<drp>(c_sp, ptr);
|
||||
},
|
||||
is_method(hdl));
|
||||
}
|
||||
return property_cpp_function_classic<T, D>::readonly(pm, hdl);
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function read(PM pm, const handle &hdl) {
|
||||
return readonly(pm, hdl);
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function write(PM pm, const handle &hdl) {
|
||||
type_info *tinfo = get_type_info(typeid(T), /*throw_if_missing=*/true);
|
||||
if (tinfo->holder_enum_v == holder_enum_t::smart_holder) {
|
||||
return cpp_function([pm](T &c, D value) { c.*pm = std::forward<D>(std::move(value)); },
|
||||
is_method(hdl));
|
||||
}
|
||||
return property_cpp_function_classic<T, D>::write(pm, hdl);
|
||||
}
|
||||
};
|
||||
|
||||
// Specialization for members held by-value, using smart_holder if that is the class_ holder,
|
||||
// or falling back to the classic implementation if not.
|
||||
// The read functions return a shared_ptr to the member, emulating the PyCLIF approach:
|
||||
// https://github.com/google/clif/blob/c371a6d4b28d25d53a16e6d2a6d97305fb1be25a/clif/python/instance.h#L233
|
||||
// This prevents disowning of the Python object owning the member.
|
||||
template <typename T, typename D>
|
||||
struct property_cpp_function_sh_member_held_by_value {
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function readonly(PM pm, const handle &hdl) {
|
||||
type_info *tinfo = get_type_info(typeid(T), /*throw_if_missing=*/true);
|
||||
if (tinfo->holder_enum_v == holder_enum_t::smart_holder) {
|
||||
return cpp_function(
|
||||
[pm](handle c_hdl) -> std::shared_ptr<typename std::add_const<D>::type> {
|
||||
std::shared_ptr<T> c_sp
|
||||
= type_caster<std::shared_ptr<T>>::shared_ptr_with_responsible_parent(
|
||||
c_hdl);
|
||||
return std::shared_ptr<typename std::add_const<D>::type>(c_sp,
|
||||
&(c_sp.get()->*pm));
|
||||
},
|
||||
is_method(hdl));
|
||||
}
|
||||
return property_cpp_function_classic<T, D>::readonly(pm, hdl);
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function read(PM pm, const handle &hdl) {
|
||||
type_info *tinfo = get_type_info(typeid(T), /*throw_if_missing=*/true);
|
||||
if (tinfo->holder_enum_v == holder_enum_t::smart_holder) {
|
||||
return cpp_function(
|
||||
[pm](handle c_hdl) -> std::shared_ptr<D> {
|
||||
std::shared_ptr<T> c_sp
|
||||
= type_caster<std::shared_ptr<T>>::shared_ptr_with_responsible_parent(
|
||||
c_hdl);
|
||||
return std::shared_ptr<D>(c_sp, &(c_sp.get()->*pm));
|
||||
},
|
||||
is_method(hdl));
|
||||
}
|
||||
return property_cpp_function_classic<T, D>::read(pm, hdl);
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function write(PM pm, const handle &hdl) {
|
||||
type_info *tinfo = get_type_info(typeid(T), /*throw_if_missing=*/true);
|
||||
if (tinfo->holder_enum_v == holder_enum_t::smart_holder) {
|
||||
return cpp_function([pm](T &c, const D &value) { c.*pm = value; }, is_method(hdl));
|
||||
}
|
||||
return property_cpp_function_classic<T, D>::write(pm, hdl);
|
||||
}
|
||||
};
|
||||
|
||||
// Specialization for std::unique_ptr members, using smart_holder if that is the class_ holder,
|
||||
// or falling back to the classic implementation if not.
|
||||
// read disowns the member unique_ptr.
|
||||
// write disowns the passed Python object.
|
||||
// readonly is disabled (static_assert) because there is no safe & intuitive way to make the member
|
||||
// accessible as a Python object without disowning the member unique_ptr. A .def_readonly disowning
|
||||
// the unique_ptr member is deemed highly prone to misunderstandings.
|
||||
template <typename T, typename D>
|
||||
struct property_cpp_function_sh_unique_ptr_member {
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function readonly(PM, const handle &) {
|
||||
static_assert(!is_instantiation<std::unique_ptr, D>::value,
|
||||
"def_readonly cannot be used for std::unique_ptr members.");
|
||||
return cpp_function{}; // Unreachable.
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function read(PM pm, const handle &hdl) {
|
||||
type_info *tinfo = get_type_info(typeid(T), /*throw_if_missing=*/true);
|
||||
if (tinfo->holder_enum_v == holder_enum_t::smart_holder) {
|
||||
return cpp_function(
|
||||
[pm](handle c_hdl) -> D {
|
||||
std::shared_ptr<T> c_sp
|
||||
= type_caster<std::shared_ptr<T>>::shared_ptr_with_responsible_parent(
|
||||
c_hdl);
|
||||
return D{std::move(c_sp.get()->*pm)};
|
||||
},
|
||||
is_method(hdl));
|
||||
}
|
||||
return property_cpp_function_classic<T, D>::read(pm, hdl);
|
||||
}
|
||||
|
||||
template <typename PM, must_be_member_function_pointer<PM> = 0>
|
||||
static cpp_function write(PM pm, const handle &hdl) {
|
||||
return cpp_function([pm](T &c, D &&value) { c.*pm = std::move(value); }, is_method(hdl));
|
||||
}
|
||||
};
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
|
||||
template <typename T, typename D>
|
||||
struct property_cpp_function<
|
||||
T,
|
||||
D,
|
||||
detail::enable_if_t<detail::all_of<std::is_pointer<D>,
|
||||
detail::both_t_and_d_use_type_caster_base<T, D>>::value>>
|
||||
: detail::property_cpp_function_sh_raw_ptr_member<T, D> {};
|
||||
|
||||
template <typename T, typename D>
|
||||
struct property_cpp_function<T,
|
||||
D,
|
||||
detail::enable_if_t<detail::all_of<
|
||||
detail::none_of<std::is_pointer<D>,
|
||||
std::is_array<D>,
|
||||
detail::is_instantiation<std::unique_ptr, D>,
|
||||
detail::is_instantiation<std::shared_ptr, D>>,
|
||||
detail::both_t_and_d_use_type_caster_base<T, D>>::value>>
|
||||
: detail::property_cpp_function_sh_member_held_by_value<T, D> {};
|
||||
|
||||
template <typename T, typename D>
|
||||
struct property_cpp_function<
|
||||
T,
|
||||
D,
|
||||
detail::enable_if_t<detail::all_of<
|
||||
detail::is_instantiation<std::unique_ptr, D>,
|
||||
detail::both_t_and_d_use_type_caster_base<T, typename D::element_type>>::value>>
|
||||
: detail::property_cpp_function_sh_unique_ptr_member<T, D> {};
|
||||
|
||||
#ifdef PYBIND11_RUN_TESTING_WITH_SMART_HOLDER_AS_DEFAULT_BUT_NEVER_USE_IN_PRODUCTION_PLEASE
|
||||
// NOTE: THIS IS MEANT FOR STRESS-TESTING OR TRIAGING ONLY!
|
||||
// Running the pybind11 unit tests with smart_holder as the default holder is to ensure
|
||||
// that `py::smart_holder` / `py::classh` is backward-compatible with all pre-existing
|
||||
// functionality.
|
||||
// Be careful not to link translation units compiled with different default holders, because
|
||||
// this will cause ODR violations (https://en.wikipedia.org/wiki/One_Definition_Rule).
|
||||
template <typename>
|
||||
using default_holder_type = smart_holder;
|
||||
#else
|
||||
template <typename T>
|
||||
using default_holder_type = std::unique_ptr<T>;
|
||||
#endif
|
||||
|
||||
template <typename type_, typename... options>
|
||||
class class_ : public detail::generic_type {
|
||||
template <typename T>
|
||||
|
@ -1869,7 +1551,7 @@ public:
|
|||
using type = type_;
|
||||
using type_alias = detail::exactly_one_t<is_subtype, void, options...>;
|
||||
constexpr static bool has_alias = !std::is_void<type_alias>::value;
|
||||
using holder_type = detail::exactly_one_t<is_holder, default_holder_type<type>, options...>;
|
||||
using holder_type = detail::exactly_one_t<is_holder, std::unique_ptr<type>, options...>;
|
||||
|
||||
static_assert(detail::all_of<is_valid_class_option<options>...>::value,
|
||||
"Unknown/invalid class_ template parameters provided");
|
||||
|
@ -1900,16 +1582,8 @@ public:
|
|||
record.type_align = alignof(conditional_t<has_alias, type_alias, type> &);
|
||||
record.holder_size = sizeof(holder_type);
|
||||
record.init_instance = init_instance;
|
||||
|
||||
if (detail::is_instantiation<std::unique_ptr, holder_type>::value) {
|
||||
record.holder_enum_v = detail::holder_enum_t::std_unique_ptr;
|
||||
} else if (detail::is_instantiation<std::shared_ptr, holder_type>::value) {
|
||||
record.holder_enum_v = detail::holder_enum_t::std_shared_ptr;
|
||||
} else if (std::is_same<holder_type, smart_holder>::value) {
|
||||
record.holder_enum_v = detail::holder_enum_t::smart_holder;
|
||||
} else {
|
||||
record.holder_enum_v = detail::holder_enum_t::custom_holder;
|
||||
}
|
||||
record.dealloc = dealloc;
|
||||
record.default_holder = detail::is_instantiation<std::unique_ptr, holder_type>::value;
|
||||
|
||||
set_operator_new<type>(&record);
|
||||
|
||||
|
@ -1919,12 +1593,6 @@ public:
|
|||
/* Process optional arguments, if any */
|
||||
process_attributes<Extra...>::init(extra..., &record);
|
||||
|
||||
if (record.release_gil_before_calling_cpp_dtor) {
|
||||
record.dealloc = dealloc_release_gil_before_calling_cpp_dtor;
|
||||
} else {
|
||||
record.dealloc = dealloc_without_manipulating_gil;
|
||||
}
|
||||
|
||||
generic_type::initialize(record);
|
||||
|
||||
if (has_alias) {
|
||||
|
@ -2048,11 +1716,9 @@ public:
|
|||
class_ &def_readwrite(const char *name, D C::*pm, const Extra &...extra) {
|
||||
static_assert(std::is_same<C, type>::value || std::is_base_of<C, type>::value,
|
||||
"def_readwrite() requires a class member (or base class member)");
|
||||
def_property(name,
|
||||
property_cpp_function<type, D>::read(pm, *this),
|
||||
property_cpp_function<type, D>::write(pm, *this),
|
||||
return_value_policy::reference_internal,
|
||||
extra...);
|
||||
cpp_function fget([pm](const type &c) -> const D & { return c.*pm; }, is_method(*this)),
|
||||
fset([pm](type &c, const D &value) { c.*pm = value; }, is_method(*this));
|
||||
def_property(name, fget, fset, return_value_policy::reference_internal, extra...);
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
@ -2060,10 +1726,8 @@ public:
|
|||
class_ &def_readonly(const char *name, const D C::*pm, const Extra &...extra) {
|
||||
static_assert(std::is_same<C, type>::value || std::is_base_of<C, type>::value,
|
||||
"def_readonly() requires a class member (or base class member)");
|
||||
def_property_readonly(name,
|
||||
property_cpp_function<type, D>::readonly(pm, *this),
|
||||
return_value_policy::reference_internal,
|
||||
extra...);
|
||||
cpp_function fget([pm](const type &c) -> const D & { return c.*pm; }, is_method(*this));
|
||||
def_property_readonly(name, fget, return_value_policy::reference_internal, extra...);
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
@ -2240,8 +1904,6 @@ private:
|
|||
/// instance. Should be called as soon as the `type` value_ptr is set for an instance. Takes
|
||||
/// an optional pointer to an existing holder to use; if not specified and the instance is
|
||||
/// `.owned`, a new holder will be constructed to manage the value pointer.
|
||||
template <typename H = holder_type,
|
||||
detail::enable_if_t<!detail::is_smart_holder<H>::value, int> = 0>
|
||||
static void init_instance(detail::instance *inst, const void *holder_ptr) {
|
||||
auto v_h = inst->get_value_and_holder(detail::get_type_info(typeid(type)));
|
||||
if (!v_h.instance_registered()) {
|
||||
|
@ -2251,73 +1913,15 @@ private:
|
|||
init_holder(inst, v_h, (const holder_type *) holder_ptr, v_h.value_ptr<type>());
|
||||
}
|
||||
|
||||
template <typename WrappedType>
|
||||
static bool try_initialization_using_shared_from_this(holder_type *, WrappedType *, ...) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Adopting existing approach used by type_caster_base, although it leads to somewhat fuzzy
|
||||
// ownership semantics: if we detected via shared_from_this that a shared_ptr exists already,
|
||||
// it is reused, irrespective of the return_value_policy in effect.
|
||||
// "SomeBaseOfWrappedType" is needed because std::enable_shared_from_this is not necessarily a
|
||||
// direct base of WrappedType.
|
||||
template <typename WrappedType, typename SomeBaseOfWrappedType>
|
||||
static bool try_initialization_using_shared_from_this(
|
||||
holder_type *uninitialized_location,
|
||||
WrappedType *value_ptr_w_t,
|
||||
const std::enable_shared_from_this<SomeBaseOfWrappedType> *) {
|
||||
auto shd_ptr = std::dynamic_pointer_cast<WrappedType>(
|
||||
detail::try_get_shared_from_this(value_ptr_w_t));
|
||||
if (!shd_ptr) {
|
||||
return false;
|
||||
}
|
||||
// Note: inst->owned ignored.
|
||||
new (uninitialized_location) holder_type(holder_type::from_shared_ptr(shd_ptr));
|
||||
return true;
|
||||
}
|
||||
|
||||
template <typename H = holder_type,
|
||||
detail::enable_if_t<detail::is_smart_holder<H>::value, int> = 0>
|
||||
static void init_instance(detail::instance *inst, const void *holder_const_void_ptr) {
|
||||
// Need for const_cast is a consequence of the type_info::init_instance type:
|
||||
// void (*init_instance)(instance *, const void *);
|
||||
auto *holder_void_ptr = const_cast<void *>(holder_const_void_ptr);
|
||||
|
||||
auto v_h = inst->get_value_and_holder(detail::get_type_info(typeid(type)));
|
||||
if (!v_h.instance_registered()) {
|
||||
register_instance(inst, v_h.value_ptr(), v_h.type);
|
||||
v_h.set_instance_registered();
|
||||
}
|
||||
auto *uninitialized_location = std::addressof(v_h.holder<holder_type>());
|
||||
auto *value_ptr_w_t = v_h.value_ptr<type>();
|
||||
// Try downcast from `type` to `type_alias`:
|
||||
inst->is_alias
|
||||
= detail::dynamic_raw_ptr_cast_if_possible<type_alias>(value_ptr_w_t) != nullptr;
|
||||
if (holder_void_ptr) {
|
||||
// Note: inst->owned ignored.
|
||||
auto *holder_ptr = static_cast<holder_type *>(holder_void_ptr);
|
||||
new (uninitialized_location) holder_type(std::move(*holder_ptr));
|
||||
} else if (!try_initialization_using_shared_from_this(
|
||||
uninitialized_location, value_ptr_w_t, value_ptr_w_t)) {
|
||||
if (inst->owned) {
|
||||
new (uninitialized_location) holder_type(holder_type::from_raw_ptr_take_ownership(
|
||||
value_ptr_w_t, /*void_cast_raw_ptr*/ inst->is_alias));
|
||||
} else {
|
||||
new (uninitialized_location)
|
||||
holder_type(holder_type::from_raw_ptr_unowned(value_ptr_w_t));
|
||||
}
|
||||
}
|
||||
v_h.set_holder_constructed();
|
||||
}
|
||||
|
||||
// Deallocates an instance; via holder, if constructed; otherwise via operator delete.
|
||||
// NOTE: The Python error indicator needs to cleared BEFORE this function is called.
|
||||
// This is because we could be deallocating while cleaning up after a Python exception.
|
||||
// If the error indicator is not cleared but the C++ destructor code makes Python C API
|
||||
// calls, those calls are likely to generate a new exception, and pybind11 will then
|
||||
// throw `error_already_set` from the C++ destructor. This is forbidden and will
|
||||
// trigger std::terminate().
|
||||
static void dealloc_impl(detail::value_and_holder &v_h) {
|
||||
/// Deallocates an instance; via holder, if constructed; otherwise via operator delete.
|
||||
static void dealloc(detail::value_and_holder &v_h) {
|
||||
// We could be deallocating because we are cleaning up after a Python exception.
|
||||
// If so, the Python error indicator will be set. We need to clear that before
|
||||
// running the destructor, in case the destructor code calls more Python.
|
||||
// If we don't, the Python API will exit with an exception, and pybind11 will
|
||||
// throw error_already_set from the C++ destructor which is forbidden and triggers
|
||||
// std::terminate().
|
||||
error_scope scope;
|
||||
if (v_h.holder_constructed()) {
|
||||
v_h.holder<holder_type>().~holder_type();
|
||||
v_h.set_holder_constructed(false);
|
||||
|
@ -2328,32 +1932,6 @@ private:
|
|||
v_h.value_ptr() = nullptr;
|
||||
}
|
||||
|
||||
static void dealloc_without_manipulating_gil(detail::value_and_holder &v_h) {
|
||||
error_scope scope;
|
||||
dealloc_impl(v_h);
|
||||
}
|
||||
|
||||
static void dealloc_release_gil_before_calling_cpp_dtor(detail::value_and_holder &v_h) {
|
||||
error_scope scope;
|
||||
// Intentionally not using `gil_scoped_release` because the non-simple
|
||||
// version unconditionally calls `get_internals()`.
|
||||
// `Py_BEGIN_ALLOW_THREADS`, `Py_END_ALLOW_THREADS` cannot be used
|
||||
// because those macros include `{` and `}`.
|
||||
PyThreadState *py_ts = PyEval_SaveThread();
|
||||
try {
|
||||
dealloc_impl(v_h);
|
||||
} catch (...) {
|
||||
// This code path is expected to be unreachable unless there is a
|
||||
// bug in pybind11 itself.
|
||||
// An alternative would be to mark this function, or
|
||||
// `dealloc_impl()`, with `nothrow`, but that would be a subtle
|
||||
// behavior change and could make debugging more difficult.
|
||||
PyEval_RestoreThread(py_ts);
|
||||
throw;
|
||||
}
|
||||
PyEval_RestoreThread(py_ts);
|
||||
}
|
||||
|
||||
static detail::function_record *get_function_record(handle h) {
|
||||
h = detail::get_function(h);
|
||||
if (!h) {
|
||||
|
@ -2375,11 +1953,6 @@ private:
|
|||
}
|
||||
};
|
||||
|
||||
// Supports easier switching between py::class_<T> and py::class_<T, py::smart_holder>:
|
||||
// users can simply replace the `_` in `class_` with `h` or vice versa.
|
||||
template <typename type_, typename... options>
|
||||
using classh = class_<type_, smart_holder, options...>;
|
||||
|
||||
/// Binds an existing constructor taking arguments Args...
|
||||
template <typename... Args>
|
||||
detail::initimpl::constructor<Args...> init() {
|
||||
|
@ -2441,11 +2014,9 @@ struct enum_base {
|
|||
.format(std::move(type_name), enum_name(arg), int_(arg));
|
||||
},
|
||||
name("__repr__"),
|
||||
is_method(m_base),
|
||||
pos_only());
|
||||
is_method(m_base));
|
||||
|
||||
m_base.attr("name")
|
||||
= property(cpp_function(&enum_name, name("name"), is_method(m_base), pos_only()));
|
||||
m_base.attr("name") = property(cpp_function(&enum_name, name("name"), is_method(m_base)));
|
||||
|
||||
m_base.attr("__str__") = cpp_function(
|
||||
[](handle arg) -> str {
|
||||
|
@ -2453,8 +2024,7 @@ struct enum_base {
|
|||
return pybind11::str("{}.{}").format(std::move(type_name), enum_name(arg));
|
||||
},
|
||||
name("__str__"),
|
||||
is_method(m_base),
|
||||
pos_only());
|
||||
is_method(m_base));
|
||||
|
||||
if (options::show_enum_members_docstring()) {
|
||||
m_base.attr("__doc__") = static_property(
|
||||
|
@ -2509,8 +2079,7 @@ struct enum_base {
|
|||
}, \
|
||||
name(op), \
|
||||
is_method(m_base), \
|
||||
arg("other"), \
|
||||
pos_only())
|
||||
arg("other"))
|
||||
|
||||
#define PYBIND11_ENUM_OP_CONV(op, expr) \
|
||||
m_base.attr(op) = cpp_function( \
|
||||
|
@ -2520,8 +2089,7 @@ struct enum_base {
|
|||
}, \
|
||||
name(op), \
|
||||
is_method(m_base), \
|
||||
arg("other"), \
|
||||
pos_only())
|
||||
arg("other"))
|
||||
|
||||
#define PYBIND11_ENUM_OP_CONV_LHS(op, expr) \
|
||||
m_base.attr(op) = cpp_function( \
|
||||
|
@ -2531,8 +2099,7 @@ struct enum_base {
|
|||
}, \
|
||||
name(op), \
|
||||
is_method(m_base), \
|
||||
arg("other"), \
|
||||
pos_only())
|
||||
arg("other"))
|
||||
|
||||
if (is_convertible) {
|
||||
PYBIND11_ENUM_OP_CONV_LHS("__eq__", !b.is_none() && a.equal(b));
|
||||
|
@ -2552,8 +2119,7 @@ struct enum_base {
|
|||
m_base.attr("__invert__")
|
||||
= cpp_function([](const object &arg) { return ~(int_(arg)); },
|
||||
name("__invert__"),
|
||||
is_method(m_base),
|
||||
pos_only());
|
||||
is_method(m_base));
|
||||
}
|
||||
} else {
|
||||
PYBIND11_ENUM_OP_STRICT("__eq__", int_(a).equal(int_(b)), return false);
|
||||
|
@ -2573,15 +2139,11 @@ struct enum_base {
|
|||
#undef PYBIND11_ENUM_OP_CONV
|
||||
#undef PYBIND11_ENUM_OP_STRICT
|
||||
|
||||
m_base.attr("__getstate__") = cpp_function([](const object &arg) { return int_(arg); },
|
||||
name("__getstate__"),
|
||||
is_method(m_base),
|
||||
pos_only());
|
||||
m_base.attr("__getstate__") = cpp_function(
|
||||
[](const object &arg) { return int_(arg); }, name("__getstate__"), is_method(m_base));
|
||||
|
||||
m_base.attr("__hash__") = cpp_function([](const object &arg) { return int_(arg); },
|
||||
name("__hash__"),
|
||||
is_method(m_base),
|
||||
pos_only());
|
||||
m_base.attr("__hash__") = cpp_function(
|
||||
[](const object &arg) { return int_(arg); }, name("__hash__"), is_method(m_base));
|
||||
}
|
||||
|
||||
PYBIND11_NOINLINE void value(char const *name_, object value, const char *doc = nullptr) {
|
||||
|
@ -2673,9 +2235,9 @@ public:
|
|||
m_base.init(is_arithmetic, is_convertible);
|
||||
|
||||
def(init([](Scalar i) { return static_cast<Type>(i); }), arg("value"));
|
||||
def_property_readonly("value", [](Type value) { return (Scalar) value; }, pos_only());
|
||||
def("__int__", [](Type value) { return (Scalar) value; }, pos_only());
|
||||
def("__index__", [](Type value) { return (Scalar) value; }, pos_only());
|
||||
def_property_readonly("value", [](Type value) { return (Scalar) value; });
|
||||
def("__int__", [](Type value) { return (Scalar) value; });
|
||||
def("__index__", [](Type value) { return (Scalar) value; });
|
||||
attr("__setstate__") = cpp_function(
|
||||
[](detail::value_and_holder &v_h, Scalar arg) {
|
||||
detail::initimpl::setstate<Base>(
|
||||
|
@ -2684,8 +2246,7 @@ public:
|
|||
detail::is_new_style_constructor(),
|
||||
pybind11::name("__setstate__"),
|
||||
is_method(*this),
|
||||
arg("state"),
|
||||
pos_only());
|
||||
arg("state"));
|
||||
}
|
||||
|
||||
/// Export enumeration entries into the parent scope
|
||||
|
@ -2757,20 +2318,13 @@ keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret) {
|
|||
inline std::pair<decltype(internals::registered_types_py)::iterator, bool>
|
||||
all_type_info_get_cache(PyTypeObject *type) {
|
||||
auto res = with_internals([type](internals &internals) {
|
||||
auto ins = internals
|
||||
.registered_types_py
|
||||
return internals
|
||||
.registered_types_py
|
||||
#ifdef __cpp_lib_unordered_map_try_emplace
|
||||
.try_emplace(type);
|
||||
.try_emplace(type);
|
||||
#else
|
||||
.emplace(type, std::vector<detail::type_info *>());
|
||||
.emplace(type, std::vector<detail::type_info *>());
|
||||
#endif
|
||||
if (ins.second) {
|
||||
// For free-threading mode, this call must be under
|
||||
// the with_internals() mutex lock, to avoid that other threads
|
||||
// continue running with the empty ins.first->second.
|
||||
all_type_info_populate(type, ins.first->second);
|
||||
}
|
||||
return ins;
|
||||
});
|
||||
if (res.second) {
|
||||
// New cache entry created; set up a weak reference to automatically remove it if the type
|
||||
|
@ -2871,8 +2425,7 @@ iterator make_iterator_impl(Iterator first, Sentinel last, Extra &&...extra) {
|
|||
|
||||
if (!detail::get_type_info(typeid(state), false)) {
|
||||
class_<state>(handle(), "iterator", pybind11::module_local())
|
||||
.def(
|
||||
"__iter__", [](state &s) -> state & { return s; }, pos_only())
|
||||
.def("__iter__", [](state &s) -> state & { return s; })
|
||||
.def(
|
||||
"__next__",
|
||||
[](state &s) -> ValueType {
|
||||
|
@ -2889,7 +2442,6 @@ iterator make_iterator_impl(Iterator first, Sentinel last, Extra &&...extra) {
|
|||
// NOLINTNEXTLINE(readability-const-return-type) // PR #3263
|
||||
},
|
||||
std::forward<Extra>(extra)...,
|
||||
pos_only(),
|
||||
Policy);
|
||||
}
|
||||
|
||||
|
@ -3024,12 +2576,10 @@ void implicitly_convertible() {
|
|||
}
|
||||
|
||||
inline void register_exception_translator(ExceptionTranslator &&translator) {
|
||||
detail::with_exception_translators(
|
||||
[&](std::forward_list<ExceptionTranslator> &exception_translators,
|
||||
std::forward_list<ExceptionTranslator> &local_exception_translators) {
|
||||
(void) local_exception_translators;
|
||||
exception_translators.push_front(std::forward<ExceptionTranslator>(translator));
|
||||
});
|
||||
detail::with_internals([&](detail::internals &internals) {
|
||||
internals.registered_exception_translators.push_front(
|
||||
std::forward<ExceptionTranslator>(translator));
|
||||
});
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -3039,12 +2589,11 @@ inline void register_exception_translator(ExceptionTranslator &&translator) {
|
|||
* the exception.
|
||||
*/
|
||||
inline void register_local_exception_translator(ExceptionTranslator &&translator) {
|
||||
detail::with_exception_translators(
|
||||
[&](std::forward_list<ExceptionTranslator> &exception_translators,
|
||||
std::forward_list<ExceptionTranslator> &local_exception_translators) {
|
||||
(void) exception_translators;
|
||||
local_exception_translators.push_front(std::forward<ExceptionTranslator>(translator));
|
||||
});
|
||||
detail::with_internals([&](detail::internals &internals) {
|
||||
(void) internals;
|
||||
detail::get_local_internals().registered_exception_translators.push_front(
|
||||
std::forward<ExceptionTranslator>(translator));
|
||||
});
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -3218,8 +2767,8 @@ get_type_override(const void *this_ptr, const type_info *this_type, const char *
|
|||
}
|
||||
|
||||
/* Don't call dispatch code if invoked from overridden function.
|
||||
Unfortunately this doesn't work on PyPy and GraalPy. */
|
||||
#if !defined(PYPY_VERSION) && !defined(GRAALVM_PYTHON)
|
||||
Unfortunately this doesn't work on PyPy. */
|
||||
#if !defined(PYPY_VERSION)
|
||||
# if PY_VERSION_HEX >= 0x03090000
|
||||
PyFrameObject *frame = PyThreadState_GetFrame(PyThreadState_Get());
|
||||
if (frame != nullptr) {
|
||||
|
|
|
@ -113,17 +113,6 @@ public:
|
|||
/// See above (the only difference is that the key is provided as a string literal)
|
||||
str_attr_accessor attr(const char *key) const;
|
||||
|
||||
/** \rst
|
||||
Similar to the above attr functions with the difference that the templated Type
|
||||
is used to set the `__annotations__` dict value to the corresponding key. Worth noting
|
||||
that attr_with_type_hint is implemented in cast.h.
|
||||
\endrst */
|
||||
template <typename T>
|
||||
obj_attr_accessor attr_with_type_hint(handle key) const;
|
||||
/// See above (the only difference is that the key is provided as a string literal)
|
||||
template <typename T>
|
||||
str_attr_accessor attr_with_type_hint(const char *key) const;
|
||||
|
||||
/** \rst
|
||||
Matches * unpacking in Python, e.g. to unpack arguments out of a ``tuple``
|
||||
or ``list`` for a function call. Applying another * to the result yields
|
||||
|
@ -193,9 +182,6 @@ public:
|
|||
/// Get or set the object's docstring, i.e. ``obj.__doc__``.
|
||||
str_attr_accessor doc() const;
|
||||
|
||||
/// Get or set the object's annotations, i.e. ``obj.__annotations__``.
|
||||
object annotations() const;
|
||||
|
||||
/// Return the object's current reference count
|
||||
ssize_t ref_count() const {
|
||||
#ifdef PYPY_VERSION
|
||||
|
@ -657,7 +643,7 @@ struct error_fetch_and_normalize {
|
|||
|
||||
bool have_trace = false;
|
||||
if (m_trace) {
|
||||
#if !defined(PYPY_VERSION) && !defined(GRAALVM_PYTHON)
|
||||
#if !defined(PYPY_VERSION)
|
||||
auto *tb = reinterpret_cast<PyTracebackObject *>(m_trace.ptr());
|
||||
|
||||
// Get the deepest trace possible.
|
||||
|
@ -1370,7 +1356,7 @@ inline bool PyUnicode_Check_Permissive(PyObject *o) {
|
|||
# define PYBIND11_STR_CHECK_FUN PyUnicode_Check
|
||||
#endif
|
||||
|
||||
inline bool PyStaticMethod_Check(PyObject *o) { return Py_TYPE(o) == &PyStaticMethod_Type; }
|
||||
inline bool PyStaticMethod_Check(PyObject *o) { return o->ob_type == &PyStaticMethod_Type; }
|
||||
|
||||
class kwargs_proxy : public handle {
|
||||
public:
|
||||
|
@ -1484,17 +1470,11 @@ public:
|
|||
PYBIND11_OBJECT_DEFAULT(iterator, object, PyIter_Check)
|
||||
|
||||
iterator &operator++() {
|
||||
init();
|
||||
advance();
|
||||
return *this;
|
||||
}
|
||||
|
||||
iterator operator++(int) {
|
||||
// Note: We must call init() first so that rv.value is
|
||||
// the same as this->value just before calling advance().
|
||||
// Otherwise, dereferencing the returned iterator may call
|
||||
// advance() again and return the 3rd item instead of the 1st.
|
||||
init();
|
||||
auto rv = *this;
|
||||
advance();
|
||||
return rv;
|
||||
|
@ -1502,12 +1482,15 @@ public:
|
|||
|
||||
// NOLINTNEXTLINE(readability-const-return-type) // PR #3263
|
||||
reference operator*() const {
|
||||
init();
|
||||
if (m_ptr && !value.ptr()) {
|
||||
auto &self = const_cast<iterator &>(*this);
|
||||
self.advance();
|
||||
}
|
||||
return value;
|
||||
}
|
||||
|
||||
pointer operator->() const {
|
||||
init();
|
||||
operator*();
|
||||
return &value;
|
||||
}
|
||||
|
||||
|
@ -1530,13 +1513,6 @@ public:
|
|||
friend bool operator!=(const iterator &a, const iterator &b) { return a->ptr() != b->ptr(); }
|
||||
|
||||
private:
|
||||
void init() const {
|
||||
if (m_ptr && !value.ptr()) {
|
||||
auto &self = const_cast<iterator &>(*this);
|
||||
self.advance();
|
||||
}
|
||||
}
|
||||
|
||||
void advance() {
|
||||
value = reinterpret_steal<object>(PyIter_Next(m_ptr));
|
||||
if (value.ptr() == nullptr && PyErr_Occurred()) {
|
||||
|
@ -2240,18 +2216,6 @@ class kwargs : public dict {
|
|||
PYBIND11_OBJECT_DEFAULT(kwargs, dict, PyDict_Check)
|
||||
};
|
||||
|
||||
// Subclasses of args and kwargs to support type hinting
|
||||
// as defined in PEP 484. See #5357 for more info.
|
||||
template <typename T>
|
||||
class Args : public args {
|
||||
using args::args;
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
class KWArgs : public kwargs {
|
||||
using kwargs::kwargs;
|
||||
};
|
||||
|
||||
class anyset : public object {
|
||||
public:
|
||||
PYBIND11_OBJECT(anyset, object, PyAnySet_Check)
|
||||
|
@ -2572,19 +2536,6 @@ str_attr_accessor object_api<D>::doc() const {
|
|||
return attr("__doc__");
|
||||
}
|
||||
|
||||
template <typename D>
|
||||
object object_api<D>::annotations() const {
|
||||
#if PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION <= 9
|
||||
// https://docs.python.org/3/howto/annotations.html#accessing-the-annotations-dict-of-an-object-in-python-3-9-and-older
|
||||
if (!hasattr(derived(), "__annotations__")) {
|
||||
setattr(derived(), "__annotations__", dict());
|
||||
}
|
||||
return attr("__annotations__");
|
||||
#else
|
||||
return getattr(derived(), "__annotations__", dict());
|
||||
#endif
|
||||
}
|
||||
|
||||
template <typename D>
|
||||
handle object_api<D>::get_type() const {
|
||||
return type::handle_of(derived());
|
||||
|
|
|
@ -11,14 +11,10 @@
|
|||
|
||||
#include "pybind11.h"
|
||||
#include "detail/common.h"
|
||||
#include "detail/descr.h"
|
||||
#include "detail/type_caster_base.h"
|
||||
|
||||
#include <deque>
|
||||
#include <initializer_list>
|
||||
#include <list>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <ostream>
|
||||
#include <set>
|
||||
#include <unordered_map>
|
||||
|
@ -39,89 +35,6 @@
|
|||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
|
||||
//
|
||||
// Begin: Equivalent of
|
||||
// https://github.com/google/clif/blob/ae4eee1de07cdf115c0c9bf9fec9ff28efce6f6c/clif/python/runtime.cc#L388-L438
|
||||
/*
|
||||
The three `PyObjectTypeIsConvertibleTo*()` functions below are
|
||||
the result of converging the behaviors of pybind11 and PyCLIF
|
||||
(http://github.com/google/clif).
|
||||
|
||||
Originally PyCLIF was extremely far on the permissive side of the spectrum,
|
||||
while pybind11 was very far on the strict side. Originally PyCLIF accepted any
|
||||
Python iterable as input for a C++ `vector`/`set`/`map` argument, as long as
|
||||
the elements were convertible. The obvious (in hindsight) problem was that
|
||||
any empty Python iterable could be passed to any of these C++ types, e.g. `{}`
|
||||
was accepted for C++ `vector`/`set` arguments, or `[]` for C++ `map` arguments.
|
||||
|
||||
The functions below strike a practical permissive-vs-strict compromise,
|
||||
informed by tens of thousands of use cases in the wild. A main objective is
|
||||
to prevent accidents and improve readability:
|
||||
|
||||
- Python literals must match the C++ types.
|
||||
|
||||
- For C++ `set`: The potentially reducing conversion from a Python sequence
|
||||
(e.g. Python `list` or `tuple`) to a C++ `set` must be explicit, by going
|
||||
through a Python `set`.
|
||||
|
||||
- However, a Python `set` can still be passed to a C++ `vector`. The rationale
|
||||
is that this conversion is not reducing. Implicit conversions of this kind
|
||||
are also fairly commonly used, therefore enforcing explicit conversions
|
||||
would have an unfavorable cost : benefit ratio; more sloppily speaking,
|
||||
such an enforcement would be more annoying than helpful.
|
||||
*/
|
||||
|
||||
inline bool PyObjectIsInstanceWithOneOfTpNames(PyObject *obj,
|
||||
std::initializer_list<const char *> tp_names) {
|
||||
if (PyType_Check(obj)) {
|
||||
return false;
|
||||
}
|
||||
const char *obj_tp_name = Py_TYPE(obj)->tp_name;
|
||||
for (const auto *tp_name : tp_names) {
|
||||
if (std::strcmp(obj_tp_name, tp_name) == 0) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
inline bool PyObjectTypeIsConvertibleToStdVector(PyObject *obj) {
|
||||
if (PySequence_Check(obj) != 0) {
|
||||
return !PyUnicode_Check(obj) && !PyBytes_Check(obj);
|
||||
}
|
||||
return (PyGen_Check(obj) != 0) || (PyAnySet_Check(obj) != 0)
|
||||
|| PyObjectIsInstanceWithOneOfTpNames(
|
||||
obj, {"dict_keys", "dict_values", "dict_items", "map", "zip"});
|
||||
}
|
||||
|
||||
inline bool PyObjectTypeIsConvertibleToStdSet(PyObject *obj) {
|
||||
return (PyAnySet_Check(obj) != 0) || PyObjectIsInstanceWithOneOfTpNames(obj, {"dict_keys"});
|
||||
}
|
||||
|
||||
inline bool PyObjectTypeIsConvertibleToStdMap(PyObject *obj) {
|
||||
if (PyDict_Check(obj)) {
|
||||
return true;
|
||||
}
|
||||
// Implicit requirement in the conditions below:
|
||||
// A type with `.__getitem__()` & `.items()` methods must implement these
|
||||
// to be compatible with https://docs.python.org/3/c-api/mapping.html
|
||||
if (PyMapping_Check(obj) == 0) {
|
||||
return false;
|
||||
}
|
||||
PyObject *items = PyObject_GetAttrString(obj, "items");
|
||||
if (items == nullptr) {
|
||||
PyErr_Clear();
|
||||
return false;
|
||||
}
|
||||
bool is_convertible = (PyCallable_Check(items) != 0);
|
||||
Py_DECREF(items);
|
||||
return is_convertible;
|
||||
}
|
||||
|
||||
//
|
||||
// End: Equivalent of clif/python/runtime.cc
|
||||
//
|
||||
|
||||
/// Extracts an const lvalue reference or rvalue reference for U based on the type of T (e.g. for
|
||||
/// forwarding a container element). Typically used indirect via forwarded_type(), below.
|
||||
template <typename T, typename U>
|
||||
|
@ -153,10 +66,17 @@ private:
|
|||
}
|
||||
void reserve_maybe(const anyset &, void *) {}
|
||||
|
||||
bool convert_iterable(const iterable &itbl, bool convert) {
|
||||
for (const auto &it : itbl) {
|
||||
public:
|
||||
bool load(handle src, bool convert) {
|
||||
if (!isinstance<anyset>(src)) {
|
||||
return false;
|
||||
}
|
||||
auto s = reinterpret_borrow<anyset>(src);
|
||||
value.clear();
|
||||
reserve_maybe(s, &value);
|
||||
for (auto entry : s) {
|
||||
key_conv conv;
|
||||
if (!conv.load(it, convert)) {
|
||||
if (!conv.load(entry, convert)) {
|
||||
return false;
|
||||
}
|
||||
value.insert(cast_op<Key &&>(std::move(conv)));
|
||||
|
@ -164,29 +84,6 @@ private:
|
|||
return true;
|
||||
}
|
||||
|
||||
bool convert_anyset(anyset s, bool convert) {
|
||||
value.clear();
|
||||
reserve_maybe(s, &value);
|
||||
return convert_iterable(s, convert);
|
||||
}
|
||||
|
||||
public:
|
||||
bool load(handle src, bool convert) {
|
||||
if (!PyObjectTypeIsConvertibleToStdSet(src.ptr())) {
|
||||
return false;
|
||||
}
|
||||
if (isinstance<anyset>(src)) {
|
||||
value.clear();
|
||||
return convert_anyset(reinterpret_borrow<anyset>(src), convert);
|
||||
}
|
||||
if (!convert) {
|
||||
return false;
|
||||
}
|
||||
assert(isinstance<iterable>(src));
|
||||
value.clear();
|
||||
return convert_iterable(reinterpret_borrow<iterable>(src), convert);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static handle cast(T &&src, return_value_policy policy, handle parent) {
|
||||
if (!std::is_lvalue_reference<T>::value) {
|
||||
|
@ -218,10 +115,15 @@ private:
|
|||
}
|
||||
void reserve_maybe(const dict &, void *) {}
|
||||
|
||||
bool convert_elements(const dict &d, bool convert) {
|
||||
public:
|
||||
bool load(handle src, bool convert) {
|
||||
if (!isinstance<dict>(src)) {
|
||||
return false;
|
||||
}
|
||||
auto d = reinterpret_borrow<dict>(src);
|
||||
value.clear();
|
||||
reserve_maybe(d, &value);
|
||||
for (const auto &it : d) {
|
||||
for (auto it : d) {
|
||||
key_conv kconv;
|
||||
value_conv vconv;
|
||||
if (!kconv.load(it.first.ptr(), convert) || !vconv.load(it.second.ptr(), convert)) {
|
||||
|
@ -232,25 +134,6 @@ private:
|
|||
return true;
|
||||
}
|
||||
|
||||
public:
|
||||
bool load(handle src, bool convert) {
|
||||
if (!PyObjectTypeIsConvertibleToStdMap(src.ptr())) {
|
||||
return false;
|
||||
}
|
||||
if (isinstance<dict>(src)) {
|
||||
return convert_elements(reinterpret_borrow<dict>(src), convert);
|
||||
}
|
||||
if (!convert) {
|
||||
return false;
|
||||
}
|
||||
auto items = reinterpret_steal<object>(PyMapping_Items(src.ptr()));
|
||||
if (!items) {
|
||||
throw error_already_set();
|
||||
}
|
||||
assert(isinstance<iterable>(items));
|
||||
return convert_elements(dict(reinterpret_borrow<iterable>(items)), convert);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static handle cast(T &&src, return_value_policy policy, handle parent) {
|
||||
dict d;
|
||||
|
@ -283,35 +166,13 @@ struct list_caster {
|
|||
using value_conv = make_caster<Value>;
|
||||
|
||||
bool load(handle src, bool convert) {
|
||||
if (!PyObjectTypeIsConvertibleToStdVector(src.ptr())) {
|
||||
if (!isinstance<sequence>(src) || isinstance<bytes>(src) || isinstance<str>(src)) {
|
||||
return false;
|
||||
}
|
||||
if (isinstance<sequence>(src)) {
|
||||
return convert_elements(src, convert);
|
||||
}
|
||||
if (!convert) {
|
||||
return false;
|
||||
}
|
||||
// Designed to be behavior-equivalent to passing tuple(src) from Python:
|
||||
// The conversion to a tuple will first exhaust the generator object, to ensure that
|
||||
// the generator is not left in an unpredictable (to the caller) partially-consumed
|
||||
// state.
|
||||
assert(isinstance<iterable>(src));
|
||||
return convert_elements(tuple(reinterpret_borrow<iterable>(src)), convert);
|
||||
}
|
||||
|
||||
private:
|
||||
template <typename T = Type, enable_if_t<has_reserve_method<T>::value, int> = 0>
|
||||
void reserve_maybe(const sequence &s, Type *) {
|
||||
value.reserve(s.size());
|
||||
}
|
||||
void reserve_maybe(const sequence &, void *) {}
|
||||
|
||||
bool convert_elements(handle seq, bool convert) {
|
||||
auto s = reinterpret_borrow<sequence>(seq);
|
||||
auto s = reinterpret_borrow<sequence>(src);
|
||||
value.clear();
|
||||
reserve_maybe(s, &value);
|
||||
for (const auto &it : seq) {
|
||||
for (const auto &it : s) {
|
||||
value_conv conv;
|
||||
if (!conv.load(it, convert)) {
|
||||
return false;
|
||||
|
@ -321,6 +182,13 @@ private:
|
|||
return true;
|
||||
}
|
||||
|
||||
private:
|
||||
template <typename T = Type, enable_if_t<has_reserve_method<T>::value, int> = 0>
|
||||
void reserve_maybe(const sequence &s, Type *) {
|
||||
value.reserve(s.size());
|
||||
}
|
||||
void reserve_maybe(const sequence &, void *) {}
|
||||
|
||||
public:
|
||||
template <typename T>
|
||||
static handle cast(T &&src, return_value_policy policy, handle parent) {
|
||||
|
@ -352,87 +220,43 @@ struct type_caster<std::deque<Type, Alloc>> : list_caster<std::deque<Type, Alloc
|
|||
template <typename Type, typename Alloc>
|
||||
struct type_caster<std::list<Type, Alloc>> : list_caster<std::list<Type, Alloc>, Type> {};
|
||||
|
||||
template <typename ArrayType, typename V, size_t... I>
|
||||
ArrayType vector_to_array_impl(V &&v, index_sequence<I...>) {
|
||||
return {{std::move(v[I])...}};
|
||||
}
|
||||
|
||||
// Based on https://en.cppreference.com/w/cpp/container/array/to_array
|
||||
template <typename ArrayType, size_t N, typename V>
|
||||
ArrayType vector_to_array(V &&v) {
|
||||
return vector_to_array_impl<ArrayType, V>(std::forward<V>(v), make_index_sequence<N>{});
|
||||
}
|
||||
|
||||
template <typename ArrayType, typename Value, bool Resizable, size_t Size = 0>
|
||||
struct array_caster {
|
||||
using value_conv = make_caster<Value>;
|
||||
|
||||
private:
|
||||
std::unique_ptr<ArrayType> value;
|
||||
template <bool R = Resizable>
|
||||
bool require_size(enable_if_t<R, size_t> size) {
|
||||
if (value.size() != size) {
|
||||
value.resize(size);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
template <bool R = Resizable>
|
||||
bool require_size(enable_if_t<!R, size_t> size) {
|
||||
return size == Size;
|
||||
}
|
||||
|
||||
template <bool R = Resizable, enable_if_t<R, int> = 0>
|
||||
bool convert_elements(handle seq, bool convert) {
|
||||
auto l = reinterpret_borrow<sequence>(seq);
|
||||
value.reset(new ArrayType{});
|
||||
// Using `resize` to preserve the behavior exactly as it was before PR #5305
|
||||
// For the `resize` to work, `Value` must be default constructible.
|
||||
// For `std::valarray`, this is a requirement:
|
||||
// https://en.cppreference.com/w/cpp/named_req/NumericType
|
||||
value->resize(l.size());
|
||||
public:
|
||||
bool load(handle src, bool convert) {
|
||||
if (!isinstance<sequence>(src)) {
|
||||
return false;
|
||||
}
|
||||
auto l = reinterpret_borrow<sequence>(src);
|
||||
if (!require_size(l.size())) {
|
||||
return false;
|
||||
}
|
||||
size_t ctr = 0;
|
||||
for (const auto &it : l) {
|
||||
value_conv conv;
|
||||
if (!conv.load(it, convert)) {
|
||||
return false;
|
||||
}
|
||||
(*value)[ctr++] = cast_op<Value &&>(std::move(conv));
|
||||
value[ctr++] = cast_op<Value &&>(std::move(conv));
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
template <bool R = Resizable, enable_if_t<!R, int> = 0>
|
||||
bool convert_elements(handle seq, bool convert) {
|
||||
auto l = reinterpret_borrow<sequence>(seq);
|
||||
if (l.size() != Size) {
|
||||
return false;
|
||||
}
|
||||
// The `temp` storage is needed to support `Value` types that are not
|
||||
// default-constructible.
|
||||
// Deliberate choice: no template specializations, for simplicity, and
|
||||
// because the compile time overhead for the specializations is deemed
|
||||
// more significant than the runtime overhead for the `temp` storage.
|
||||
std::vector<Value> temp;
|
||||
temp.reserve(l.size());
|
||||
for (auto it : l) {
|
||||
value_conv conv;
|
||||
if (!conv.load(it, convert)) {
|
||||
return false;
|
||||
}
|
||||
temp.emplace_back(cast_op<Value &&>(std::move(conv)));
|
||||
}
|
||||
value.reset(new ArrayType(vector_to_array<ArrayType, Size>(std::move(temp))));
|
||||
return true;
|
||||
}
|
||||
|
||||
public:
|
||||
bool load(handle src, bool convert) {
|
||||
if (!PyObjectTypeIsConvertibleToStdVector(src.ptr())) {
|
||||
return false;
|
||||
}
|
||||
if (isinstance<sequence>(src)) {
|
||||
return convert_elements(src, convert);
|
||||
}
|
||||
if (!convert) {
|
||||
return false;
|
||||
}
|
||||
// Designed to be behavior-equivalent to passing tuple(src) from Python:
|
||||
// The conversion to a tuple will first exhaust the generator object, to ensure that
|
||||
// the generator is not left in an unpredictable (to the caller) partially-consumed
|
||||
// state.
|
||||
assert(isinstance<iterable>(src));
|
||||
return convert_elements(tuple(reinterpret_borrow<iterable>(src)), convert);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static handle cast(T &&src, return_value_policy policy, handle parent) {
|
||||
list l(src.size());
|
||||
|
@ -448,36 +272,12 @@ public:
|
|||
return l.release();
|
||||
}
|
||||
|
||||
// Code copied from PYBIND11_TYPE_CASTER macro.
|
||||
// Intentionally preserving the behavior exactly as it was before PR #5305
|
||||
template <typename T_, enable_if_t<std::is_same<ArrayType, remove_cv_t<T_>>::value, int> = 0>
|
||||
static handle cast(T_ *src, return_value_policy policy, handle parent) {
|
||||
if (!src) {
|
||||
return none().release();
|
||||
}
|
||||
if (policy == return_value_policy::take_ownership) {
|
||||
auto h = cast(std::move(*src), policy, parent);
|
||||
delete src; // WARNING: Assumes `src` was allocated with `new`.
|
||||
return h;
|
||||
}
|
||||
return cast(*src, policy, parent);
|
||||
}
|
||||
|
||||
// NOLINTNEXTLINE(google-explicit-constructor)
|
||||
operator ArrayType *() { return &(*value); }
|
||||
// NOLINTNEXTLINE(google-explicit-constructor)
|
||||
operator ArrayType &() { return *value; }
|
||||
// NOLINTNEXTLINE(google-explicit-constructor)
|
||||
operator ArrayType &&() && { return std::move(*value); }
|
||||
|
||||
template <typename T_>
|
||||
using cast_op_type = movable_cast_op_type<T_>;
|
||||
|
||||
static constexpr auto name
|
||||
= const_name<Resizable>(const_name(""), const_name("Annotated[")) + const_name("list[")
|
||||
+ value_conv::name + const_name("]")
|
||||
+ const_name<Resizable>(
|
||||
const_name(""), const_name(", FixedSize(") + const_name<Size>() + const_name(")]"));
|
||||
PYBIND11_TYPE_CASTER(ArrayType,
|
||||
const_name<Resizable>(const_name(""), const_name("Annotated["))
|
||||
+ const_name("list[") + value_conv::name + const_name("]")
|
||||
+ const_name<Resizable>(const_name(""),
|
||||
const_name(", FixedSize(")
|
||||
+ const_name<Size>() + const_name(")]")));
|
||||
};
|
||||
|
||||
template <typename Type, size_t Size>
|
||||
|
|
|
@ -106,7 +106,7 @@ public:
|
|||
return true;
|
||||
}
|
||||
|
||||
PYBIND11_TYPE_CASTER(T, io_name("Union[os.PathLike, str, bytes]", "pathlib.Path"));
|
||||
PYBIND11_TYPE_CASTER(T, const_name("os.PathLike"));
|
||||
};
|
||||
|
||||
#endif // PYBIND11_HAS_FILESYSTEM || defined(PYBIND11_HAS_EXPERIMENTAL_FILESYSTEM)
|
||||
|
|
|
@ -487,7 +487,7 @@ PYBIND11_NAMESPACE_END(detail)
|
|||
//
|
||||
// std::vector
|
||||
//
|
||||
template <typename Vector, typename holder_type = default_holder_type<Vector>, typename... Args>
|
||||
template <typename Vector, typename holder_type = std::unique_ptr<Vector>, typename... Args>
|
||||
class_<Vector, holder_type> bind_vector(handle scope, std::string const &name, Args &&...args) {
|
||||
using Class_ = class_<Vector, holder_type>;
|
||||
|
||||
|
@ -694,43 +694,9 @@ struct ItemsViewImpl : public detail::items_view {
|
|||
Map ↦
|
||||
};
|
||||
|
||||
inline str format_message_key_error_key_object(handle py_key) {
|
||||
str message = "pybind11::bind_map key";
|
||||
if (!py_key) {
|
||||
return message;
|
||||
}
|
||||
try {
|
||||
message = str(py_key);
|
||||
} catch (const std::exception &) {
|
||||
try {
|
||||
message = repr(py_key);
|
||||
} catch (const std::exception &) {
|
||||
return message;
|
||||
}
|
||||
}
|
||||
const ssize_t cut_length = 100;
|
||||
if (len(message) > 2 * cut_length + 3) {
|
||||
return str(message[slice(0, cut_length, 1)]) + str("✄✄✄")
|
||||
+ str(message[slice(-cut_length, static_cast<ssize_t>(len(message)), 1)]);
|
||||
}
|
||||
return message;
|
||||
}
|
||||
|
||||
template <typename KeyType>
|
||||
str format_message_key_error(const KeyType &key) {
|
||||
object py_key;
|
||||
try {
|
||||
py_key = cast(key);
|
||||
} catch (const std::exception &) {
|
||||
do { // Trick to avoid "empty catch" warning/error.
|
||||
} while (false);
|
||||
}
|
||||
return format_message_key_error_key_object(py_key);
|
||||
}
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
|
||||
template <typename Map, typename holder_type = default_holder_type<Map>, typename... Args>
|
||||
template <typename Map, typename holder_type = std::unique_ptr<Map>, typename... Args>
|
||||
class_<Map, holder_type> bind_map(handle scope, const std::string &name, Args &&...args) {
|
||||
using KeyType = typename Map::key_type;
|
||||
using MappedType = typename Map::mapped_type;
|
||||
|
@ -819,8 +785,7 @@ class_<Map, holder_type> bind_map(handle scope, const std::string &name, Args &&
|
|||
[](Map &m, const KeyType &k) -> MappedType & {
|
||||
auto it = m.find(k);
|
||||
if (it == m.end()) {
|
||||
set_error(PyExc_KeyError, detail::format_message_key_error(k));
|
||||
throw error_already_set();
|
||||
throw key_error();
|
||||
}
|
||||
return it->second;
|
||||
},
|
||||
|
@ -843,8 +808,7 @@ class_<Map, holder_type> bind_map(handle scope, const std::string &name, Args &&
|
|||
cl.def("__delitem__", [](Map &m, const KeyType &k) {
|
||||
auto it = m.find(k);
|
||||
if (it == m.end()) {
|
||||
set_error(PyExc_KeyError, detail::format_message_key_error(k));
|
||||
throw error_already_set();
|
||||
throw key_error();
|
||||
}
|
||||
m.erase(it);
|
||||
});
|
||||
|
|
|
@ -1,60 +0,0 @@
|
|||
// Copyright (c) 2021 The Pybind Development Team.
|
||||
// All rights reserved. Use of this source code is governed by a
|
||||
// BSD-style license that can be found in the LICENSE file.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "detail/common.h"
|
||||
#include "detail/using_smart_holder.h"
|
||||
#include "detail/value_and_holder.h"
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
// PYBIND11:REMINDER: Needs refactoring of existing pybind11 code.
|
||||
inline bool deregister_instance(instance *self, void *valptr, const type_info *tinfo);
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
|
||||
// The original core idea for this struct goes back to PyCLIF:
|
||||
// https://github.com/google/clif/blob/07f95d7e69dca2fcf7022978a55ef3acff506c19/clif/python/runtime.cc#L37
|
||||
// URL provided here mainly to give proper credit.
|
||||
struct trampoline_self_life_support {
|
||||
detail::value_and_holder v_h;
|
||||
|
||||
trampoline_self_life_support() = default;
|
||||
|
||||
void activate_life_support(const detail::value_and_holder &v_h_) {
|
||||
Py_INCREF((PyObject *) v_h_.inst);
|
||||
v_h = v_h_;
|
||||
}
|
||||
|
||||
void deactivate_life_support() {
|
||||
Py_DECREF((PyObject *) v_h.inst);
|
||||
v_h = detail::value_and_holder();
|
||||
}
|
||||
|
||||
~trampoline_self_life_support() {
|
||||
if (v_h.inst != nullptr && v_h.vh != nullptr) {
|
||||
void *value_void_ptr = v_h.value_ptr();
|
||||
if (value_void_ptr != nullptr) {
|
||||
PyGILState_STATE threadstate = PyGILState_Ensure();
|
||||
v_h.value_ptr() = nullptr;
|
||||
v_h.holder<smart_holder>().release_disowned();
|
||||
detail::deregister_instance(v_h.inst, value_void_ptr, v_h.type);
|
||||
Py_DECREF((PyObject *) v_h.inst); // Must be after deregister.
|
||||
PyGILState_Release(threadstate);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// For the next two, the default implementations generate undefined behavior (ASAN failures
|
||||
// manually verified). The reason is that v_h needs to be kept default-initialized.
|
||||
trampoline_self_life_support(const trampoline_self_life_support &) {}
|
||||
trampoline_self_life_support(trampoline_self_life_support &&) noexcept {}
|
||||
|
||||
// These should never be needed (please provide test cases if you think they are).
|
||||
trampoline_self_life_support &operator=(const trampoline_self_life_support &) = delete;
|
||||
trampoline_self_life_support &operator=(trampoline_self_life_support &&) = delete;
|
||||
};
|
||||
|
||||
PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE)
|
|
@ -16,13 +16,6 @@
|
|||
|
||||
#include <algorithm>
|
||||
|
||||
#if defined(__cpp_nontype_template_args) && __cpp_nontype_template_args >= 201911L
|
||||
# define PYBIND11_TYPING_H_HAS_STRING_LITERAL
|
||||
# include <numeric>
|
||||
# include <ranges>
|
||||
# include <string_view>
|
||||
#endif
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
PYBIND11_NAMESPACE_BEGIN(typing)
|
||||
|
||||
|
@ -89,18 +82,6 @@ class Optional : public object {
|
|||
using object::object;
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
class Final : public object {
|
||||
PYBIND11_OBJECT_DEFAULT(Final, object, PyObject_Type)
|
||||
using object::object;
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
class ClassVar : public object {
|
||||
PYBIND11_OBJECT_DEFAULT(ClassVar, object, PyObject_Type)
|
||||
using object::object;
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
class TypeGuard : public bool_ {
|
||||
using bool_::bool_;
|
||||
|
@ -119,7 +100,8 @@ class Never : public none {
|
|||
using none::none;
|
||||
};
|
||||
|
||||
#if defined(PYBIND11_TYPING_H_HAS_STRING_LITERAL)
|
||||
#if defined(__cpp_nontype_template_args) && __cpp_nontype_template_args >= 201911L
|
||||
# define PYBIND11_TYPING_H_HAS_STRING_LITERAL
|
||||
template <size_t N>
|
||||
struct StringLiteral {
|
||||
constexpr StringLiteral(const char (&str)[N]) { std::copy_n(str, N, name); }
|
||||
|
@ -194,19 +176,16 @@ template <typename Return, typename... Args>
|
|||
struct handle_type_name<typing::Callable<Return(Args...)>> {
|
||||
using retval_type = conditional_t<std::is_same<Return, void>::value, void_type, Return>;
|
||||
static constexpr auto name
|
||||
= const_name("Callable[[")
|
||||
+ ::pybind11::detail::concat(::pybind11::detail::arg_descr(make_caster<Args>::name)...)
|
||||
+ const_name("], ") + ::pybind11::detail::return_descr(make_caster<retval_type>::name)
|
||||
+ const_name("]");
|
||||
= const_name("Callable[[") + ::pybind11::detail::concat(make_caster<Args>::name...)
|
||||
+ const_name("], ") + make_caster<retval_type>::name + const_name("]");
|
||||
};
|
||||
|
||||
template <typename Return>
|
||||
struct handle_type_name<typing::Callable<Return(ellipsis)>> {
|
||||
// PEP 484 specifies this syntax for defining only return types of callables
|
||||
using retval_type = conditional_t<std::is_same<Return, void>::value, void_type, Return>;
|
||||
static constexpr auto name = const_name("Callable[..., ")
|
||||
+ ::pybind11::detail::return_descr(make_caster<retval_type>::name)
|
||||
+ const_name("]");
|
||||
static constexpr auto name
|
||||
= const_name("Callable[..., ") + make_caster<retval_type>::name + const_name("]");
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
|
@ -226,16 +205,6 @@ struct handle_type_name<typing::Optional<T>> {
|
|||
static constexpr auto name = const_name("Optional[") + make_caster<T>::name + const_name("]");
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
struct handle_type_name<typing::Final<T>> {
|
||||
static constexpr auto name = const_name("Final[") + make_caster<T>::name + const_name("]");
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
struct handle_type_name<typing::ClassVar<T>> {
|
||||
static constexpr auto name = const_name("ClassVar[") + make_caster<T>::name + const_name("]");
|
||||
};
|
||||
|
||||
template <typename T>
|
||||
struct handle_type_name<typing::TypeGuard<T>> {
|
||||
static constexpr auto name = const_name("TypeGuard[") + make_caster<T>::name + const_name("]");
|
||||
|
@ -257,35 +226,15 @@ struct handle_type_name<typing::Never> {
|
|||
};
|
||||
|
||||
#if defined(PYBIND11_TYPING_H_HAS_STRING_LITERAL)
|
||||
template <typing::StringLiteral StrLit>
|
||||
consteval auto sanitize_string_literal() {
|
||||
constexpr std::string_view v(StrLit.name);
|
||||
constexpr std::string_view special_chars("!@%{}-");
|
||||
constexpr auto num_special_chars = std::accumulate(
|
||||
special_chars.begin(), special_chars.end(), (size_t) 0, [&v](auto acc, const char &c) {
|
||||
return std::move(acc) + std::ranges::count(v, c);
|
||||
});
|
||||
char result[v.size() + num_special_chars + 1];
|
||||
size_t i = 0;
|
||||
for (auto c : StrLit.name) {
|
||||
if (special_chars.find(c) != std::string_view::npos) {
|
||||
result[i++] = '!';
|
||||
}
|
||||
result[i++] = c;
|
||||
}
|
||||
return typing::StringLiteral(result);
|
||||
}
|
||||
|
||||
template <typing::StringLiteral... Literals>
|
||||
struct handle_type_name<typing::Literal<Literals...>> {
|
||||
static constexpr auto name
|
||||
= const_name("Literal[")
|
||||
+ pybind11::detail::concat(const_name(sanitize_string_literal<Literals>().name)...)
|
||||
+ const_name("]");
|
||||
static constexpr auto name = const_name("Literal[")
|
||||
+ pybind11::detail::concat(const_name(Literals.name)...)
|
||||
+ const_name("]");
|
||||
};
|
||||
template <typing::StringLiteral StrLit>
|
||||
struct handle_type_name<typing::TypeVar<StrLit>> {
|
||||
static constexpr auto name = const_name(sanitize_string_literal<StrLit>().name);
|
||||
static constexpr auto name = const_name(StrLit.name);
|
||||
};
|
||||
#endif
|
||||
|
||||
|
|
|
@ -1,75 +0,0 @@
|
|||
/*
|
||||
pybind11/warnings.h: Python warnings wrappers.
|
||||
|
||||
Copyright (c) 2024 Jan Iwaszkiewicz <jiwaszkiewicz6@gmail.com>
|
||||
|
||||
All rights reserved. Use of this source code is governed by a
|
||||
BSD-style license that can be found in the LICENSE file.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "pybind11.h"
|
||||
#include "detail/common.h"
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE)
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(detail)
|
||||
|
||||
inline bool PyWarning_Check(PyObject *obj) {
|
||||
int result = PyObject_IsSubclass(obj, PyExc_Warning);
|
||||
if (result == 1) {
|
||||
return true;
|
||||
}
|
||||
if (result == -1) {
|
||||
raise_from(PyExc_SystemError,
|
||||
"pybind11::detail::PyWarning_Check(): PyObject_IsSubclass() call failed.");
|
||||
throw error_already_set();
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
PYBIND11_NAMESPACE_END(detail)
|
||||
|
||||
PYBIND11_NAMESPACE_BEGIN(warnings)
|
||||
|
||||
inline object
|
||||
new_warning_type(handle scope, const char *name, handle base = PyExc_RuntimeWarning) {
|
||||
if (!detail::PyWarning_Check(base.ptr())) {
|
||||
pybind11_fail("pybind11::warnings::new_warning_type(): cannot create custom warning, base "
|
||||
"must be a subclass of "
|
||||
"PyExc_Warning!");
|
||||
}
|
||||
if (hasattr(scope, name)) {
|
||||
pybind11_fail("pybind11::warnings::new_warning_type(): an attribute with name \""
|
||||
+ std::string(name) + "\" exists already.");
|
||||
}
|
||||
std::string full_name = scope.attr("__name__").cast<std::string>() + std::string(".") + name;
|
||||
handle h(PyErr_NewException(full_name.c_str(), base.ptr(), nullptr));
|
||||
if (!h) {
|
||||
raise_from(PyExc_SystemError,
|
||||
"pybind11::warnings::new_warning_type(): PyErr_NewException() call failed.");
|
||||
throw error_already_set();
|
||||
}
|
||||
auto obj = reinterpret_steal<object>(h);
|
||||
scope.attr(name) = obj;
|
||||
return obj;
|
||||
}
|
||||
|
||||
// Similar to Python `warnings.warn()`
|
||||
inline void
|
||||
warn(const char *message, handle category = PyExc_RuntimeWarning, int stack_level = 2) {
|
||||
if (!detail::PyWarning_Check(category.ptr())) {
|
||||
pybind11_fail(
|
||||
"pybind11::warnings::warn(): cannot raise warning, category must be a subclass of "
|
||||
"PyExc_Warning!");
|
||||
}
|
||||
|
||||
if (PyErr_WarnEx(category.ptr(), message, stack_level) == -1) {
|
||||
throw error_already_set();
|
||||
}
|
||||
}
|
||||
|
||||
PYBIND11_NAMESPACE_END(warnings)
|
||||
|
||||
PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE)
|
|
@ -2,8 +2,8 @@ from __future__ import annotations
|
|||
|
||||
import sys
|
||||
|
||||
if sys.version_info < (3, 8): # noqa: UP036
|
||||
msg = "pybind11 does not support Python < 3.8. v2.13 was the last release supporting Python 3.7."
|
||||
if sys.version_info < (3, 7): # noqa: UP036
|
||||
msg = "pybind11 does not support Python < 3.7. v2.12 was the last release supporting Python 3.6."
|
||||
raise ImportError(msg)
|
||||
|
||||
|
||||
|
|
|
@ -71,11 +71,6 @@ def main() -> None:
|
|||
action="store_true",
|
||||
help="Print the pkgconfig directory, ideal for setting $PKG_CONFIG_PATH.",
|
||||
)
|
||||
parser.add_argument(
|
||||
"--extension-suffix",
|
||||
action="store_true",
|
||||
help="Print the extension for a Python module",
|
||||
)
|
||||
args = parser.parse_args()
|
||||
if not sys.argv[1:]:
|
||||
parser.print_help()
|
||||
|
@ -85,8 +80,6 @@ def main() -> None:
|
|||
print(quote(get_cmake_dir()))
|
||||
if args.pkgconfigdir:
|
||||
print(quote(get_pkgconfig_dir()))
|
||||
if args.extension_suffix:
|
||||
print(sysconfig.get_config_var("EXT_SUFFIX"))
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
|
|
@ -8,5 +8,5 @@ def _to_int(s: str) -> int | str:
|
|||
return s
|
||||
|
||||
|
||||
__version__ = "3.0.0.dev1"
|
||||
__version__ = "2.13.6"
|
||||
version_info = tuple(_to_int(s) for s in __version__.split("."))
|
||||
|
|
|
@ -249,7 +249,7 @@ def has_flag(compiler: Any, flag: str) -> bool:
|
|||
cpp_flag_cache = None
|
||||
|
||||
|
||||
@lru_cache
|
||||
@lru_cache()
|
||||
def auto_cpp_level(compiler: Any) -> str | int:
|
||||
"""
|
||||
Return the max supported C++ std level (17, 14, or 11). Returns latest on Windows.
|
||||
|
|
|
@ -30,7 +30,7 @@ ignore_missing_imports = true
|
|||
|
||||
|
||||
[tool.pylint]
|
||||
master.py-version = "3.8"
|
||||
master.py-version = "3.7"
|
||||
reports.output-format = "colorized"
|
||||
messages_control.disable = [
|
||||
"design",
|
||||
|
@ -45,7 +45,7 @@ messages_control.disable = [
|
|||
]
|
||||
|
||||
[tool.ruff]
|
||||
target-version = "py38"
|
||||
target-version = "py37"
|
||||
src = ["src"]
|
||||
|
||||
[tool.ruff.lint]
|
||||
|
@ -71,6 +71,7 @@ ignore = [
|
|||
"PLR", # Design related pylint
|
||||
"E501", # Line too long (Black is enough)
|
||||
"PT011", # Too broad with raises in pytest
|
||||
"PT004", # Fixture that doesn't return needs underscore (no, it is fine)
|
||||
"SIM118", # iter(x) is not always the same as iter(x.keys())
|
||||
]
|
||||
unfixable = ["T20"]
|
||||
|
|
|
@ -14,6 +14,7 @@ classifiers =
|
|||
Topic :: Utilities
|
||||
Programming Language :: C++
|
||||
Programming Language :: Python :: 3 :: Only
|
||||
Programming Language :: Python :: 3.7
|
||||
Programming Language :: Python :: 3.8
|
||||
Programming Language :: Python :: 3.9
|
||||
Programming Language :: Python :: 3.10
|
||||
|
@ -38,5 +39,5 @@ project_urls =
|
|||
Chat = https://gitter.im/pybind/Lobby
|
||||
|
||||
[options]
|
||||
python_requires = >=3.8
|
||||
python_requires = >=3.7
|
||||
zip_safe = False
|
||||
|
|
|
@ -144,10 +144,6 @@ with remove_output("pybind11/include", "pybind11/share"):
|
|||
stderr=sys.stderr,
|
||||
)
|
||||
|
||||
# pkgconf-pypi needs pybind11/share/pkgconfig to be importable
|
||||
Path("pybind11/share/__init__.py").touch()
|
||||
Path("pybind11/share/pkgconfig/__init__.py").touch()
|
||||
|
||||
txt = get_and_replace(setup_py, version=version, extra_cmd=extra_cmd)
|
||||
code = compile(txt, setup_py, "exec")
|
||||
exec(code, {"SDist": SDist})
|
||||
|
|
|
@ -5,7 +5,16 @@
|
|||
# All rights reserved. Use of this source code is governed by a
|
||||
# BSD-style license that can be found in the LICENSE file.
|
||||
|
||||
cmake_minimum_required(VERSION 3.15...3.30)
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
|
||||
# The `cmake_minimum_required(VERSION 3.5...3.29)` syntax does not work with
|
||||
# some versions of VS that have a patched CMake 3.11. This forces us to emulate
|
||||
# the behavior using the following workaround:
|
||||
if(${CMAKE_VERSION} VERSION_LESS 3.29)
|
||||
cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION})
|
||||
else()
|
||||
cmake_policy(VERSION 3.29)
|
||||
endif()
|
||||
|
||||
# Filter out items; print an optional message if any items filtered. This ignores extensions.
|
||||
#
|
||||
|
@ -67,8 +76,8 @@ project(pybind11_tests CXX)
|
|||
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../tools")
|
||||
|
||||
option(PYBIND11_WERROR "Report all warnings as errors" OFF)
|
||||
option(DOWNLOAD_EIGEN "Download EIGEN" OFF)
|
||||
option(PYBIND11_CUDA_TESTS "Enable building CUDA tests" OFF)
|
||||
option(DOWNLOAD_EIGEN "Download EIGEN (requires CMake 3.11+)" OFF)
|
||||
option(PYBIND11_CUDA_TESTS "Enable building CUDA tests (requires CMake 3.12+)" OFF)
|
||||
set(PYBIND11_TEST_OVERRIDE
|
||||
""
|
||||
CACHE STRING "Tests from ;-separated list of *.cpp files will be built instead of all tests")
|
||||
|
@ -115,24 +124,6 @@ set(PYBIND11_TEST_FILES
|
|||
test_callbacks
|
||||
test_chrono
|
||||
test_class
|
||||
test_class_release_gil_before_calling_cpp_dtor
|
||||
test_class_sh_basic
|
||||
test_class_sh_disowning
|
||||
test_class_sh_disowning_mi
|
||||
test_class_sh_factory_constructors
|
||||
test_class_sh_inheritance
|
||||
test_class_sh_mi_thunks
|
||||
test_class_sh_property
|
||||
test_class_sh_property_non_owning
|
||||
test_class_sh_shared_ptr_copy_move
|
||||
test_class_sh_trampoline_basic
|
||||
test_class_sh_trampoline_self_life_support
|
||||
test_class_sh_trampoline_shared_from_this
|
||||
test_class_sh_trampoline_shared_ptr_cpp_arg
|
||||
test_class_sh_trampoline_unique_ptr
|
||||
test_class_sh_unique_ptr_custom_deleter
|
||||
test_class_sh_unique_ptr_member
|
||||
test_class_sh_virtual_py_cpp_mix
|
||||
test_const_name
|
||||
test_constants_and_functions
|
||||
test_copy_move
|
||||
|
@ -140,7 +131,6 @@ set(PYBIND11_TEST_FILES
|
|||
test_custom_type_casters
|
||||
test_custom_type_setup
|
||||
test_docstring_options
|
||||
test_docs_advanced_cast_custom
|
||||
test_eigen_matrix
|
||||
test_eigen_tensor
|
||||
test_enum
|
||||
|
@ -174,8 +164,7 @@ set(PYBIND11_TEST_FILES
|
|||
test_unnamed_namespace_a
|
||||
test_unnamed_namespace_b
|
||||
test_vector_unique_ptr_member
|
||||
test_virtual_functions
|
||||
test_warnings)
|
||||
test_virtual_functions)
|
||||
|
||||
# Invoking cmake with something like:
|
||||
# cmake -DPYBIND11_TEST_OVERRIDE="test_callbacks.cpp;test_pickling.cpp" ..
|
||||
|
@ -263,21 +252,25 @@ endif()
|
|||
if(PYBIND11_TEST_FILES_EIGEN_I GREATER -1)
|
||||
# Try loading via newer Eigen's Eigen3Config first (bypassing tools/FindEigen3.cmake).
|
||||
# Eigen 3.3.1+ exports a cmake 3.0+ target for handling dependency requirements, but also
|
||||
# produces a fatal error if loaded from a pre-3.0 cmake.
|
||||
if(DOWNLOAD_EIGEN)
|
||||
if(CMAKE_VERSION VERSION_LESS 3.18)
|
||||
set(_opts)
|
||||
else()
|
||||
set(_opts SOURCE_SUBDIR no-cmake-build)
|
||||
if(CMAKE_VERSION VERSION_LESS 3.11)
|
||||
message(FATAL_ERROR "CMake 3.11+ required when using DOWNLOAD_EIGEN")
|
||||
endif()
|
||||
|
||||
include(FetchContent)
|
||||
FetchContent_Declare(
|
||||
eigen
|
||||
GIT_REPOSITORY "${PYBIND11_EIGEN_REPO}"
|
||||
GIT_TAG "${PYBIND11_EIGEN_VERSION_HASH}"
|
||||
${_opts})
|
||||
FetchContent_MakeAvailable(eigen)
|
||||
if(NOT CMAKE_VERSION VERSION_LESS 3.18)
|
||||
set(EIGEN3_INCLUDE_DIR "${eigen_SOURCE_DIR}")
|
||||
GIT_TAG "${PYBIND11_EIGEN_VERSION_HASH}")
|
||||
|
||||
FetchContent_GetProperties(eigen)
|
||||
if(NOT eigen_POPULATED)
|
||||
message(
|
||||
STATUS
|
||||
"Downloading Eigen ${PYBIND11_EIGEN_VERSION_STRING} (${PYBIND11_EIGEN_VERSION_HASH}) from ${PYBIND11_EIGEN_REPO}"
|
||||
)
|
||||
FetchContent_Populate(eigen)
|
||||
endif()
|
||||
|
||||
set(EIGEN3_INCLUDE_DIR ${eigen_SOURCE_DIR})
|
||||
|
@ -325,7 +318,8 @@ if(PYBIND11_TEST_FILES_EIGEN_I GREATER -1)
|
|||
if(PYBIND11_TEST_FILES_EIGEN_I GREATER -1)
|
||||
list(REMOVE_AT PYBIND11_TEST_FILES ${PYBIND11_TEST_FILES_EIGEN_I})
|
||||
endif()
|
||||
message(STATUS "Building tests WITHOUT Eigen, use -DDOWNLOAD_EIGEN=ON to download")
|
||||
message(
|
||||
STATUS "Building tests WITHOUT Eigen, use -DDOWNLOAD_EIGEN=ON on CMake 3.11+ to download")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
|
@ -510,19 +504,15 @@ foreach(target ${test_targets})
|
|||
if(SKBUILD)
|
||||
install(TARGETS ${target} LIBRARY DESTINATION .)
|
||||
endif()
|
||||
|
||||
if("${target}" STREQUAL "exo_planet_c_api")
|
||||
if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Intel|Clang|NVHPC)")
|
||||
target_compile_options(${target} PRIVATE -fno-exceptions)
|
||||
endif()
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
# Provide nice organisation in IDEs
|
||||
source_group(
|
||||
TREE "${CMAKE_CURRENT_SOURCE_DIR}/../include"
|
||||
PREFIX "Header Files"
|
||||
FILES ${PYBIND11_HEADERS})
|
||||
if(NOT CMAKE_VERSION VERSION_LESS 3.8)
|
||||
source_group(
|
||||
TREE "${CMAKE_CURRENT_SOURCE_DIR}/../include"
|
||||
PREFIX "Header Files"
|
||||
FILES ${PYBIND11_HEADERS})
|
||||
endif()
|
||||
|
||||
# Make sure pytest is found or produce a warning
|
||||
pybind11_find_import(pytest VERSION 3.1)
|
||||
|
@ -606,9 +596,6 @@ add_custom_command(
|
|||
${CMAKE_CURRENT_BINARY_DIR}/sosize-$<TARGET_FILE_NAME:pybind11_tests>.txt)
|
||||
|
||||
if(NOT PYBIND11_CUDA_TESTS)
|
||||
# Test pure C++ code (not depending on Python). Provides the `test_pure_cpp` target.
|
||||
add_subdirectory(pure_cpp)
|
||||
|
||||
# Test embedding the interpreter. Provides the `cpptest` target.
|
||||
add_subdirectory(test_embed)
|
||||
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue