diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index 5417018365..72e27e3b68 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -25,16 +25,16 @@ jobs: # Github Actions requires a single row to be added to the build matrix. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. name: [ - macos-11-xcode-13.4.1, + macos-12-xcode-14.2, ] build_type: [Debug, Release] build_unstable: [ON] include: - - name: macos-11-xcode-13.4.1 - os: macos-11 + - name: macos-12-xcode-14.2 + os: macos-12 compiler: xcode - version: "13.4.1" + version: "14.2" steps: - name: Checkout diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 879777cc97..037704a36b 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -31,7 +31,7 @@ jobs: ubuntu-20.04-gcc-9, ubuntu-20.04-gcc-9-tbb, ubuntu-20.04-clang-9, - macOS-11-xcode-13.4.1, + macos-12-xcode-14.2, windows-2022-msbuild, ] @@ -54,10 +54,10 @@ jobs: compiler: clang version: "9" - - name: macOS-11-xcode-13.4.1 - os: macOS-11 + - name: macos-12-xcode-14.2 + os: macos-12 compiler: xcode - version: "13.4.1" + version: "14.2" - name: windows-2022-msbuild os: windows-2022 diff --git a/gtsam/base/base.i b/gtsam/base/base.i index 31d09cb3d5..3dc438e16d 100644 --- a/gtsam/base/base.i +++ b/gtsam/base/base.i @@ -86,7 +86,7 @@ class IndexPairSetMap { #include #include -bool linear_independent(Matrix A, Matrix B, double tol); +bool linear_independent(gtsam::Matrix A, gtsam::Matrix B, double tol); #include virtual class Value { @@ -100,7 +100,7 @@ virtual class Value { }; #include -template class FourierBasis { - static Vector CalculateWeights(size_t N, double x); - static Matrix WeightMatrix(size_t N, Vector x); + static gtsam::Vector CalculateWeights(size_t N, double x); + static gtsam::Matrix WeightMatrix(size_t N, gtsam::Vector x); - static Matrix DifferentiationMatrix(size_t N); - static Vector DerivativeWeights(size_t N, double x); + static gtsam::Matrix DifferentiationMatrix(size_t N); + static gtsam::Vector DerivativeWeights(size_t N, double x); }; #include class Chebyshev1Basis { - static Matrix CalculateWeights(size_t N, double x); - static Matrix WeightMatrix(size_t N, Vector X); + static gtsam::Matrix CalculateWeights(size_t N, double x); + static gtsam::Matrix WeightMatrix(size_t N, gtsam::Vector X); }; class Chebyshev2Basis { - static Matrix CalculateWeights(size_t N, double x); - static Matrix WeightMatrix(size_t N, Vector x); + static gtsam::Matrix CalculateWeights(size_t N, double x); + static gtsam::Matrix WeightMatrix(size_t N, gtsam::Vector x); }; #include @@ -34,16 +34,16 @@ class Chebyshev2 { static double Point(size_t N, int j); static double Point(size_t N, int j, double a, double b); - static Vector Points(size_t N); - static Vector Points(size_t N, double a, double b); + static gtsam::Vector Points(size_t N); + static gtsam::Vector Points(size_t N, double a, double b); - static Matrix WeightMatrix(size_t N, Vector X); - static Matrix WeightMatrix(size_t N, Vector X, double a, double b); + 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 Matrix CalculateWeights(size_t N, double x, double a, double b); - static Matrix DerivativeWeights(size_t N, double x, double a, double b); - static Matrix IntegrationWeights(size_t N, double a, double b); - static Matrix DifferentiationMatrix(size_t N, double a, double b); + 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 DifferentiationMatrix(size_t N, double a, double b); }; #include @@ -64,10 +64,10 @@ template virtual class VectorEvaluationFactor : gtsam::NoiseModelFactor { VectorEvaluationFactor(); - VectorEvaluationFactor(gtsam::Key key, const Vector& z, + VectorEvaluationFactor(gtsam::Key key, const gtsam::Vector& z, const gtsam::noiseModel::Base* model, const size_t M, const size_t N, double x); - VectorEvaluationFactor(gtsam::Key key, const Vector& z, + VectorEvaluationFactor(gtsam::Key key, const gtsam::Vector& z, const gtsam::noiseModel::Base* model, const size_t M, const size_t N, double x, double a, double b); }; @@ -116,10 +116,10 @@ template virtual class VectorDerivativeFactor : gtsam::NoiseModelFactor { VectorDerivativeFactor(); - VectorDerivativeFactor(gtsam::Key key, const Vector& z, + VectorDerivativeFactor(gtsam::Key key, const gtsam::Vector& z, const gtsam::noiseModel::Base* model, const size_t M, const size_t N, double x); - VectorDerivativeFactor(gtsam::Key key, const Vector& z, + VectorDerivativeFactor(gtsam::Key key, const gtsam::Vector& z, const gtsam::noiseModel::Base* model, const size_t M, const size_t N, double x, double a, double b); }; diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 3cf78989ca..3d816fc25a 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -9,7 +9,7 @@ class Point2 { // Standard Constructors Point2(); Point2(double x, double y); - Point2(Vector v); + Point2(gtsam::Vector v); // Testable void print(string s = "") const; @@ -21,7 +21,7 @@ class Point2 { // Standard Interface double x() const; double y() const; - Vector vector() const; + gtsam::Vector vector() const; double distance(const gtsam::Point2& p2) const; double norm() const; @@ -83,21 +83,21 @@ class StereoPoint2 { // Operator Overloads gtsam::StereoPoint2 operator-() const; - // gtsam::StereoPoint2 operator+(Vector b) const; //TODO Mixed types not yet + // gtsam::StereoPoint2 operator+(gtsam::Vector b) const; //TODO Mixed types not yet // supported gtsam::StereoPoint2 operator+(const gtsam::StereoPoint2& p2) const; gtsam::StereoPoint2 operator-(const gtsam::StereoPoint2& p2) const; // Manifold - gtsam::StereoPoint2 retract(Vector v) const; - Vector localCoordinates(const gtsam::StereoPoint2& p) const; + gtsam::StereoPoint2 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::StereoPoint2& p) const; // Lie Group - static gtsam::StereoPoint2 Expmap(Vector v); - static Vector Logmap(const gtsam::StereoPoint2& p); + static gtsam::StereoPoint2 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::StereoPoint2& p); // Standard Interface - Vector vector() const; + gtsam::Vector vector() const; double uL() const; double uR() const; double v() const; @@ -111,7 +111,7 @@ class Point3 { // Standard Constructors Point3(); Point3(double x, double y, double z); - Point3(Vector v); + Point3(gtsam::Vector v); // Testable void print(string s = "") const; @@ -121,7 +121,7 @@ class Point3 { static gtsam::Point3 Identity(); // Standard Interface - Vector vector() const; + gtsam::Vector vector() const; double x() const; double y() const; double z() const; @@ -166,15 +166,15 @@ class Rot2 { gtsam::Rot2 operator*(const gtsam::Rot2& p2) const; // Manifold - gtsam::Rot2 retract(Vector v) const; - gtsam::Rot2 retract(Vector v, Eigen::Ref H1, Eigen::Ref H2) const; - Vector localCoordinates(const gtsam::Rot2& p) const; - Vector localCoordinates(const gtsam::Rot2& p, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Rot2 retract(gtsam::Vector v) const; + gtsam::Rot2 retract(gtsam::Vector v, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Vector localCoordinates(const gtsam::Rot2& p) const; + gtsam::Vector localCoordinates(const gtsam::Rot2& p, Eigen::Ref H1, Eigen::Ref H2) const; // Lie Group - static gtsam::Rot2 Expmap(Vector v); - static Vector Logmap(const gtsam::Rot2& p); - Vector logmap(const gtsam::Rot2& p); + static gtsam::Rot2 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::Rot2& p); + gtsam::Vector logmap(const gtsam::Rot2& p); // Group Action on Point2 gtsam::Point2 rotate(const gtsam::Point2& point) const; @@ -188,7 +188,7 @@ class Rot2 { double degrees() const; double c() const; double s() const; - Matrix matrix() const; + gtsam::Matrix matrix() const; // enabling serialization functionality void serialize() const; @@ -198,10 +198,10 @@ class Rot2 { class SO3 { // Standard Constructors SO3(); - SO3(Matrix R); - static gtsam::SO3 FromMatrix(Matrix R); - static gtsam::SO3 AxisAngle(const Vector axis, double theta); - static gtsam::SO3 ClosestTo(const Matrix M); + SO3(gtsam::Matrix R); + static gtsam::SO3 FromMatrix(gtsam::Matrix R); + static gtsam::SO3 AxisAngle(const gtsam::Vector axis, double theta); + static gtsam::SO3 ClosestTo(const gtsam::Matrix M); // Testable void print(string s = "") const; @@ -217,21 +217,21 @@ class SO3 { gtsam::SO3 operator*(const gtsam::SO3& R) const; // Manifold - gtsam::SO3 retract(Vector v) const; - Vector localCoordinates(const gtsam::SO3& R) const; - static gtsam::SO3 Expmap(Vector v); + gtsam::SO3 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::SO3& R) const; + static gtsam::SO3 Expmap(gtsam::Vector v); // Other methods - Vector vec() const; - Matrix matrix() const; + gtsam::Vector vec() const; + gtsam::Matrix matrix() const; }; #include class SO4 { // Standard Constructors SO4(); - SO4(Matrix R); - static gtsam::SO4 FromMatrix(Matrix R); + SO4(gtsam::Matrix R); + static gtsam::SO4 FromMatrix(gtsam::Matrix R); // Testable void print(string s = "") const; @@ -247,21 +247,21 @@ class SO4 { gtsam::SO4 operator*(const gtsam::SO4& Q) const; // Manifold - gtsam::SO4 retract(Vector v) const; - Vector localCoordinates(const gtsam::SO4& Q) const; - static gtsam::SO4 Expmap(Vector v); + gtsam::SO4 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::SO4& Q) const; + static gtsam::SO4 Expmap(gtsam::Vector v); // Other methods - Vector vec() const; - Matrix matrix() const; + gtsam::Vector vec() const; + gtsam::Matrix matrix() const; }; #include class SOn { // Standard Constructors SOn(size_t n); - static gtsam::SOn FromMatrix(Matrix R); - static gtsam::SOn Lift(size_t n, Matrix R); + static gtsam::SOn FromMatrix(gtsam::Matrix R); + static gtsam::SOn Lift(size_t n, gtsam::Matrix R); // Testable void print(string s = "") const; @@ -277,13 +277,13 @@ class SOn { gtsam::SOn operator*(const gtsam::SOn& Q) const; // Manifold - gtsam::SOn retract(Vector v) const; - Vector localCoordinates(const gtsam::SOn& Q) const; - static gtsam::SOn Expmap(Vector v); + gtsam::SOn retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::SOn& Q) const; + static gtsam::SOn Expmap(gtsam::Vector v); // Other methods - Vector vec() const; - Matrix matrix() const; + gtsam::Vector vec() const; + gtsam::Matrix matrix() const; // enabling serialization functionality void serialize() const; @@ -295,14 +295,14 @@ class Quaternion { double x() const; double y() const; double z() const; - Vector coeffs() const; + gtsam::Vector coeffs() const; }; #include class Rot3 { // Standard Constructors and Named Constructors Rot3(); - Rot3(Matrix R); + Rot3(gtsam::Matrix R); Rot3(const gtsam::Point3& col1, const gtsam::Point3& col2, const gtsam::Point3& col3); Rot3(double R11, double R12, double R13, double R21, double R22, double R23, @@ -313,7 +313,7 @@ class Rot3 { static gtsam::Rot3 Ry(double t); static gtsam::Rot3 Rz(double t); static gtsam::Rot3 RzRyRx(double x, double y, double z); - static gtsam::Rot3 RzRyRx(Vector xyz); + static gtsam::Rot3 RzRyRx(gtsam::Vector xyz); static gtsam::Rot3 Yaw( double t); // positive yaw is to right (as in aircraft heading) static gtsam::Rot3 Pitch( @@ -323,9 +323,9 @@ class Rot3 { static gtsam::Rot3 Ypr(double y, double p, double r); static gtsam::Rot3 Quaternion(double w, double x, double y, double z); static gtsam::Rot3 AxisAngle(const gtsam::Point3& axis, double angle); - static gtsam::Rot3 Rodrigues(Vector v); + static gtsam::Rot3 Rodrigues(gtsam::Vector v); static gtsam::Rot3 Rodrigues(double wx, double wy, double wz); - static gtsam::Rot3 ClosestTo(const Matrix M); + static gtsam::Rot3 ClosestTo(const gtsam::Matrix M); // Testable void print(string s = "") const; @@ -341,10 +341,10 @@ class Rot3 { gtsam::Rot3 operator*(const gtsam::Rot3& p2) const; // Manifold - // gtsam::Rot3 retractCayley(Vector v) const; // TODO, does not exist in both - // Matrix and Quaternion options - gtsam::Rot3 retract(Vector v) const; - Vector localCoordinates(const gtsam::Rot3& p) const; + // gtsam::Rot3 retractCayley(gtsam::Vector v) const; // TODO, does not exist in both + // gtsam::Matrix and Quaternion options + gtsam::Rot3 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Rot3& p) const; // Group Action on Point3 gtsam::Point3 rotate(const gtsam::Point3& p) const; @@ -358,21 +358,21 @@ class Rot3 { gtsam::Unit3 unrotate(const gtsam::Unit3& p) const; // Standard Interface - static gtsam::Rot3 Expmap(Vector v); - static Vector Logmap(const gtsam::Rot3& p); - Vector logmap(const gtsam::Rot3& p); - Matrix matrix() const; - Matrix transpose() const; + static gtsam::Rot3 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::Rot3& p); + gtsam::Vector logmap(const gtsam::Rot3& p); + gtsam::Matrix matrix() const; + gtsam::Matrix transpose() const; gtsam::Point3 column(size_t index) const; - Vector xyz() const; - Vector ypr() const; - Vector rpy() const; + gtsam::Vector xyz() const; + gtsam::Vector ypr() const; + gtsam::Vector rpy() const; double roll() const; double pitch() const; double yaw() const; pair axisAngle() const; gtsam::Quaternion toQuaternion() const; - // Vector quaternion() const; // @deprecated, see https://github.com/borglab/gtsam/pull/1219 + // gtsam::Vector quaternion() const; // @deprecated, see https://github.com/borglab/gtsam/pull/1219 gtsam::Rot3 slerp(double t, const gtsam::Rot3& other) const; // enabling serialization functionality @@ -387,7 +387,7 @@ class Pose2 { Pose2(double x, double y, double theta); Pose2(double theta, const gtsam::Point2& t); Pose2(const gtsam::Rot2& r, const gtsam::Point2& t); - Pose2(Vector v); + Pose2(gtsam::Vector v); static std::optional Align(const gtsam::Point2Pairs& abPointPairs); static std::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); @@ -408,32 +408,32 @@ class Pose2 { gtsam::Pose2 operator*(const gtsam::Pose2& p2) const; // Manifold - gtsam::Pose2 retract(Vector v) const; - gtsam::Pose2 retract(Vector v, Eigen::Ref H1, Eigen::Ref H2) const; - Vector localCoordinates(const gtsam::Pose2& p) const; - Vector localCoordinates(const gtsam::Pose2& p, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Pose2 retract(gtsam::Vector v) const; + gtsam::Pose2 retract(gtsam::Vector v, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Vector localCoordinates(const gtsam::Pose2& p) const; + gtsam::Vector localCoordinates(const gtsam::Pose2& p, Eigen::Ref H1, Eigen::Ref H2) const; // Lie Group - static gtsam::Pose2 Expmap(Vector v); - static Vector Logmap(const gtsam::Pose2& p); - Vector logmap(const gtsam::Pose2& p); - Vector logmap(const gtsam::Pose2& p, Eigen::Ref H); - static Matrix ExpmapDerivative(Vector v); - static Matrix LogmapDerivative(const gtsam::Pose2& v); - Matrix AdjointMap() const; - Vector Adjoint(Vector xi) const; - static Matrix adjointMap_(Vector v); - static Vector adjoint_(Vector xi, Vector y); - static Vector adjointTranspose(Vector xi, Vector y); - static Matrix wedge(double vx, double vy, double w); + static gtsam::Pose2 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::Pose2& p); + gtsam::Vector logmap(const gtsam::Pose2& p); + gtsam::Vector logmap(const gtsam::Pose2& p, Eigen::Ref H); + static gtsam::Matrix ExpmapDerivative(gtsam::Vector v); + static gtsam::Matrix LogmapDerivative(const gtsam::Pose2& v); + gtsam::Matrix AdjointMap() const; + gtsam::Vector Adjoint(gtsam::Vector xi) const; + static gtsam::Matrix adjointMap_(gtsam::Vector v); + static gtsam::Vector adjoint_(gtsam::Vector xi, gtsam::Vector y); + static gtsam::Vector adjointTranspose(gtsam::Vector xi, gtsam::Vector y); + static gtsam::Matrix wedge(double vx, double vy, double w); // Group Actions on Point2 gtsam::Point2 transformFrom(const gtsam::Point2& p) const; gtsam::Point2 transformTo(const gtsam::Point2& p) const; - // Matrix versions - Matrix transformFrom(const Matrix& points) const; - Matrix transformTo(const Matrix& points) const; + // gtsam::Matrix versions + gtsam::Matrix transformFrom(const gtsam::Matrix& points) const; + gtsam::Matrix transformTo(const gtsam::Matrix& points) const; // Standard Interface double x() const; @@ -445,7 +445,7 @@ class Pose2 { gtsam::Point2 translation(Eigen::Ref Hself) const; gtsam::Rot2 rotation() const; gtsam::Rot2 rotation(Eigen::Ref Hself) const; - Matrix matrix() const; + gtsam::Matrix matrix() const; // enabling serialization functionality void serialize() const; @@ -458,7 +458,7 @@ class Pose3 { Pose3(const gtsam::Pose3& other); Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); Pose3(const gtsam::Pose2& pose2); - Pose3(Matrix mat); + Pose3(gtsam::Matrix mat); static std::optional Align(const gtsam::Point3Pairs& abPointPairs); static std::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); @@ -488,33 +488,33 @@ class Pose3 { gtsam::Pose3 operator*(const gtsam::Pose3& pose) const; // Manifold - gtsam::Pose3 retract(Vector v) const; - gtsam::Pose3 retract(Vector v, Eigen::Ref Hxi) const; - Vector localCoordinates(const gtsam::Pose3& pose) const; - Vector localCoordinates(const gtsam::Pose3& pose, Eigen::Ref Hxi) const; + gtsam::Pose3 retract(gtsam::Vector v) const; + gtsam::Pose3 retract(gtsam::Vector v, Eigen::Ref Hxi) const; + gtsam::Vector localCoordinates(const gtsam::Pose3& pose) const; + gtsam::Vector localCoordinates(const gtsam::Pose3& pose, Eigen::Ref Hxi) const; // Lie Group - static gtsam::Pose3 Expmap(Vector v); - static gtsam::Pose3 Expmap(Vector v, Eigen::Ref Hxi); - static Vector Logmap(const gtsam::Pose3& pose); - static Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref Hpose); - gtsam::Pose3 expmap(Vector v); - Vector logmap(const gtsam::Pose3& pose); - Matrix AdjointMap() const; - Vector Adjoint(Vector xi) const; - Vector Adjoint(Vector xi, Eigen::Ref H_this, + static gtsam::Pose3 Expmap(gtsam::Vector v); + static gtsam::Pose3 Expmap(gtsam::Vector v, Eigen::Ref Hxi); + static gtsam::Vector Logmap(const gtsam::Pose3& pose); + static gtsam::Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref Hpose); + gtsam::Pose3 expmap(gtsam::Vector v); + gtsam::Vector logmap(const gtsam::Pose3& pose); + gtsam::Matrix AdjointMap() const; + gtsam::Vector Adjoint(gtsam::Vector xi) const; + gtsam::Vector Adjoint(gtsam::Vector xi, Eigen::Ref H_this, Eigen::Ref H_xib) const; - Vector AdjointTranspose(Vector xi) const; - Vector AdjointTranspose(Vector xi, Eigen::Ref H_this, + gtsam::Vector AdjointTranspose(gtsam::Vector xi) const; + gtsam::Vector AdjointTranspose(gtsam::Vector xi, Eigen::Ref H_this, Eigen::Ref H_x) const; - static Matrix adjointMap(Vector xi); - static Vector adjoint(Vector xi, Vector y); - static Matrix adjointMap_(Vector xi); - static Vector adjoint_(Vector xi, Vector y); - static Vector adjointTranspose(Vector xi, Vector y); - static Matrix ExpmapDerivative(Vector xi); - static Matrix LogmapDerivative(const gtsam::Pose3& xi); - static Matrix wedge(double wx, double wy, double wz, double vx, double vy, + static gtsam::Matrix adjointMap(gtsam::Vector xi); + static gtsam::Vector adjoint(gtsam::Vector xi, gtsam::Vector y); + static gtsam::Matrix adjointMap_(gtsam::Vector xi); + static gtsam::Vector adjoint_(gtsam::Vector xi, gtsam::Vector y); + static gtsam::Vector adjointTranspose(gtsam::Vector xi, gtsam::Vector y); + static gtsam::Matrix ExpmapDerivative(gtsam::Vector xi); + static gtsam::Matrix LogmapDerivative(const gtsam::Pose3& xi); + static gtsam::Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz); // Group Action on Point3 @@ -525,9 +525,9 @@ class Pose3 { gtsam::Point3 transformTo(const gtsam::Point3& point, Eigen::Ref Hself, Eigen::Ref Hpoint) const; - // Matrix versions - Matrix transformFrom(const Matrix& points) const; - Matrix transformTo(const Matrix& points) const; + // gtsam::Matrix versions + gtsam::Matrix transformFrom(const gtsam::Matrix& points) const; + gtsam::Matrix transformTo(const gtsam::Matrix& points) const; // Standard Interface gtsam::Rot3 rotation() const; @@ -537,7 +537,7 @@ class Pose3 { double x() const; double y() const; double z() const; - Matrix matrix() const; + gtsam::Matrix matrix() const; gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& pose) const; gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& pose, Eigen::Ref Hself, Eigen::Ref HaTb) const; @@ -584,9 +584,9 @@ class Unit3 { bool equals(const gtsam::Unit3& pose, double tol) const; // Other functionality - Matrix basis() const; - Matrix basis(Eigen::Ref H) const; - Matrix skew() const; + gtsam::Matrix basis() const; + gtsam::Matrix basis(Eigen::Ref H) const; + gtsam::Matrix skew() const; gtsam::Point3 point3() const; gtsam::Point3 point3(Eigen::Ref H) const; @@ -602,8 +602,8 @@ class Unit3 { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Unit3 retract(Vector v) const; - Vector localCoordinates(const gtsam::Unit3& s) const; + gtsam::Unit3 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Unit3& s) const; gtsam::Unit3 FromPoint3(const gtsam::Point3& point) const; gtsam::Unit3 FromPoint3(const gtsam::Point3& point, Eigen::Ref H) const; @@ -632,14 +632,14 @@ class EssentialMatrix { // Manifold static size_t Dim(); size_t dim() const; - gtsam::EssentialMatrix retract(Vector v) const; - Vector localCoordinates(const gtsam::EssentialMatrix& s) const; + gtsam::EssentialMatrix retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::EssentialMatrix& s) const; // Other methods: gtsam::Rot3 rotation() const; gtsam::Unit3 direction() const; - Matrix matrix() const; - double error(Vector vA, Vector vB); + gtsam::Matrix matrix() const; + double error(gtsam::Vector vA, gtsam::Vector vB); }; #include @@ -647,7 +647,7 @@ class Cal3_S2 { // Standard Constructors Cal3_S2(); Cal3_S2(double fx, double fy, double s, double u0, double v0); - Cal3_S2(Vector v); + Cal3_S2(gtsam::Vector v); Cal3_S2(double fov, int w, int h); // Testable @@ -657,8 +657,8 @@ class Cal3_S2 { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3_S2 retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3_S2& c) const; + gtsam::Cal3_S2 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3_S2& c) const; // Action on Point2 gtsam::Point2 calibrate(const gtsam::Point2& p) const; @@ -677,9 +677,9 @@ class Cal3_S2 { double px() const; double py() const; gtsam::Point2 principalPoint() const; - Vector vector() const; - Matrix K() const; - Matrix inverse() const; + gtsam::Vector vector() const; + gtsam::Matrix K() const; + gtsam::Matrix inverse() const; // enabling serialization functionality void serialize() const; @@ -701,9 +701,9 @@ virtual class Cal3DS2_Base { double py() const; double k1() const; double k2() const; - Matrix K() const; - Vector k() const; - Vector vector() const; + gtsam::Matrix K() const; + gtsam::Vector k() const; + gtsam::Vector vector() const; // Action on Point2 gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; @@ -727,7 +727,7 @@ virtual class Cal3DS2 : gtsam::Cal3DS2_Base { double k2); Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2); - Cal3DS2(Vector v); + Cal3DS2(gtsam::Vector v); // Testable bool equals(const gtsam::Cal3DS2& rhs, double tol) const; @@ -735,8 +735,8 @@ virtual class Cal3DS2 : gtsam::Cal3DS2_Base { // Manifold size_t dim() const; static size_t Dim(); - gtsam::Cal3DS2 retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3DS2& c) const; + gtsam::Cal3DS2 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3DS2& c) const; // enabling serialization functionality void serialize() const; @@ -750,7 +750,7 @@ virtual class Cal3Unified : gtsam::Cal3DS2_Base { double k2); Cal3Unified(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2, double xi); - Cal3Unified(Vector v); + Cal3Unified(gtsam::Vector v); // Testable bool equals(const gtsam::Cal3Unified& rhs, double tol) const; @@ -763,8 +763,8 @@ virtual class Cal3Unified : gtsam::Cal3DS2_Base { // Manifold size_t dim() const; static size_t Dim(); - gtsam::Cal3Unified retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3Unified& c) const; + gtsam::Cal3Unified retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3Unified& c) const; // Action on Point2 // Note: the signature of this functions differ from the functions @@ -788,7 +788,7 @@ class Cal3Fisheye { Cal3Fisheye(); Cal3Fisheye(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4, double tol = 1e-5); - Cal3Fisheye(Vector v); + Cal3Fisheye(gtsam::Vector v); // Testable void print(string s = "Cal3Fisheye") const; @@ -797,8 +797,8 @@ class Cal3Fisheye { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3Fisheye retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3Fisheye& c) const; + gtsam::Cal3Fisheye retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3Fisheye& c) const; // Action on Point2 gtsam::Point2 calibrate(const gtsam::Point2& p) const; @@ -821,10 +821,10 @@ class Cal3Fisheye { double px() const; double py() const; gtsam::Point2 principalPoint() const; - Vector vector() const; - Vector k() const; - Matrix K() const; - Matrix inverse() const; + gtsam::Vector vector() const; + gtsam::Vector k() const; + gtsam::Matrix K() const; + gtsam::Matrix inverse() const; // enabling serialization functionality void serialize() const; @@ -835,13 +835,13 @@ class Cal3_S2Stereo { // Standard Constructors Cal3_S2Stereo(); Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b); - Cal3_S2Stereo(Vector v); + Cal3_S2Stereo(gtsam::Vector v); // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3_S2Stereo retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3_S2Stereo& c) const; + gtsam::Cal3_S2Stereo retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3_S2Stereo& c) const; // Testable void print(string s = "") const; @@ -853,11 +853,11 @@ class Cal3_S2Stereo { double skew() const; double px() const; double py() const; - Matrix K() const; + gtsam::Matrix K() const; gtsam::Point2 principalPoint() const; double baseline() const; Vector6 vector() const; - Matrix inverse() const; + gtsam::Matrix inverse() const; }; #include @@ -875,8 +875,8 @@ class Cal3Bundler { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3Bundler retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3Bundler& c) const; + gtsam::Cal3Bundler retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3Bundler& c) const; // Action on Point2 gtsam::Point2 calibrate(const gtsam::Point2& p) const; @@ -895,9 +895,9 @@ class Cal3Bundler { double k2() const; double px() const; double py() const; - Vector vector() const; - Vector k() const; - Matrix K() const; + gtsam::Vector vector() const; + gtsam::Vector k() const; + gtsam::Matrix K() const; // enabling serialization functionality void serialize() const; @@ -908,7 +908,7 @@ class CalibratedCamera { // Standard Constructors and Named Constructors CalibratedCamera(); CalibratedCamera(const gtsam::Pose3& pose); - CalibratedCamera(Vector v); + CalibratedCamera(gtsam::Vector v); static gtsam::CalibratedCamera Level(const gtsam::Pose2& pose2, double height); @@ -919,8 +919,8 @@ class CalibratedCamera { // Manifold static size_t Dim(); size_t dim() const; - gtsam::CalibratedCamera retract(Vector d) const; - Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + gtsam::CalibratedCamera retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; // Action on Point3 gtsam::Point2 project(const gtsam::Point3& point) const; @@ -972,8 +972,8 @@ class PinholeCamera { CALIBRATION calibration() const; // Manifold - This retract(Vector d) const; - Vector localCoordinates(const This& T2) const; + This retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const This& T2) const; size_t dim() const; static size_t Dim(); @@ -1039,8 +1039,8 @@ class PinholePose { CALIBRATION calibration() const; // Manifold - This retract(Vector d) const; - Vector localCoordinates(const This& T2) const; + This retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const This& T2) const; size_t dim() const; static size_t Dim(); @@ -1081,8 +1081,8 @@ class Similarity2 { Similarity2(); Similarity2(double s); Similarity2(const gtsam::Rot2& R, const gtsam::Point2& t, double s); - Similarity2(const Matrix& R, const Vector& t, double s); - Similarity2(const Matrix& T); + Similarity2(const gtsam::Matrix& R, const gtsam::Vector& t, double s); + Similarity2(const gtsam::Matrix& T); gtsam::Point2 transformFrom(const gtsam::Point2& p) const; gtsam::Pose2 transformFrom(const gtsam::Pose2& T); @@ -1093,7 +1093,7 @@ class Similarity2 { // Standard Interface bool equals(const gtsam::Similarity2& sim, double tol) const; void print(const std::string& s = "") const; - Matrix matrix() const; + gtsam::Matrix matrix() const; gtsam::Rot2& rotation(); gtsam::Point2& translation(); double scale() const; @@ -1105,8 +1105,8 @@ class Similarity3 { Similarity3(); Similarity3(double s); Similarity3(const gtsam::Rot3& R, const gtsam::Point3& t, double s); - Similarity3(const Matrix& R, const Vector& t, double s); - Similarity3(const Matrix& T); + Similarity3(const gtsam::Matrix& R, const gtsam::Vector& t, double s); + Similarity3(const gtsam::Matrix& T); gtsam::Point3 transformFrom(const gtsam::Point3& p) const; gtsam::Pose3 transformFrom(const gtsam::Pose3& T); @@ -1117,7 +1117,7 @@ class Similarity3 { // Standard Interface bool equals(const gtsam::Similarity3& sim, double tol) const; void print(const std::string& s = "") const; - Matrix matrix() const; + gtsam::Matrix matrix() const; gtsam::Rot3& rotation(); gtsam::Point3& translation(); double scale() const; @@ -1148,8 +1148,8 @@ class StereoCamera { gtsam::Cal3_S2Stereo calibration() const; // Manifold - gtsam::StereoCamera retract(Vector d) const; - Vector localCoordinates(const gtsam::StereoCamera& T2) const; + gtsam::StereoCamera retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const gtsam::StereoCamera& T2) const; size_t dim() const; static size_t Dim(); diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 6d77e8eda0..c5504bb07a 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -161,31 +161,31 @@ class FactorIndices { namespace utilities { #include -gtsam::KeyList createKeyList(Vector I); -gtsam::KeyList createKeyList(string s, Vector I); -gtsam::KeyVector createKeyVector(Vector I); -gtsam::KeyVector createKeyVector(string s, Vector I); -gtsam::KeySet createKeySet(Vector I); -gtsam::KeySet createKeySet(string s, Vector I); -Matrix extractPoint2(const gtsam::Values& values); -Matrix extractPoint3(const gtsam::Values& values); +gtsam::KeyList createKeyList(gtsam::Vector I); +gtsam::KeyList createKeyList(string s, gtsam::Vector I); +gtsam::KeyVector createKeyVector(gtsam::Vector I); +gtsam::KeyVector createKeyVector(string s, gtsam::Vector I); +gtsam::KeySet createKeySet(gtsam::Vector I); +gtsam::KeySet createKeySet(string s, gtsam::Vector I); +gtsam::Matrix extractPoint2(const gtsam::Values& values); +gtsam::Matrix extractPoint3(const gtsam::Values& values); gtsam::Values allPose2s(gtsam::Values& values); -Matrix extractPose2(const gtsam::Values& values); +gtsam::Matrix extractPose2(const gtsam::Values& values); gtsam::Values allPose3s(gtsam::Values& values); -Matrix extractPose3(const gtsam::Values& values); -Matrix extractVectors(const gtsam::Values& values, char c); +gtsam::Matrix extractPose3(const gtsam::Values& values); +gtsam::Matrix extractVectors(const gtsam::Values& values, char c); void perturbPoint2(gtsam::Values& values, double sigma, int seed = 42u); void perturbPose2(gtsam::Values& values, double sigmaT, double sigmaR, int seed = 42u); void perturbPoint3(gtsam::Values& values, double sigma, int seed = 42u); void insertBackprojections(gtsam::Values& values, const gtsam::PinholeCamera& c, - Vector J, Matrix Z, double depth); + gtsam::Vector J, gtsam::Matrix Z, double depth); void insertProjectionFactors( - gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, + gtsam::NonlinearFactorGraph& graph, size_t i, gtsam::Vector J, gtsam::Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K, const gtsam::Pose3& body_P_sensor = gtsam::Pose3()); -Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, +gtsam::Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values); gtsam::Values localToWorld(const gtsam::Values& local, const gtsam::Pose2& base); diff --git a/gtsam/linear/linear.i b/gtsam/linear/linear.i index 2bf55bba10..4b0963b8db 100644 --- a/gtsam/linear/linear.i +++ b/gtsam/linear/linear.i @@ -12,52 +12,52 @@ virtual class Base { // bool isConstrained() const; // bool isUnit() const; // size_t dim() const; - // Vector sigmas() const; + // gtsam::Vector sigmas() const; }; virtual class Gaussian : gtsam::noiseModel::Base { - static gtsam::noiseModel::Gaussian* Information(Matrix R, bool smart = true); - static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R, bool smart = true); - static gtsam::noiseModel::Gaussian* Covariance(Matrix R, bool smart = true); + static gtsam::noiseModel::Gaussian* Information(gtsam::Matrix R, bool smart = true); + static gtsam::noiseModel::Gaussian* SqrtInformation(gtsam::Matrix R, bool smart = true); + static gtsam::noiseModel::Gaussian* Covariance(gtsam::Matrix R, bool smart = true); bool equals(gtsam::noiseModel::Base& expected, double tol); // access to noise model - Matrix R() const; - Matrix information() const; - Matrix covariance() const; + gtsam::Matrix R() const; + gtsam::Matrix information() const; + gtsam::Matrix covariance() const; // Whitening operations - Vector whiten(Vector v) const; - Vector unwhiten(Vector v) const; - Matrix Whiten(Matrix H) const; + gtsam::Vector whiten(gtsam::Vector v) const; + gtsam::Vector unwhiten(gtsam::Vector v) const; + gtsam::Matrix Whiten(gtsam::Matrix H) const; // enabling serialization functionality void serializable() const; }; virtual class Diagonal : gtsam::noiseModel::Gaussian { - static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas, bool smart = true); - static gtsam::noiseModel::Diagonal* Variances(Vector variances, bool smart = true); - static gtsam::noiseModel::Diagonal* Precisions(Vector precisions, bool smart = true); - Matrix R() const; + static gtsam::noiseModel::Diagonal* Sigmas(gtsam::Vector sigmas, bool smart = true); + static gtsam::noiseModel::Diagonal* Variances(gtsam::Vector variances, bool smart = true); + static gtsam::noiseModel::Diagonal* Precisions(gtsam::Vector precisions, bool smart = true); + gtsam::Matrix R() const; // access to noise model - Vector sigmas() const; - Vector invsigmas() const; - Vector precisions() const; + gtsam::Vector sigmas() const; + gtsam::Vector invsigmas() const; + gtsam::Vector precisions() const; // enabling serialization functionality void serializable() const; }; virtual class Constrained : gtsam::noiseModel::Diagonal { - static gtsam::noiseModel::Constrained* MixedSigmas(Vector mu, Vector sigmas); - static gtsam::noiseModel::Constrained* MixedSigmas(double m, Vector sigmas); - static gtsam::noiseModel::Constrained* MixedVariances(Vector mu, Vector variances); - static gtsam::noiseModel::Constrained* MixedVariances(Vector variances); - static gtsam::noiseModel::Constrained* MixedPrecisions(Vector mu, Vector precisions); - static gtsam::noiseModel::Constrained* MixedPrecisions(Vector precisions); + static gtsam::noiseModel::Constrained* MixedSigmas(gtsam::Vector mu, gtsam::Vector sigmas); + static gtsam::noiseModel::Constrained* MixedSigmas(double m, gtsam::Vector sigmas); + static gtsam::noiseModel::Constrained* MixedVariances(gtsam::Vector mu, gtsam::Vector variances); + static gtsam::noiseModel::Constrained* MixedVariances(gtsam::Vector variances); + static gtsam::noiseModel::Constrained* MixedPrecisions(gtsam::Vector mu, gtsam::Vector precisions); + static gtsam::noiseModel::Constrained* MixedPrecisions(gtsam::Vector precisions); static gtsam::noiseModel::Constrained* All(size_t dim); static gtsam::noiseModel::Constrained* All(size_t dim, double mu); @@ -257,13 +257,13 @@ virtual class Robust : gtsam::noiseModel::Base { class Sampler { // Constructors Sampler(gtsam::noiseModel::Diagonal* model, int seed); - Sampler(Vector sigmas, int seed); + Sampler(gtsam::Vector sigmas, int seed); // Standard Interface size_t dim() const; - Vector sigmas() const; + gtsam::Vector sigmas() const; gtsam::noiseModel::Diagonal* model() const; - Vector sample(); + gtsam::Vector sample(); }; #include @@ -284,10 +284,10 @@ class VectorValues { const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::VectorValues& expected, double tol) const; - void insert(size_t j, Vector value); - Vector vector() const; - Vector vector(const gtsam::KeyVector& keys) const; - Vector at(size_t j) const; + void insert(size_t j, gtsam::Vector value); + gtsam::Vector vector() const; + gtsam::Vector vector(const gtsam::KeyVector& keys) const; + gtsam::Vector at(size_t j) const; void insert(const gtsam::VectorValues& values); void update(const gtsam::VectorValues& values); @@ -318,23 +318,23 @@ virtual class GaussianFactor : gtsam::Factor { double error(const gtsam::VectorValues& c) const; gtsam::GaussianFactor* clone() const; gtsam::GaussianFactor* negate() const; - Matrix augmentedInformation() const; - Matrix information() const; - Matrix augmentedJacobian() const; - pair jacobian() const; + gtsam::Matrix augmentedInformation() const; + gtsam::Matrix information() const; + gtsam::Matrix augmentedJacobian() const; + pair jacobian() const; }; #include virtual class JacobianFactor : gtsam::GaussianFactor { //Constructors JacobianFactor(); - JacobianFactor(Vector b_in); - JacobianFactor(size_t i1, Matrix A1, Vector b, + JacobianFactor(gtsam::Vector b_in); + JacobianFactor(size_t i1, gtsam::Matrix A1, gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); - JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, Vector b, + JacobianFactor(size_t i1, gtsam::Matrix A1, size_t i2, gtsam::Matrix A2, gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); - JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3, - Vector b, const gtsam::noiseModel::Diagonal* model); + JacobianFactor(size_t i1, gtsam::Matrix A1, size_t i2, gtsam::Matrix A2, size_t i3, gtsam::Matrix A3, + gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); JacobianFactor(const gtsam::GaussianFactorGraph& graph); JacobianFactor(const gtsam::GaussianFactorGraph& graph, const gtsam::VariableSlots& p_variableSlots); @@ -349,25 +349,25 @@ virtual class JacobianFactor : gtsam::GaussianFactor { void print(string s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::GaussianFactor& lf, double tol) const; - Vector unweighted_error(const gtsam::VectorValues& c) const; - Vector error_vector(const gtsam::VectorValues& c) const; + gtsam::Vector unweighted_error(const gtsam::VectorValues& c) const; + gtsam::Vector error_vector(const gtsam::VectorValues& c) const; double error(const gtsam::VectorValues& c) const; //Standard Interface - Matrix getA() const; - Vector getb() const; + gtsam::Matrix getA() const; + gtsam::Vector getb() const; size_t rows() const; size_t cols() const; bool isConstrained() const; - pair jacobianUnweighted() const; - Matrix augmentedJacobianUnweighted() const; + pair jacobianUnweighted() const; + gtsam::Matrix augmentedJacobianUnweighted() const; - void transposeMultiplyAdd(double alpha, Vector e, gtsam::VectorValues& x) const; + void transposeMultiplyAdd(double alpha, gtsam::Vector e, gtsam::VectorValues& x) const; gtsam::JacobianFactor whiten() const; pair eliminate(const gtsam::Ordering& keys) const; - void setModel(bool anyConstrained, Vector sigmas); + void setModel(bool anyConstrained, gtsam::Vector sigmas); gtsam::noiseModel::Diagonal* get_model() const; @@ -382,12 +382,12 @@ virtual class HessianFactor : gtsam::GaussianFactor { //Constructors HessianFactor(); HessianFactor(const gtsam::GaussianFactor& factor); - HessianFactor(size_t j, Matrix G, Vector g, double f); - HessianFactor(size_t j, Vector mu, Matrix Sigma); - HessianFactor(size_t j1, size_t j2, Matrix G11, Matrix G12, Vector g1, Matrix G22, - Vector g2, double f); - HessianFactor(size_t j1, size_t j2, size_t j3, Matrix G11, Matrix G12, Matrix G13, - Vector g1, Matrix G22, Matrix G23, Vector g2, Matrix G33, Vector g3, + HessianFactor(size_t j, gtsam::Matrix G, gtsam::Vector g, double f); + HessianFactor(size_t j, gtsam::Vector mu, gtsam::Matrix Sigma); + HessianFactor(size_t j1, size_t j2, gtsam::Matrix G11, gtsam::Matrix G12, gtsam::Vector g1, gtsam::Matrix G22, + gtsam::Vector g2, double f); + HessianFactor(size_t j1, size_t j2, size_t j3, gtsam::Matrix G11, gtsam::Matrix G12, gtsam::Matrix G13, + gtsam::Vector g1, gtsam::Matrix G22, gtsam::Matrix G23, gtsam::Vector g2, gtsam::Matrix G33, gtsam::Vector g3, double f); HessianFactor(const gtsam::GaussianFactorGraph& factors); @@ -399,9 +399,9 @@ virtual class HessianFactor : gtsam::GaussianFactor { //Standard Interface size_t rows() const; - Matrix information() const; + gtsam::Matrix information() const; double constantTerm() const; - Vector linearTerm() const; + gtsam::Vector linearTerm() const; // enabling serialization functionality void serialize() const; @@ -430,12 +430,12 @@ class GaussianFactorGraph { void push_back(const gtsam::GaussianBayesNet& bayesNet); void push_back(const gtsam::GaussianBayesTree& bayesTree); void add(const gtsam::GaussianFactor& factor); - void add(Vector b); - void add(size_t key1, Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); - void add(size_t key1, Matrix A1, size_t key2, Matrix A2, Vector b, + void add(gtsam::Vector b); + void add(size_t key1, gtsam::Matrix A1, gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, gtsam::Matrix A1, size_t key2, gtsam::Matrix A2, gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); - void add(size_t key1, Matrix A1, size_t key2, Matrix A2, size_t key3, Matrix A3, - Vector b, const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, gtsam::Matrix A1, size_t key2, gtsam::Matrix A2, size_t key3, gtsam::Matrix A3, + gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); // error and probability double error(const gtsam::VectorValues& c) const; @@ -477,15 +477,15 @@ class GaussianFactorGraph { gtsam::GaussianFactorGraph* marginal(const gtsam::KeyVector& key_vector); // Conversion to matrices - Matrix sparseJacobian_() const; - Matrix augmentedJacobian() const; - Matrix augmentedJacobian(const gtsam::Ordering& ordering) const; - pair jacobian() const; - pair jacobian(const gtsam::Ordering& ordering) const; - Matrix augmentedHessian() const; - Matrix augmentedHessian(const gtsam::Ordering& ordering) const; - pair hessian() const; - pair hessian(const gtsam::Ordering& ordering) const; + gtsam::Matrix sparseJacobian_() const; + gtsam::Matrix augmentedJacobian() const; + gtsam::Matrix augmentedJacobian(const gtsam::Ordering& ordering) const; + pair jacobian() const; + pair jacobian(const gtsam::Ordering& ordering) const; + gtsam::Matrix augmentedHessian() const; + gtsam::Matrix augmentedHessian(const gtsam::Ordering& ordering) const; + pair hessian() const; + pair hessian(const gtsam::Ordering& ordering) const; string dot( const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter, @@ -503,37 +503,37 @@ class GaussianFactorGraph { #include virtual class GaussianConditional : gtsam::JacobianFactor { // Constructors - GaussianConditional(size_t key, Vector d, Matrix R, + GaussianConditional(size_t key, gtsam::Vector d, gtsam::Matrix R, const gtsam::noiseModel::Diagonal* sigmas); - GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + GaussianConditional(size_t key, gtsam::Vector d, gtsam::Matrix R, size_t name1, gtsam::Matrix S, const gtsam::noiseModel::Diagonal* sigmas); - GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, - size_t name2, Matrix T, + GaussianConditional(size_t key, gtsam::Vector d, gtsam::Matrix R, size_t name1, gtsam::Matrix S, + size_t name2, gtsam::Matrix T, const gtsam::noiseModel::Diagonal* sigmas); // Constructors with no noise model - GaussianConditional(size_t key, Vector d, Matrix R); - GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S); - GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, - size_t name2, Matrix T); + GaussianConditional(size_t key, gtsam::Vector d, gtsam::Matrix R); + GaussianConditional(size_t key, gtsam::Vector d, gtsam::Matrix R, size_t name1, gtsam::Matrix S); + GaussianConditional(size_t key, gtsam::Vector d, gtsam::Matrix R, size_t name1, gtsam::Matrix S, + size_t name2, gtsam::Matrix T); // Named constructors static gtsam::GaussianConditional FromMeanAndStddev(gtsam::Key key, - const Vector& mu, + const gtsam::Vector& mu, double sigma); static gtsam::GaussianConditional FromMeanAndStddev(gtsam::Key key, - const Matrix& A, + const gtsam::Matrix& A, gtsam::Key parent, - const Vector& b, + const gtsam::Vector& b, double sigma); static gtsam::GaussianConditional FromMeanAndStddev(gtsam::Key key, - const Matrix& A1, + const gtsam::Matrix& A1, gtsam::Key parent1, - const Matrix& A2, + const gtsam::Matrix& A2, gtsam::Key parent2, - const Vector& b, + const gtsam::Vector& b, double sigma); // Testable void print(string s = "GaussianConditional", @@ -550,7 +550,7 @@ virtual class GaussianConditional : gtsam::JacobianFactor { gtsam::VectorValues solve(const gtsam::VectorValues& parents) const; gtsam::JacobianFactor* likelihood( const gtsam::VectorValues& frontalValues) const; - gtsam::JacobianFactor* likelihood(Vector frontal) const; + gtsam::JacobianFactor* likelihood(gtsam::Vector frontal) const; gtsam::VectorValues sample(const gtsam::VectorValues& parents) const; gtsam::VectorValues sample() const; @@ -558,9 +558,9 @@ virtual class GaussianConditional : gtsam::JacobianFactor { gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents, const gtsam::VectorValues& rhs) const; void solveTransposeInPlace(gtsam::VectorValues& gy) const; - Matrix R() const; - Matrix S() const; - Vector d() const; + gtsam::Matrix R() const; + gtsam::Matrix S() const; + gtsam::Vector d() const; // enabling serialization functionality void serialize() const; @@ -574,11 +574,11 @@ virtual class GaussianConditional : gtsam::JacobianFactor { #include virtual class GaussianDensity : gtsam::GaussianConditional { // Constructors - GaussianDensity(gtsam::Key key, Vector d, Matrix R, + GaussianDensity(gtsam::Key key, gtsam::Vector d, gtsam::Matrix R, const gtsam::noiseModel::Diagonal* sigmas); static gtsam::GaussianDensity FromMeanAndStddev(gtsam::Key key, - const Vector& mean, + const gtsam::Vector& mean, double sigma); // Testable @@ -588,8 +588,8 @@ virtual class GaussianDensity : gtsam::GaussianConditional { bool equals(const gtsam::GaussianDensity& cg, double tol) const; // Standard Interface - Vector mean() const; - Matrix covariance() const; + gtsam::Vector mean() const; + gtsam::Matrix covariance() const; }; #include @@ -632,7 +632,7 @@ virtual class GaussianBayesNet { void saveGraph(const string& s) const; - std::pair matrix() const; + std::pair matrix() const; gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; gtsam::VectorValues gradientAtZero() const; double error(const gtsam::VectorValues& x) const; @@ -673,7 +673,7 @@ virtual class GaussianBayesTree { double error(const gtsam::VectorValues& x) const; double determinant() const; double logDeterminant() const; - Matrix marginalCovariance(size_t key) const; + gtsam::Matrix marginalCovariance(size_t key) const; gtsam::GaussianConditional* marginalFactor(size_t key) const; gtsam::GaussianFactorGraph* joint(size_t key1, size_t key2) const; gtsam::GaussianBayesNet* jointBayesNet(size_t key1, size_t key2) const; @@ -751,20 +751,20 @@ virtual class SubgraphSolver { #include class KalmanFilter { KalmanFilter(size_t n); - // gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0); - gtsam::GaussianDensity* init(Vector x0, Matrix P0); + // gtsam::GaussianDensity* init(gtsam::Vector x0, const gtsam::SharedDiagonal& P0); + gtsam::GaussianDensity* init(gtsam::Vector x0, gtsam::Matrix P0); void print(string s = "") const; static size_t step(gtsam::GaussianDensity* p); - gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F, - Matrix B, Vector u, const gtsam::noiseModel::Diagonal* modelQ); - gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, Matrix F, - Matrix B, Vector u, Matrix Q); - gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, Matrix A0, - Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); - gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H, - Vector z, const gtsam::noiseModel::Diagonal* model); - gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H, - Vector z, Matrix Q); + gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, gtsam::Matrix F, + gtsam::Matrix B, gtsam::Vector u, const gtsam::noiseModel::Diagonal* modelQ); + gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, gtsam::Matrix F, + gtsam::Matrix B, gtsam::Vector u, gtsam::Matrix Q); + gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, gtsam::Matrix A0, + gtsam::Matrix A1, gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); + gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, gtsam::Matrix H, + gtsam::Vector z, const gtsam::noiseModel::Diagonal* model); + gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, gtsam::Matrix H, + gtsam::Vector z, gtsam::Matrix Q); }; } \ No newline at end of file diff --git a/gtsam/navigation/navigation.i b/gtsam/navigation/navigation.i index aad6f98514..db47baa750 100644 --- a/gtsam/navigation/navigation.i +++ b/gtsam/navigation/navigation.i @@ -10,7 +10,7 @@ namespace imuBias { class ConstantBias { // Constructors ConstantBias(); - ConstantBias(Vector biasAcc, Vector biasGyro); + ConstantBias(gtsam::Vector biasAcc, gtsam::Vector biasGyro); // Testable void print(string s = "") const; @@ -25,11 +25,11 @@ class ConstantBias { gtsam::imuBias::ConstantBias operator-(const gtsam::imuBias::ConstantBias& b) const; // Standard Interface - Vector vector() const; - Vector accelerometer() const; - Vector gyroscope() const; - Vector correctAccelerometer(Vector measurement) const; - Vector correctGyroscope(Vector measurement) const; + gtsam::Vector vector() const; + gtsam::Vector accelerometer() const; + gtsam::Vector gyroscope() const; + gtsam::Vector correctAccelerometer(gtsam::Vector measurement) const; + gtsam::Vector correctGyroscope(gtsam::Vector measurement) const; // enabling serialization functionality void serialize() const; @@ -41,8 +41,8 @@ class ConstantBias { class NavState { // Constructors NavState(); - NavState(const gtsam::Rot3& R, const gtsam::Point3& t, Vector v); - NavState(const gtsam::Pose3& pose, Vector v); + NavState(const gtsam::Rot3& R, const gtsam::Point3& t, gtsam::Vector v); + NavState(const gtsam::Pose3& pose, gtsam::Vector v); // Testable void print(string s = "") const; @@ -51,11 +51,11 @@ class NavState { // Access gtsam::Rot3 attitude() const; gtsam::Point3 position() const; - Vector velocity() const; + gtsam::Vector velocity() const; gtsam::Pose3 pose() const; - gtsam::NavState retract(const Vector& x) const; - Vector localCoordinates(const gtsam::NavState& g) const; + gtsam::NavState retract(const gtsam::Vector& x) const; + gtsam::Vector localCoordinates(const gtsam::NavState& g) const; // enabling serialization functionality void serialize() const; @@ -69,19 +69,19 @@ virtual class PreintegratedRotationParams { void print(string s = "") const; bool equals(const gtsam::PreintegratedRotationParams& expected, double tol); - void setGyroscopeCovariance(Matrix cov); - void setOmegaCoriolis(Vector omega); + void setGyroscopeCovariance(gtsam::Matrix cov); + void setOmegaCoriolis(gtsam::Vector omega); void setBodyPSensor(const gtsam::Pose3& pose); - Matrix getGyroscopeCovariance() const; + gtsam::Matrix getGyroscopeCovariance() const; - std::optional getOmegaCoriolis() const; + std::optional getOmegaCoriolis() const; std::optional getBodyPSensor() const; }; #include virtual class PreintegrationParams : gtsam::PreintegratedRotationParams { - PreintegrationParams(Vector n_gravity); + PreintegrationParams(gtsam::Vector n_gravity); gtsam::Vector n_gravity; @@ -94,12 +94,12 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams { void print(string s = "") const; bool equals(const gtsam::PreintegrationParams& expected, double tol); - void setAccelerometerCovariance(Matrix cov); - void setIntegrationCovariance(Matrix cov); + void setAccelerometerCovariance(gtsam::Matrix cov); + void setIntegrationCovariance(gtsam::Matrix cov); void setUse2ndOrderCoriolis(bool flag); - Matrix getAccelerometerCovariance() const; - Matrix getIntegrationCovariance() const; + gtsam::Matrix getAccelerometerCovariance() const; + gtsam::Matrix getIntegrationCovariance() const; bool getUse2ndOrderCoriolis() const; // enabling serialization functionality @@ -118,19 +118,19 @@ class PreintegratedImuMeasurements { bool equals(const gtsam::PreintegratedImuMeasurements& expected, double tol); // Standard Interface - void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, + void integrateMeasurement(gtsam::Vector measuredAcc, gtsam::Vector measuredOmega, double deltaT); void resetIntegration(); void resetIntegrationAndSetBias(const gtsam::imuBias::ConstantBias& biasHat); - Matrix preintMeasCov() const; - Vector preintegrated() const; + gtsam::Matrix preintMeasCov() const; + gtsam::Vector preintegrated() const; double deltaTij() const; gtsam::Rot3 deltaRij() const; - Vector deltaPij() const; - Vector deltaVij() const; + gtsam::Vector deltaPij() const; + gtsam::Vector deltaVij() const; gtsam::imuBias::ConstantBias biasHat() const; - Vector biasHatVector() const; + gtsam::Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; @@ -145,14 +145,14 @@ virtual class ImuFactor: gtsam::NonlinearFactor { // Standard Interface gtsam::PreintegratedImuMeasurements preintegratedMeasurements() const; - Vector evaluateError(const gtsam::Pose3& pose_i, Vector vel_i, - const gtsam::Pose3& pose_j, Vector vel_j, + gtsam::Vector evaluateError(const gtsam::Pose3& pose_i, gtsam::Vector vel_i, + const gtsam::Pose3& pose_j, gtsam::Vector vel_j, const gtsam::imuBias::ConstantBias& bias); }; #include virtual class PreintegrationCombinedParams : gtsam::PreintegrationParams { - PreintegrationCombinedParams(Vector n_gravity); + PreintegrationCombinedParams(gtsam::Vector n_gravity); static gtsam::PreintegrationCombinedParams* MakeSharedD(double g); static gtsam::PreintegrationCombinedParams* MakeSharedU(double g); @@ -163,13 +163,13 @@ virtual class PreintegrationCombinedParams : gtsam::PreintegrationParams { void print(string s = "") const; bool equals(const gtsam::PreintegrationCombinedParams& expected, double tol); - void setBiasAccCovariance(Matrix cov); - void setBiasOmegaCovariance(Matrix cov); - void setBiasAccOmegaInit(Matrix cov); + void setBiasAccCovariance(gtsam::Matrix cov); + void setBiasOmegaCovariance(gtsam::Matrix cov); + void setBiasAccOmegaInit(gtsam::Matrix cov); - Matrix getBiasAccCovariance() const ; - Matrix getBiasOmegaCovariance() const ; - Matrix getBiasAccOmegaInit() const; + gtsam::Matrix getBiasAccCovariance() const ; + gtsam::Matrix getBiasOmegaCovariance() const ; + gtsam::Matrix getBiasAccOmegaInit() const; }; @@ -184,18 +184,18 @@ class PreintegratedCombinedMeasurements { double tol); // Standard Interface - void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, + void integrateMeasurement(gtsam::Vector measuredAcc, gtsam::Vector measuredOmega, double deltaT); void resetIntegration(); void resetIntegrationAndSetBias(const gtsam::imuBias::ConstantBias& biasHat); - Matrix preintMeasCov() const; + gtsam::Matrix preintMeasCov() const; double deltaTij() const; gtsam::Rot3 deltaRij() const; - Vector deltaPij() const; - Vector deltaVij() const; + gtsam::Vector deltaPij() const; + gtsam::Vector deltaVij() const; gtsam::imuBias::ConstantBias biasHat() const; - Vector biasHatVector() const; + gtsam::Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; }; @@ -207,8 +207,8 @@ virtual class CombinedImuFactor: gtsam::NoiseModelFactor { // Standard Interface gtsam::PreintegratedCombinedMeasurements preintegratedMeasurements() const; - Vector evaluateError(const gtsam::Pose3& pose_i, Vector vel_i, - const gtsam::Pose3& pose_j, Vector vel_j, + gtsam::Vector evaluateError(const gtsam::Pose3& pose_i, gtsam::Vector vel_i, + const gtsam::Pose3& pose_j, gtsam::Vector vel_j, const gtsam::imuBias::ConstantBias& bias_i, const gtsam::imuBias::ConstantBias& bias_j); }; @@ -217,12 +217,12 @@ virtual class CombinedImuFactor: gtsam::NoiseModelFactor { class PreintegratedAhrsMeasurements { // Standard Constructor PreintegratedAhrsMeasurements(const gtsam::PreintegrationParams* params, - const Vector& biasHat); + const gtsam::Vector& biasHat); PreintegratedAhrsMeasurements(const gtsam::PreintegrationParams* p, - const Vector& bias_hat, double deltaTij, + const gtsam::Vector& bias_hat, double deltaTij, const gtsam::Rot3& deltaRij, - const Matrix& delRdelBiasOmega, - const Matrix& preint_meas_cov); + const gtsam::Matrix& delRdelBiasOmega, + const gtsam::Matrix& preint_meas_cov); PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs); // Testable @@ -232,27 +232,27 @@ class PreintegratedAhrsMeasurements { // get Data gtsam::Rot3 deltaRij() const; double deltaTij() const; - Vector biasHat() const; + gtsam::Vector biasHat() const; // Standard Interface - void integrateMeasurement(Vector measuredOmega, double deltaT); + void integrateMeasurement(gtsam::Vector measuredOmega, double deltaT); void resetIntegration() ; }; virtual class AHRSFactor : gtsam::NonlinearFactor { AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, - const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis); + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis); AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, - const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis, const gtsam::Pose3& body_P_sensor); // Standard Interface gtsam::PreintegratedAhrsMeasurements preintegratedMeasurements() const; - Vector evaluateError(const gtsam::Rot3& rot_i, const gtsam::Rot3& rot_j, - Vector bias) const; - gtsam::Rot3 predict(const gtsam::Rot3& rot_i, Vector bias, + gtsam::Vector evaluateError(const gtsam::Rot3& rot_i, const gtsam::Rot3& rot_j, + gtsam::Vector bias) const; + gtsam::Rot3 predict(const gtsam::Rot3& rot_i, gtsam::Vector bias, const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, - Vector omegaCoriolis) const; + gtsam::Vector omegaCoriolis) const; }; #include @@ -333,25 +333,25 @@ virtual class BarometricFactor : gtsam::NonlinearFactor { #include virtual class Scenario { gtsam::Pose3 pose(double t) const; - Vector omega_b(double t) const; - Vector velocity_n(double t) const; - Vector acceleration_n(double t) const; + gtsam::Vector omega_b(double t) const; + gtsam::Vector velocity_n(double t) const; + gtsam::Vector acceleration_n(double t) const; gtsam::Rot3 rotation(double t) const; gtsam::NavState navState(double t) const; - Vector velocity_b(double t) const; - Vector acceleration_b(double t) const; + gtsam::Vector velocity_b(double t) const; + gtsam::Vector acceleration_b(double t) const; }; virtual class ConstantTwistScenario : gtsam::Scenario { - ConstantTwistScenario(Vector w, Vector v); - ConstantTwistScenario(Vector w, Vector v, + ConstantTwistScenario(gtsam::Vector w, gtsam::Vector v); + ConstantTwistScenario(gtsam::Vector w, gtsam::Vector v, const gtsam::Pose3& nTb0); }; virtual class AcceleratingScenario : gtsam::Scenario { AcceleratingScenario(const gtsam::Rot3& nRb, const gtsam::Point3& p0, - Vector v0, Vector a_n, - Vector omega_b); + gtsam::Vector v0, gtsam::Vector a_n, + gtsam::Vector omega_b); }; #include @@ -360,11 +360,11 @@ class ScenarioRunner { const gtsam::PreintegrationParams* p, double imuSampleTime, const gtsam::imuBias::ConstantBias& bias); - Vector gravity_n() const; - Vector actualAngularVelocity(double t) const; - Vector actualSpecificForce(double t) const; - Vector measuredAngularVelocity(double t) const; - Vector measuredSpecificForce(double t) const; + gtsam::Vector gravity_n() const; + gtsam::Vector actualAngularVelocity(double t) const; + gtsam::Vector actualSpecificForce(double t) const; + gtsam::Vector measuredAngularVelocity(double t) const; + gtsam::Vector measuredSpecificForce(double t) const; double imuSampleTime() const; gtsam::PreintegratedImuMeasurements integrate( double T, const gtsam::imuBias::ConstantBias& estimatedBias, @@ -372,10 +372,10 @@ class ScenarioRunner { gtsam::NavState predict( const gtsam::PreintegratedImuMeasurements& pim, const gtsam::imuBias::ConstantBias& estimatedBias) const; - Matrix estimateCovariance( + gtsam::Matrix estimateCovariance( double T, size_t N, const gtsam::imuBias::ConstantBias& estimatedBias) const; - Matrix estimateNoiseCovariance(size_t N) const; + gtsam::Matrix estimateNoiseCovariance(size_t N) const; }; } diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index c39cfd22a8..9084a50fa7 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -63,7 +63,7 @@ class NonlinearFactorGraph { gtsam::KeyVector keyVector() const; template @@ -146,8 +146,8 @@ class Marginals { void print(string s = "Marginals: ", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; - Matrix marginalCovariance(size_t variable) const; - Matrix marginalInformation(size_t variable) const; + gtsam::Matrix marginalCovariance(size_t variable) const; + gtsam::Matrix marginalInformation(size_t variable) const; gtsam::JointMarginal jointMarginalCovariance( const gtsam::KeyVector& variables) const; gtsam::JointMarginal jointMarginalInformation( @@ -155,8 +155,8 @@ class Marginals { }; class JointMarginal { - Matrix at(size_t iVariable, size_t jVariable) const; - Matrix fullMatrix() const; + gtsam::Matrix at(size_t iVariable, size_t jVariable) const; + gtsam::Matrix fullMatrix() const; void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter) const; }; @@ -368,10 +368,10 @@ virtual class GncOptimizer { const gtsam::Values& initialValues, const PARAMS& params); void setInlierCostThresholds(const double inth); - const Vector& getInlierCostThresholds(); + const gtsam::Vector& getInlierCostThresholds(); void setInlierCostThresholdsAtProbability(const double alpha); - void setWeights(const Vector w); - const Vector& getWeights(); + void setWeights(const gtsam::Vector w); + const gtsam::Vector& getWeights(); gtsam::Values optimize(); }; @@ -417,7 +417,7 @@ class ISAM2DoglegParams { }; class ISAM2ThresholdMapValue { - ISAM2ThresholdMapValue(char c, Vector thresholds); + ISAM2ThresholdMapValue(char c, gtsam::Vector thresholds); ISAM2ThresholdMapValue(const gtsam::ISAM2ThresholdMapValue& other); }; @@ -467,7 +467,7 @@ class ISAM2Clique { ISAM2Clique(); // Standard Interface - Vector gradientContribution() const; + gtsam::Vector gradientContribution() const; void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter); }; @@ -535,9 +535,9 @@ class ISAM2 { gtsam::PinholeCamera, gtsam::PinholeCamera, gtsam::PinholeCamera, - gtsam::PinholeCamera, Vector, Matrix}> + gtsam::PinholeCamera, gtsam::Vector, gtsam::Matrix}> VALUE calculateEstimate(size_t key) const; - Matrix marginalCovariance(size_t key) const; + gtsam::Matrix marginalCovariance(size_t key) const; gtsam::Values calculateBestEstimate() const; gtsam::VectorValues getDelta() const; double error(const gtsam::VectorValues& x) const; @@ -564,7 +564,7 @@ class NonlinearISAM { void printStats() const; void saveGraph(string s) const; gtsam::Values estimate() const; - Matrix marginalCovariance(size_t key) const; + gtsam::Matrix marginalCovariance(size_t key) const; int reorderInterval() const; int reorderCounter() const; void update(const gtsam::NonlinearFactorGraph& newFactors, @@ -583,7 +583,7 @@ class NonlinearISAM { //************************************************************************* #include template + gtsam::Vector, gtsam::Matrix}> VALUE calculateEstimate(size_t key) const; }; diff --git a/gtsam/nonlinear/values.i b/gtsam/nonlinear/values.i index 1b0322699d..3582a3249f 100644 --- a/gtsam/nonlinear/values.i +++ b/gtsam/nonlinear/values.i @@ -66,10 +66,10 @@ class Values { // void update(size_t j, const gtsam::Value& val); // gtsam::Value at(size_t j) const; - // The order is important: Vector has to precede Point2/Point3 so `atVector` + // The order is important: gtsam::Vector has to precede Point2/Point3 so `atVector` // can work for those fixed-size vectors. - void insert(size_t j, Vector vector); - void insert(size_t j, Matrix matrix); + void insert(size_t j, gtsam::Vector vector); + void insert(size_t j, gtsam::Matrix matrix); void insert(size_t j, const gtsam::Point2& point2); void insert(size_t j, const gtsam::Point3& point3); void insert(size_t j, const gtsam::Rot2& rot2); @@ -101,10 +101,10 @@ class Values { template void insert(size_t j, const T& val); - // The order is important: Vector has to precede Point2/Point3 so `atVector` + // The order is important: gtsam::Vector has to precede Point2/Point3 so `atVector` // can work for those fixed-size vectors. - void update(size_t j, Vector vector); - void update(size_t j, Matrix matrix); + void update(size_t j, gtsam::Vector vector); + void update(size_t j, gtsam::Matrix matrix); void update(size_t j, const gtsam::Point2& point2); void update(size_t j, const gtsam::Point3& point3); void update(size_t j, const gtsam::Rot2& rot2); @@ -133,10 +133,10 @@ class Values { void update(size_t j, const gtsam::NavState& nav_state); void update(size_t j, double c); - // The order is important: Vector has to precede Point2/Point3 so `atVector` + // The order is important: gtsam::Vector has to precede Point2/Point3 so `atVector` // can work for those fixed-size vectors. - void insert_or_assign(size_t j, Vector vector); - void insert_or_assign(size_t j, Matrix matrix); + void insert_or_assign(size_t j, gtsam::Vector vector); + void insert_or_assign(size_t j, gtsam::Matrix matrix); void insert_or_assign(size_t j, const gtsam::Point2& point2); void insert_or_assign(size_t j, const gtsam::Point3& point3); void insert_or_assign(size_t j, const gtsam::Rot2& rot2); @@ -201,8 +201,8 @@ class Values { gtsam::PinholePose, gtsam::imuBias::ConstantBias, gtsam::NavState, - Vector, - Matrix, + gtsam::Vector, + gtsam::Matrix, double}> T at(size_t j); }; diff --git a/gtsam/sfm/sfm.i b/gtsam/sfm/sfm.i index 930a0dd466..ba25cf7938 100644 --- a/gtsam/sfm/sfm.i +++ b/gtsam/sfm/sfm.i @@ -81,7 +81,7 @@ virtual class ShonanFactor3 : gtsam::NoiseModelFactor { ShonanFactor3(size_t key1, size_t key2, const gtsam::Rot3& R12, size_t p); ShonanFactor3(size_t key1, size_t key2, const gtsam::Rot3& R12, size_t p, gtsam::noiseModel::Base* model); - Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2); + gtsam::Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2); }; #include @@ -162,23 +162,23 @@ class ShonanAveraging2 { gtsam::Rot2 measured(size_t i); gtsam::KeyVector keys(size_t i); - // Matrix API (advanced use, debugging) - Matrix denseD() const; - Matrix denseQ() const; - Matrix denseL() const; - // Matrix computeLambda_(Matrix S) const; - Matrix computeLambda_(const gtsam::Values& values) const; - Matrix computeA_(const gtsam::Values& values) const; + // gtsam::Matrix API (advanced use, debugging) + gtsam::Matrix denseD() const; + gtsam::Matrix denseQ() const; + gtsam::Matrix denseL() const; + // gtsam::Matrix computeLambda_(gtsam::Matrix S) const; + gtsam::Matrix computeLambda_(const gtsam::Values& values) const; + gtsam::Matrix computeA_(const gtsam::Values& values) const; double computeMinEigenValue(const gtsam::Values& values) const; gtsam::Values initializeWithDescent(size_t p, const gtsam::Values& values, - const Vector& minEigenVector, + const gtsam::Vector& minEigenVector, double minEigenValue) const; // Advanced API gtsam::NonlinearFactorGraph buildGraphAt(size_t p) const; gtsam::Values initializeRandomlyAt(size_t p) const; double costAt(size_t p, const gtsam::Values& values) const; - pair computeMinEigenVector(const gtsam::Values& values) const; + pair computeMinEigenVector(const gtsam::Values& values) const; bool checkOptimality(const gtsam::Values& values) const; gtsam::LevenbergMarquardtOptimizer* createOptimizerAt( size_t p, const gtsam::Values& initial); @@ -212,23 +212,23 @@ class ShonanAveraging3 { gtsam::Rot3 measured(size_t i); gtsam::KeyVector keys(size_t i); - // Matrix API (advanced use, debugging) - Matrix denseD() const; - Matrix denseQ() const; - Matrix denseL() const; - // Matrix computeLambda_(Matrix S) const; - Matrix computeLambda_(const gtsam::Values& values) const; - Matrix computeA_(const gtsam::Values& values) const; + // gtsam::Matrix API (advanced use, debugging) + gtsam::Matrix denseD() const; + gtsam::Matrix denseQ() const; + gtsam::Matrix denseL() const; + // gtsam::Matrix computeLambda_(gtsam::Matrix S) const; + gtsam::Matrix computeLambda_(const gtsam::Values& values) const; + gtsam::Matrix computeA_(const gtsam::Values& values) const; double computeMinEigenValue(const gtsam::Values& values) const; gtsam::Values initializeWithDescent(size_t p, const gtsam::Values& values, - const Vector& minEigenVector, + const gtsam::Vector& minEigenVector, double minEigenValue) const; // Advanced API gtsam::NonlinearFactorGraph buildGraphAt(size_t p) const; gtsam::Values initializeRandomlyAt(size_t p) const; double costAt(size_t p, const gtsam::Values& values) const; - pair computeMinEigenVector(const gtsam::Values& values) const; + pair computeMinEigenVector(const gtsam::Values& values) const; bool checkOptimality(const gtsam::Values& values) const; gtsam::LevenbergMarquardtOptimizer* createOptimizerAt( size_t p, const gtsam::Values& initial); diff --git a/gtsam/slam/slam.i b/gtsam/slam/slam.i index 97b198b2f4..f054aaab42 100644 --- a/gtsam/slam/slam.i +++ b/gtsam/slam/slam.i @@ -12,7 +12,7 @@ namespace gtsam { // ###### #include -template virtual class BetweenFactor : gtsam::NoiseModelFactor { @@ -227,7 +227,7 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor { void print(string s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::EssentialMatrixFactor& other, double tol) const; - Vector evaluateError(const gtsam::EssentialMatrix& E) const; + gtsam::Vector evaluateError(const gtsam::EssentialMatrix& E) const; }; #include @@ -237,7 +237,7 @@ virtual class EssentialMatrixConstraint : gtsam::NoiseModelFactor { void print(string s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; bool equals(const gtsam::EssentialMatrixConstraint& other, double tol) const; - Vector evaluateError(const gtsam::Pose3& p1, const gtsam::Pose3& p2) const; + gtsam::Vector evaluateError(const gtsam::Pose3& p1, const gtsam::Pose3& p2) const; const gtsam::EssentialMatrix& measured() const; }; @@ -336,7 +336,7 @@ virtual class FrobeniusFactor : gtsam::NoiseModelFactor { FrobeniusFactor(size_t key1, size_t key2); FrobeniusFactor(size_t key1, size_t key2, gtsam::noiseModel::Base* model); - Vector evaluateError(const T& R1, const T& R2); + gtsam::Vector evaluateError(const T& R1, const T& R2); }; template @@ -345,7 +345,7 @@ virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor { FrobeniusBetweenFactor(size_t key1, size_t key2, const T& R12, gtsam::noiseModel::Base* model); - Vector evaluateError(const T& R1, const T& R2); + gtsam::Vector evaluateError(const T& R1, const T& R2); }; #include diff --git a/gtsam_unstable/gtsam_unstable.i b/gtsam_unstable/gtsam_unstable.i index 9323255adf..8566934dd8 100644 --- a/gtsam_unstable/gtsam_unstable.i +++ b/gtsam_unstable/gtsam_unstable.i @@ -54,10 +54,10 @@ class Dummy { #include class PoseRTV { PoseRTV(); - PoseRTV(Vector rtv); - PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const Vector& vel); - PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const Vector& vel); - PoseRTV(const gtsam::Pose3& pose, const Vector& vel); + PoseRTV(gtsam::Vector rtv); + PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const gtsam::Vector& vel); + PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const gtsam::Vector& vel); + PoseRTV(const gtsam::Pose3& pose, const gtsam::Vector& vel); PoseRTV(const gtsam::Pose3& pose); PoseRTV(double roll, double pitch, double yaw, double x, double y, double z, double vx, double vy, double vz); @@ -68,21 +68,21 @@ class PoseRTV { // access gtsam::Point3 translation() const; gtsam::Rot3 rotation() const; - Vector velocity() const; + gtsam::Vector velocity() const; gtsam::Pose3 pose() const; - // Vector interfaces - Vector vector() const; - Vector translationVec() const; - Vector velocityVec() const; + // gtsam::Vector interfaces + gtsam::Vector vector() const; + gtsam::Vector translationVec() const; + gtsam::Vector velocityVec() const; // manifold/Lie static size_t Dim(); size_t dim() const; - gtsam::PoseRTV retract(Vector v) const; - Vector localCoordinates(const gtsam::PoseRTV& p) const; - static gtsam::PoseRTV Expmap(Vector v); - static Vector Logmap(const gtsam::PoseRTV& p); + gtsam::PoseRTV retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::PoseRTV& p) const; + static gtsam::PoseRTV Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::PoseRTV& p); gtsam::PoseRTV inverse() const; gtsam::PoseRTV compose(const gtsam::PoseRTV& p) const; gtsam::PoseRTV between(const gtsam::PoseRTV& p) const; @@ -94,10 +94,10 @@ class PoseRTV { // IMU/dynamics gtsam::PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const; gtsam::PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const; - gtsam::PoseRTV generalDynamics(Vector accel, Vector gyro, double dt) const; - Vector imuPrediction(const gtsam::PoseRTV& x2, double dt) const; + gtsam::PoseRTV generalDynamics(gtsam::Vector accel, gtsam::Vector gyro, double dt) const; + gtsam::Vector imuPrediction(const gtsam::PoseRTV& x2, double dt) const; gtsam::Point3 translationIntegration(const gtsam::PoseRTV& x2, double dt) const; - Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const; + gtsam::Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const; void serializable() const; // enabling serialization functionality }; @@ -126,16 +126,16 @@ class Pose3Upright { gtsam::Pose3 pose() const; size_t dim() const; - gtsam::Pose3Upright retract(Vector v) const; - Vector localCoordinates(const gtsam::Pose3Upright& p2) const; + gtsam::Pose3Upright retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Pose3Upright& p2) const; static gtsam::Pose3Upright Identity(); gtsam::Pose3Upright inverse() const; gtsam::Pose3Upright compose(const gtsam::Pose3Upright& p2) const; gtsam::Pose3Upright between(const gtsam::Pose3Upright& p2) const; - static gtsam::Pose3Upright Expmap(Vector xi); - static Vector Logmap(const gtsam::Pose3Upright& p); + static gtsam::Pose3Upright Expmap(gtsam::Vector xi); + static gtsam::Vector Logmap(const gtsam::Pose3Upright& p); void serializable() const; // enabling serialization functionality }; // \class Pose3Upright @@ -156,8 +156,8 @@ class BearingS2 { bool equals(const gtsam::BearingS2& x, double tol) const; size_t dim() const; - gtsam::BearingS2 retract(Vector v) const; - Vector localCoordinates(const gtsam::BearingS2& p2) const; + gtsam::BearingS2 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::BearingS2& p2) const; void serializable() const; // enabling serialization functionality }; @@ -304,17 +304,17 @@ virtual class BetweenFactorEM : gtsam::NonlinearFactor { const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier, double prior_inlier, double prior_outlier, bool flag_bump_up_near_zero_probs); - Vector whitenedError(const gtsam::Values& x); - Vector unwhitenedError(const gtsam::Values& x); - Vector calcIndicatorProb(const gtsam::Values& x); + gtsam::Vector whitenedError(const gtsam::Values& x); + gtsam::Vector unwhitenedError(const gtsam::Values& x); + gtsam::Vector calcIndicatorProb(const gtsam::Values& x); gtsam::Pose2 measured(); // TODO: figure out how to output a template instead void set_flag_bump_up_near_zero_probs(bool flag); bool get_flag_bump_up_near_zero_probs() const; void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph); - void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12); - Matrix get_model_inlier_cov(); - Matrix get_model_outlier_cov(); + void updateNoiseModels_givenCovs(const gtsam::Values& values, gtsam::Matrix cov1, gtsam::Matrix cov2, gtsam::Matrix cov12); + gtsam::Matrix get_model_inlier_cov(); + gtsam::Matrix get_model_outlier_cov(); void serializable() const; // enabling serialization functionality }; @@ -332,15 +332,15 @@ virtual class TransformBtwRobotsUnaryFactorEM : gtsam::NonlinearFactor { const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier, double prior_inlier, double prior_outlier, bool flag_bump_up_near_zero_probs, bool start_with_M_step); - Vector whitenedError(const gtsam::Values& x); - Vector unwhitenedError(const gtsam::Values& x); - Vector calcIndicatorProb(const gtsam::Values& x); + gtsam::Vector whitenedError(const gtsam::Values& x); + gtsam::Vector unwhitenedError(const gtsam::Values& x); + gtsam::Vector calcIndicatorProb(const gtsam::Values& x); void setValAValB(const gtsam::Values valA, const gtsam::Values valB); void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph); - void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12); - Matrix get_model_inlier_cov(); - Matrix get_model_outlier_cov(); + void updateNoiseModels_givenCovs(const gtsam::Values& values, gtsam::Matrix cov1, gtsam::Matrix cov2, gtsam::Matrix cov12); + gtsam::Matrix get_model_inlier_cov(); + gtsam::Matrix get_model_outlier_cov(); void serializable() const; // enabling serialization functionality }; @@ -352,8 +352,8 @@ virtual class TransformBtwRobotsUnaryFactor : gtsam::NonlinearFactor { const gtsam::Values& valA, const gtsam::Values& valB, const gtsam::noiseModel::Gaussian* model); - Vector whitenedError(const gtsam::Values& x); - Vector unwhitenedError(const gtsam::Values& x); + gtsam::Vector whitenedError(const gtsam::Values& x); + gtsam::Vector unwhitenedError(const gtsam::Values& x); void setValAValB(const gtsam::Values valA, const gtsam::Values valB); void serializable() const; // enabling serialization functionality @@ -419,16 +419,16 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor { template virtual class IMUFactor : gtsam::NoiseModelFactor { /** Standard constructor */ - IMUFactor(Vector accel, Vector gyro, + IMUFactor(gtsam::Vector accel, gtsam::Vector gyro, double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); /** Full IMU vector specification */ - IMUFactor(Vector imu_vector, + IMUFactor(gtsam::Vector imu_vector, double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); - Vector gyro() const; - Vector accel() const; - Vector z() const; + gtsam::Vector gyro() const; + gtsam::Vector accel() const; + gtsam::Vector z() const; template size_t key() const; @@ -438,16 +438,16 @@ virtual class IMUFactor : gtsam::NoiseModelFactor { template virtual class FullIMUFactor : gtsam::NoiseModelFactor { /** Standard constructor */ - FullIMUFactor(Vector accel, Vector gyro, + FullIMUFactor(gtsam::Vector accel, gtsam::Vector gyro, double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); /** Single IMU vector - imu = [accel, gyro] */ - FullIMUFactor(Vector imu, + FullIMUFactor(gtsam::Vector imu, double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); - Vector gyro() const; - Vector accel() const; - Vector z() const; + gtsam::Vector gyro() const; + gtsam::Vector accel() const; + gtsam::Vector z() const; template size_t key() const; @@ -466,14 +466,14 @@ virtual class DRollPrior : gtsam::NonlinearFactor { }; virtual class VelocityPrior : gtsam::NonlinearFactor { - VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model); + VelocityPrior(size_t key, gtsam::Vector vel, const gtsam::noiseModel::Base* model); }; virtual class DGroundConstraint : gtsam::NonlinearFactor { // Primary constructor allows for variable height of the "floor" DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model); // Fully specify vector - use only for debugging - DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model); + DGroundConstraint(size_t key, gtsam::Vector constraint, const gtsam::noiseModel::Base* model); }; #include @@ -481,7 +481,7 @@ virtual class VelocityConstraint3 : gtsam::NonlinearFactor { /** Standard constructor */ VelocityConstraint3(size_t key1, size_t key2, size_t velKey, double dt); - Vector evaluateError(const double& x1, const double& x2, const double& v) const; + gtsam::Vector evaluateError(const double& x1, const double& x2, const double& v) const; }; #include @@ -489,7 +489,7 @@ virtual class PendulumFactor1 : gtsam::NonlinearFactor { /** Standard constructor */ PendulumFactor1(size_t k1, size_t k, size_t velKey, double dt); - Vector evaluateError(const double& qk1, const double& qk, const double& v) const; + gtsam::Vector evaluateError(const double& qk1, const double& qk, const double& v) const; }; #include @@ -497,35 +497,35 @@ virtual class PendulumFactor2 : gtsam::NonlinearFactor { /** Standard constructor */ PendulumFactor2(size_t vk1, size_t vk, size_t qKey, double dt, double L, double g); - Vector evaluateError(const double& vk1, const double& vk, const double& q) const; + gtsam::Vector evaluateError(const double& vk1, const double& vk, const double& q) const; }; virtual class PendulumFactorPk : gtsam::NonlinearFactor { /** Standard constructor */ PendulumFactorPk(size_t pk, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha); - Vector evaluateError(const double& pk, const double& qk, const double& qk1) const; + gtsam::Vector evaluateError(const double& pk, const double& qk, const double& qk1) const; }; virtual class PendulumFactorPk1 : gtsam::NonlinearFactor { /** Standard constructor */ PendulumFactorPk1(size_t pk1, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha); - Vector evaluateError(const double& pk1, const double& qk, const double& qk1) const; + gtsam::Vector evaluateError(const double& pk1, const double& qk, const double& qk1) const; }; #include virtual class Reconstruction : gtsam::NoiseModelFactor { Reconstruction(size_t gKey1, size_t gKey, size_t xiKey, double h); - Vector evaluateError(const gtsam::Pose3& gK1, const gtsam::Pose3& gK, Vector xiK) const; + gtsam::Vector evaluateError(const gtsam::Pose3& gK1, const gtsam::Pose3& gK, gtsam::Vector xiK) const; }; virtual class DiscreteEulerPoincareHelicopter : gtsam::NoiseModelFactor { DiscreteEulerPoincareHelicopter(size_t xiKey, size_t xiKey_1, size_t gKey, - double h, Matrix Inertia, Vector Fu, double m); + double h, gtsam::Matrix Inertia, gtsam::Vector Fu, double m); - Vector evaluateError(Vector xiK, Vector xiK_1, const gtsam::Pose3& gK) const; + gtsam::Vector evaluateError(gtsam::Vector xiK, gtsam::Vector xiK_1, const gtsam::Pose3& gK) const; }; //************************************************************************* @@ -649,25 +649,25 @@ virtual class InvDepthFactorVariant3b : gtsam::NoiseModelFactor { #include class Mechanization_bRn2 { Mechanization_bRn2(); - Mechanization_bRn2(gtsam::Rot3& initial_bRn, Vector initial_x_g, - Vector initial_x_a); - Vector b_g(double g_e); + Mechanization_bRn2(gtsam::Rot3& initial_bRn, gtsam::Vector initial_x_g, + gtsam::Vector initial_x_a); + gtsam::Vector b_g(double g_e); gtsam::Rot3 bRn(); - Vector x_g(); - Vector x_a(); - static gtsam::Mechanization_bRn2 initialize(Matrix U, Matrix F, double g_e); - gtsam::Mechanization_bRn2 correct(Vector dx) const; - gtsam::Mechanization_bRn2 integrate(Vector u, double dt) const; + gtsam::Vector x_g(); + gtsam::Vector x_a(); + static gtsam::Mechanization_bRn2 initialize(gtsam::Matrix U, gtsam::Matrix F, double g_e); + gtsam::Mechanization_bRn2 correct(gtsam::Vector dx) const; + gtsam::Mechanization_bRn2 integrate(gtsam::Vector u, double dt) const; //void print(string s) const; }; #include class AHRS { - AHRS(Matrix U, Matrix F, double g_e); + AHRS(gtsam::Matrix U, gtsam::Matrix F, double g_e); pair initialize(double g_e); - pair integrate(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector u, double dt); - pair aid(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, bool Farrel); - pair aidGeneral(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, Vector f_expected, const gtsam::Rot3& increment); + pair integrate(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, gtsam::Vector u, double dt); + pair aid(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, gtsam::Vector f, bool Farrel); + pair aidGeneral(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, gtsam::Vector f, gtsam::Vector f_expected, const gtsam::Rot3& increment); //void print(string s) const; }; diff --git a/python/requirements.txt b/python/requirements.txt index d117e48f98..099cc80d60 100644 --- a/python/requirements.txt +++ b/python/requirements.txt @@ -1 +1 @@ -numpy>=1.11.0,<2.0.0 +numpy>=1.11.0 diff --git a/wrap/DOCS.md b/wrap/DOCS.md index ecb6ee9856..e7457e4a00 100644 --- a/wrap/DOCS.md +++ b/wrap/DOCS.md @@ -12,7 +12,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the - Only one Method/Constructor per line, though methods/constructors can extend across multiple lines. - Methods can return - - Eigen types: `Matrix`, `Vector`. + - Eigen types: `gtsam::Matrix`, `gtsam::Vector`. - C/C++ basic types: `string`, `bool`, `size_t`, `int`, `double`, `char`, `unsigned char`. - `void` - Any class with which be copied with `std::make_shared()`. @@ -34,7 +34,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the - Overloads are supported, but arguments of different types *have* to have different names. - Arguments to functions can be any of - - Eigen types: `Matrix`, `Vector`. + - Eigen types: `gtsam::Matrix`, `gtsam::Vector`. - Eigen types and classes as an optionally const reference. - C/C++ basic types: `string`, `bool`, `size_t`, `size_t`, `double`, `char`, `unsigned char`. - Any class with which be copied with `std::make_shared()` (except Eigen). diff --git a/wrap/gtwrap/interface_parser/type.py b/wrap/gtwrap/interface_parser/type.py index e56a2f0150..02fe8868b2 100644 --- a/wrap/gtwrap/interface_parser/type.py +++ b/wrap/gtwrap/interface_parser/type.py @@ -63,9 +63,6 @@ def __init__(self, else: self.instantiations = [] - if self.name in ["Matrix", "Vector"] and not self.namespaces: - self.namespaces = ["gtsam"] - @staticmethod def from_parse_result(parse_result: Union[str, list]): """Unpack the parsed result to get the Typename instance.""" @@ -220,7 +217,6 @@ def to_cpp(self) -> str: Generate the C++ code for wrapping. Treat all pointers as "const shared_ptr&" - Treat Matrix and Vector as "const Matrix&" and "const Vector&" resp. """ if self.is_shared_ptr: @@ -228,17 +224,14 @@ def to_cpp(self) -> str: typename=self.typename.to_cpp()) elif self.is_ptr: typename = "{typename}*".format(typename=self.typename.to_cpp()) - elif self.is_ref or self.typename.name in ["Matrix", "Vector"]: + elif self.is_ref: typename = typename = "{typename}&".format( typename=self.typename.to_cpp()) else: typename = self.typename.to_cpp() return ("{const}{typename}".format( - const="const " if - (self.is_const - or self.typename.name in ["Matrix", "Vector"]) else "", - typename=typename)) + const="const " if self.is_const else "", typename=typename)) def get_typename(self): """Convenience method to get the typename of this type.""" @@ -305,13 +298,10 @@ def to_cpp(self): typename = f"std::shared_ptr<{typename}>" elif self.is_ptr: typename = "{typename}*".format(typename=typename) - elif self.is_ref or self.typename.name in ["Matrix", "Vector"]: + elif self.is_ref: typename = typename = "{typename}&".format(typename=typename) else: pass return ("{const}{typename}".format( - const="const " if - (self.is_const - or self.typename.name in ["Matrix", "Vector"]) else "", - typename=typename)) + const="const " if self.is_const else "", typename=typename)) diff --git a/wrap/pybind11/.appveyor.yml b/wrap/pybind11/.appveyor.yml index 360760ac8d..391cf1071c 100644 --- a/wrap/pybind11/.appveyor.yml +++ b/wrap/pybind11/.appveyor.yml @@ -9,7 +9,7 @@ platform: - x86 environment: matrix: - - PYTHON: 36 + - PYTHON: 38 CONFIG: Debug install: - ps: | diff --git a/wrap/pybind11/.github/CONTRIBUTING.md b/wrap/pybind11/.github/CONTRIBUTING.md index ad79743953..f5a08e2d78 100644 --- a/wrap/pybind11/.github/CONTRIBUTING.md +++ b/wrap/pybind11/.github/CONTRIBUTING.md @@ -135,7 +135,7 @@ The valid options are: * Use `-G` and the name of a generator to use something different. `cmake --help` lists the generators available. - On Unix, setting `CMAKE_GENERATER=Ninja` in your environment will give - you automatic mulithreading on all your CMake projects! + you automatic multithreading on all your CMake projects! * Open the `CMakeLists.txt` with QtCreator to generate for that IDE. * You can use `-DCMAKE_EXPORT_COMPILE_COMMANDS=ON` to generate the `.json` file that some tools expect. diff --git a/wrap/pybind11/.github/dependabot.yml b/wrap/pybind11/.github/dependabot.yml index 2c7d170839..22c34bd74d 100644 --- a/wrap/pybind11/.github/dependabot.yml +++ b/wrap/pybind11/.github/dependabot.yml @@ -4,4 +4,12 @@ updates: - package-ecosystem: "github-actions" directory: "/" schedule: - interval: "daily" + interval: "weekly" + groups: + actions: + patterns: + - "*" + ignore: + - dependency-name: actions/checkout + versions: + - "<5" diff --git a/wrap/pybind11/.github/labeler.yml b/wrap/pybind11/.github/labeler.yml index abb0d05aaa..e5a8de7511 100644 --- a/wrap/pybind11/.github/labeler.yml +++ b/wrap/pybind11/.github/labeler.yml @@ -1,8 +1,13 @@ docs: -- any: - - 'docs/**/*.rst' - - '!docs/changelog.rst' - - '!docs/upgrade.rst' + all: + - changed-files: + - all-globs-to-all-files: + - '!docs/changelog.rst' + - '!docs/upgrade.rst' + - base-branch: "^(?!dependabot).*" + - base-branch: "^(?!pre-commit-ci).*" ci: -- '.github/workflows/*.yml' + - changed-files: + - any-glob-to-any-file: + - '.github/workflows/*.yml' diff --git a/wrap/pybind11/.github/labeler_merged.yml b/wrap/pybind11/.github/labeler_merged.yml index 2374ad42e4..cf6c1f2931 100644 --- a/wrap/pybind11/.github/labeler_merged.yml +++ b/wrap/pybind11/.github/labeler_merged.yml @@ -1,3 +1,8 @@ +# Add 'needs changelog` label to any change to code files as long as the `CHANGELOG` hasn't changed +# Skip dependabot and pre-commit-ci PRs needs changelog: -- all: - - '!docs/changelog.rst' + - all: + - changed-files: + - all-globs-to-all-files: "!docs/changelog.rst" + - base-branch: "^(?!dependabot).*" + - base-branch: "^(?!pre-commit-ci).*" diff --git a/wrap/pybind11/.github/workflows/ci.yml b/wrap/pybind11/.github/workflows/ci.yml index 48f7c5e934..3054d842a1 100644 --- a/wrap/pybind11/.github/workflows/ci.yml +++ b/wrap/pybind11/.github/workflows/ci.yml @@ -30,13 +30,12 @@ jobs: strategy: fail-fast: false matrix: - runs-on: [ubuntu-20.04, windows-2022, macos-latest] + runs-on: [ubuntu-20.04, windows-2022, macos-13] python: - - '3.6' + - '3.8' - '3.9' - - '3.10' - - '3.11' - '3.12' + - '3.13' - 'pypy-3.8' - 'pypy-3.9' - 'pypy-3.10' @@ -49,37 +48,42 @@ jobs: include: # Just add a key - runs-on: ubuntu-20.04 - python: '3.6' + python: '3.8' args: > -DPYBIND11_FINDPYTHON=ON -DCMAKE_CXX_FLAGS="-D_=1" + exercise_D_: 1 - runs-on: ubuntu-20.04 python: 'pypy-3.8' args: > -DPYBIND11_FINDPYTHON=ON - runs-on: windows-2019 - python: '3.6' + python: '3.8' args: > -DPYBIND11_FINDPYTHON=ON # Inject a couple Windows 2019 runs - runs-on: windows-2019 python: '3.9' + # Extra ubuntu latest job + - runs-on: ubuntu-latest + python: '3.11' + name: "🐍 ${{ matrix.python }} • ${{ matrix.runs-on }} • x64 ${{ matrix.args }}" runs-on: ${{ matrix.runs-on }} steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Setup Python ${{ matrix.python }} - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python }} allow-prereleases: true - name: Setup Boost (Linux) # Can't use boost + define _ - if: runner.os == 'Linux' && matrix.python != '3.6' + if: runner.os == 'Linux' && matrix.exercise_D_ != 1 run: sudo apt-get install libboost-dev - name: Setup Boost (macOS) @@ -87,11 +91,11 @@ jobs: run: brew install boost - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Cache wheels if: runner.os == 'macOS' - uses: actions/cache@v3 + uses: actions/cache@v4 with: # This path is specific to macOS - we really only need it for PyPy NumPy wheels # See https://github.com/actions/cache/blob/master/examples.md#python---pip @@ -109,12 +113,15 @@ jobs: run: python -m pip install pytest-github-actions-annotate-failures # First build - C++11 mode and inplace - # More-or-less randomly adding -DPYBIND11_SIMPLE_GIL_MANAGEMENT=ON here. + # More-or-less randomly adding -DPYBIND11_SIMPLE_GIL_MANAGEMENT=ON here + # (same for PYBIND11_NUMPY_1_ONLY, but requires a NumPy 1.x at runtime). - name: Configure C++11 ${{ matrix.args }} run: > cmake -S . -B . -DPYBIND11_WERROR=ON + -DPYBIND11_DISABLE_HANDLE_TYPE_NAME_DEFAULT_IMPLEMENTATION=ON -DPYBIND11_SIMPLE_GIL_MANAGEMENT=ON + -DPYBIND11_NUMPY_1_ONLY=ON -DDOWNLOAD_CATCH=ON -DDOWNLOAD_EIGEN=ON -DCMAKE_CXX_STANDARD=11 @@ -127,9 +134,7 @@ jobs: run: cmake --build . --target pytest -j 2 - name: C++11 tests - # TODO: Figure out how to load the DLL on Python 3.8+ - if: "!(runner.os == 'Windows' && (matrix.python == 3.8 || matrix.python == 3.9 || matrix.python == '3.10' || matrix.python == '3.11' || matrix.python == 'pypy-3.8'))" - run: cmake --build . --target cpptest -j 2 + run: cmake --build . --target cpptest -j 2 - name: Interface test C++11 run: cmake --build . --target test_cmake_build @@ -139,11 +144,13 @@ jobs: # Second build - C++17 mode and in a build directory # More-or-less randomly adding -DPYBIND11_SIMPLE_GIL_MANAGEMENT=OFF here. + # (same for PYBIND11_NUMPY_1_ONLY, but requires a NumPy 1.x at runtime). - name: Configure C++17 run: > cmake -S . -B build2 -DPYBIND11_WERROR=ON -DPYBIND11_SIMPLE_GIL_MANAGEMENT=OFF + -DPYBIND11_NUMPY_1_ONLY=ON -DDOWNLOAD_CATCH=ON -DDOWNLOAD_EIGEN=ON -DCMAKE_CXX_STANDARD=17 @@ -156,8 +163,6 @@ jobs: run: cmake --build build2 --target pytest - name: C++ tests - # TODO: Figure out how to load the DLL on Python 3.8+ - if: "!(runner.os == 'Windows' && (matrix.python == 3.8 || matrix.python == 3.9 || matrix.python == '3.10' || matrix.python == '3.11' || matrix.python == 'pypy-3.8'))" run: cmake --build build2 --target cpptest # Third build - C++17 mode with unstable ABI @@ -188,6 +193,35 @@ jobs: pytest tests/extra_setuptools if: "!(matrix.runs-on == 'windows-2022')" + manylinux: + name: Manylinux on 🐍 3.13t • GIL + runs-on: ubuntu-latest + timeout-minutes: 40 + container: quay.io/pypa/musllinux_1_2_x86_64:latest + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + + - name: Prepare venv + run: python3.13t -m venv .venv + + - name: Install Python deps + run: .venv/bin/pip install -r tests/requirements.txt + + - name: Configure C++11 + run: > + cmake -S. -Bbuild + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + -DPython_ROOT_DIR=.venv + + - name: Build C++11 + run: cmake --build build -j2 + + - name: Python tests C++11 + run: cmake --build build --target pytest -j2 deadsnakes: strategy: @@ -195,9 +229,10 @@ jobs: matrix: include: # TODO: Fails on 3.10, investigate - - python-version: "3.9" - python-debug: true - valgrind: true + # JOB DISABLED (NEEDS WORK): https://github.com/pybind/pybind11/issues/4889 + # - python-version: "3.9" + # python-debug: true + # valgrind: true - python-version: "3.11" python-debug: false @@ -205,20 +240,20 @@ jobs: runs-on: ubuntu-20.04 steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Setup Python ${{ matrix.python-version }} (deadsnakes) - uses: deadsnakes/action@v3.0.1 + uses: deadsnakes/action@v3.1.0 with: python-version: ${{ matrix.python-version }} debug: ${{ matrix.python-debug }} - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Valgrind cache if: matrix.valgrind - uses: actions/cache@v3 + uses: actions/cache@v4 id: cache-valgrind with: path: valgrind @@ -302,12 +337,15 @@ jobs: - clang: 15 std: 20 container_suffix: "-bullseye" + - clang: 16 + std: 20 + container_suffix: "-bullseye" name: "🐍 3 • Clang ${{ matrix.clang }} • C++${{ matrix.std }} • x64" container: "silkeh/clang:${{ matrix.clang }}${{ matrix.container_suffix }}" steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Add wget and python3 run: apt-get update && apt-get install -y python3-dev python3-numpy python3-pytest libeigen3-dev @@ -341,7 +379,7 @@ jobs: container: nvidia/cuda:12.2.0-devel-ubuntu22.04 steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 # tzdata will try to ask for the timezone, so set the DEBIAN_FRONTEND - name: Install 🐍 3 @@ -365,7 +403,7 @@ jobs: # container: centos:8 # # steps: -# - uses: actions/checkout@v3 +# - uses: actions/checkout@v4 # # - name: Add Python 3 and a few requirements # run: yum update -y && yum install -y git python3-devel python3-numpy python3-pytest make environment-modules @@ -401,54 +439,55 @@ jobs: # run: cmake --build build --target test_cmake_build - # Testing on CentOS 7 + PGI compilers, which seems to require more workarounds - centos-nvhpc7: - if: ${{ false }} # JOB DISABLED (NEEDS WORK): https://github.com/pybind/pybind11/issues/4690 - runs-on: ubuntu-latest - name: "🐍 3 • CentOS7 / PGI 22.9 • x64" - container: centos:7 + # Testing on Ubuntu + NVHPC (previous PGI) compilers, which seems to require more workarounds + ubuntu-nvhpc7: + runs-on: ubuntu-20.04 + name: "🐍 3 • NVHPC 23.5 • C++17 • x64" + env: + # tzdata will try to ask for the timezone, so set the DEBIAN_FRONTEND + DEBIAN_FRONTEND: 'noninteractive' steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - - name: Add Python 3 and a few requirements - run: yum update -y && yum install -y epel-release && yum install -y git python3-devel make environment-modules cmake3 yum-utils + - name: Add NVHPC Repo + run: | + echo 'deb [trusted=yes] https://developer.download.nvidia.com/hpc-sdk/ubuntu/amd64 /' | \ + sudo tee /etc/apt/sources.list.d/nvhpc.list - - name: Install NVidia HPC SDK - run: yum-config-manager --add-repo https://developer.download.nvidia.com/hpc-sdk/rhel/nvhpc.repo && yum -y install nvhpc-22.9 + - name: Install 🐍 3 & NVHPC + run: | + sudo apt-get update -y && \ + sudo apt-get install -y cmake environment-modules git python3-dev python3-pip python3-numpy && \ + sudo apt-get install -y --no-install-recommends nvhpc-23-5 && \ + sudo rm -rf /var/lib/apt/lists/* + python3 -m pip install --upgrade pip + python3 -m pip install --upgrade pytest - # On CentOS 7, we have to filter a few tests (compiler internal error) - # and allow deeper template recursion (not needed on CentOS 8 with a newer - # standard library). On some systems, you many need further workarounds: + # On some systems, you many need further workarounds: # https://github.com/pybind/pybind11/pull/2475 - name: Configure shell: bash run: | source /etc/profile.d/modules.sh - module load /opt/nvidia/hpc_sdk/modulefiles/nvhpc/22.9 - cmake3 -S . -B build -DDOWNLOAD_CATCH=ON \ - -DCMAKE_CXX_STANDARD=11 \ + module load /opt/nvidia/hpc_sdk/modulefiles/nvhpc/23.5 + cmake -S . -B build -DDOWNLOAD_CATCH=ON \ + -DCMAKE_CXX_STANDARD=17 \ -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") \ -DCMAKE_CXX_FLAGS="-Wc,--pending_instantiations=0" \ -DPYBIND11_TEST_FILTER="test_smart_ptr.cpp" - # Building before installing Pip should produce a warning but not an error - name: Build - run: cmake3 --build build -j 2 --verbose - - - name: Install CMake with pip - run: | - python3 -m pip install --upgrade pip - python3 -m pip install pytest + run: cmake --build build -j 2 --verbose - name: Python tests - run: cmake3 --build build --target pytest + run: cmake --build build --target pytest - name: C++ tests - run: cmake3 --build build --target cpptest + run: cmake --build build --target cpptest - name: Interface test - run: cmake3 --build build --target test_cmake_build + run: cmake --build build --target test_cmake_build # Testing on GCC using the GCC docker images (only recent images supported) @@ -465,12 +504,13 @@ jobs: - { gcc: 10, std: 17 } - { gcc: 11, std: 20 } - { gcc: 12, std: 20 } + - { gcc: 13, std: 20 } name: "🐍 3 • GCC ${{ matrix.gcc }} • C++${{ matrix.std }}• x64" container: "gcc:${{ matrix.gcc }}" steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Add Python 3 run: apt-get update; apt-get install -y python3-dev python3-numpy python3-pytest python3-pip libeigen3-dev @@ -479,7 +519,7 @@ jobs: run: python3 -m pip install --upgrade pip - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Configure shell: bash @@ -524,13 +564,11 @@ jobs: # Testing on ICC using the oneAPI apt repo icc: runs-on: ubuntu-20.04 - strategy: - fail-fast: false name: "🐍 3 • ICC latest • x64" steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Add apt repo run: | @@ -618,15 +656,13 @@ jobs: cmake --build build-17 --target test_cmake_build - # Testing on CentOS (manylinux uses a centos base, and this is an easy way - # to get GCC 4.8, which is the manylinux1 compiler). + # Testing on CentOS (manylinux uses a centos base). centos: runs-on: ubuntu-latest strategy: fail-fast: false matrix: container: - - "centos:7" # GCC 4.8 - "almalinux:8" - "almalinux:9" @@ -634,14 +670,15 @@ jobs: container: "${{ matrix.container }}" steps: - - uses: actions/checkout@v3 + - name: Latest actions/checkout + uses: actions/checkout@v4 - - name: Add Python 3 (RHEL 7) - if: matrix.container == 'centos:7' - run: yum update -y && yum install -y python3-devel gcc-c++ make git + - name: Add Python 3.8 + if: matrix.container == 'almalinux:8' + run: dnf update -y && dnf install -y python38-devel gcc-c++ make git - - name: Add Python 3 (RHEL 8+) - if: matrix.container != 'centos:7' + - name: Add Python 3 (default) + if: matrix.container != 'almalinux:8' run: dnf update -y && dnf install -y python3-devel gcc-c++ make git - name: Update pip @@ -651,6 +688,11 @@ jobs: run: | python3 -m pip install cmake -r tests/requirements.txt + - name: Ensure NumPy 2 is used (required Python >= 3.9) + if: matrix.container == 'almalinux:9' + run: | + python3 -m pip install 'numpy>=2.0.0b1' 'scipy>=1.13.0rc1' + - name: Configure shell: bash run: > @@ -682,7 +724,7 @@ jobs: container: i386/debian:buster steps: - - uses: actions/checkout@v1 # Required to run inside docker + - uses: actions/checkout@v1 # v1 is required to run inside docker - name: Install requirements run: | @@ -725,9 +767,9 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - - uses: actions/setup-python@v4 + - uses: actions/setup-python@v5 with: python-version: "3.x" @@ -759,17 +801,25 @@ jobs: fail-fast: false matrix: python: - - 3.6 - - 3.7 - - 3.8 - - 3.9 + - '3.7' + - '3.8' + - '3.9' + - '3.10' + - '3.11' + - '3.12' include: - - python: 3.9 + - python: '3.12' args: -DCMAKE_CXX_STANDARD=20 - - python: 3.8 + - python: '3.11' + args: -DCMAKE_CXX_STANDARD=20 + - python: '3.10' + args: -DCMAKE_CXX_STANDARD=20 + - python: '3.9' + args: -DCMAKE_CXX_STANDARD=20 + - python: '3.8' args: -DCMAKE_CXX_STANDARD=17 - - python: 3.7 + - python: '3.7' args: -DCMAKE_CXX_STANDARD=14 @@ -777,19 +827,19 @@ jobs: runs-on: windows-2019 steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Setup Python ${{ matrix.python }} - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python }} architecture: x86 - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Prepare MSVC - uses: ilammy/msvc-dev-cmd@v1.12.1 + uses: ilammy/msvc-dev-cmd@v1.13.0 with: arch: x86 @@ -830,19 +880,19 @@ jobs: runs-on: windows-2019 steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Setup Python ${{ matrix.python }} - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python }} architecture: x86 - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Prepare MSVC - uses: ilammy/msvc-dev-cmd@v1.12.1 + uses: ilammy/msvc-dev-cmd@v1.13.0 with: arch: x86 @@ -878,19 +928,21 @@ jobs: runs-on: windows-2022 steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Setup Python ${{ matrix.python }} - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python }} - name: Prepare env + # Ensure use of NumPy 2 (via NumPy nightlies but can be changed soon) run: | python3 -m pip install -r tests/requirements.txt + python3 -m pip install 'numpy>=2.0.0b1' 'scipy>=1.13.0rc1' - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Configure C++20 run: > @@ -948,20 +1000,30 @@ jobs: mingw-w64-${{matrix.env}}-gcc mingw-w64-${{matrix.env}}-python-pip mingw-w64-${{matrix.env}}-python-numpy - mingw-w64-${{matrix.env}}-python-scipy mingw-w64-${{matrix.env}}-cmake mingw-w64-${{matrix.env}}-make mingw-w64-${{matrix.env}}-python-pytest - mingw-w64-${{matrix.env}}-eigen3 mingw-w64-${{matrix.env}}-boost mingw-w64-${{matrix.env}}-catch - - uses: actions/checkout@v3 + - uses: msys2/setup-msys2@v2 + if: matrix.sys == 'mingw64' + with: + msystem: ${{matrix.sys}} + install: >- + git + mingw-w64-${{matrix.env}}-python-scipy + mingw-w64-${{matrix.env}}-eigen3 + + - uses: actions/checkout@v4 - name: Configure C++11 # LTO leads to many undefined reference like # `pybind11::detail::function_call::function_call(pybind11::detail::function_call&&) - run: cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=11 -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON -S . -B build + run: >- + cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=11 -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON + -DPYTHON_EXECUTABLE=$(python -c "import sys; print(sys.executable)") + -S . -B build - name: Build C++11 run: cmake --build build -j 2 @@ -979,7 +1041,10 @@ jobs: run: git clean -fdx - name: Configure C++14 - run: cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=14 -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON -S . -B build2 + run: >- + cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=14 -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON + -DPYTHON_EXECUTABLE=$(python -c "import sys; print(sys.executable)") + -S . -B build2 - name: Build C++14 run: cmake --build build2 -j 2 @@ -997,7 +1062,10 @@ jobs: run: git clean -fdx - name: Configure C++17 - run: cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=17 -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON -S . -B build3 + run: >- + cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=17 -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON + -DPYTHON_EXECUTABLE=$(python -c "import sys; print(sys.executable)") + -S . -B build3 - name: Build C++17 run: cmake --build build3 -j 2 @@ -1027,21 +1095,21 @@ jobs: run: env - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Set up Clang uses: egor-tensin/setup-clang@v1 - name: Setup Python ${{ matrix.python }} - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python }} - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Install ninja-build tool - uses: seanmiddleditch/gha-setup-ninja@v3 + uses: seanmiddleditch/gha-setup-ninja@v5 - name: Run pip installs run: | @@ -1081,8 +1149,8 @@ jobs: run: git clean -fdx macos_brew_install_llvm: - name: "macos-latest • brew install llvm" - runs-on: macos-latest + name: "macos-13 • brew install llvm" + runs-on: macos-13 env: # https://apple.stackexchange.com/questions/227026/how-to-install-recent-clang-with-homebrew @@ -1096,7 +1164,7 @@ jobs: run: env - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Show Clang++ version before brew install llvm run: clang++ --version @@ -1108,7 +1176,7 @@ jobs: run: clang++ --version - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Run pip installs run: | diff --git a/wrap/pybind11/.github/workflows/configure.yml b/wrap/pybind11/.github/workflows/configure.yml index ec7cd612de..0e55a07954 100644 --- a/wrap/pybind11/.github/workflows/configure.yml +++ b/wrap/pybind11/.github/workflows/configure.yml @@ -24,7 +24,7 @@ jobs: strategy: fail-fast: false matrix: - runs-on: [ubuntu-20.04, macos-latest, windows-latest] + runs-on: [ubuntu-20.04, macos-13, windows-latest] arch: [x64] cmake: ["3.26"] @@ -35,9 +35,9 @@ jobs: - runs-on: ubuntu-20.04 arch: x64 - cmake: "3.27" + cmake: "3.29" - - runs-on: macos-latest + - runs-on: macos-13 arch: x64 cmake: "3.7" @@ -49,10 +49,10 @@ jobs: runs-on: ${{ matrix.runs-on }} steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Setup Python 3.7 - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: 3.7 architecture: ${{ matrix.arch }} @@ -63,7 +63,7 @@ jobs: # An action for adding a specific version of CMake: # https://github.com/jwlawson/actions-setup-cmake - name: Setup CMake ${{ matrix.cmake }} - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 with: cmake-version: ${{ matrix.cmake }} diff --git a/wrap/pybind11/.github/workflows/format.yml b/wrap/pybind11/.github/workflows/format.yml index b8242ee52c..1eaa56e1c8 100644 --- a/wrap/pybind11/.github/workflows/format.yml +++ b/wrap/pybind11/.github/workflows/format.yml @@ -25,13 +25,13 @@ jobs: name: Format runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 - - uses: actions/setup-python@v4 + - uses: actions/checkout@v4 + - uses: actions/setup-python@v5 with: python-version: "3.x" - name: Add matchers run: echo "::add-matcher::$GITHUB_WORKSPACE/.github/matchers/pylint.json" - - uses: pre-commit/action@v3.0.0 + - uses: pre-commit/action@v3.0.1 with: # Slow hooks are marked with manual - slow is okay here, run them too extra_args: --hook-stage manual --all-files @@ -43,7 +43,7 @@ jobs: runs-on: ubuntu-latest container: silkeh/clang:15-bullseye steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Install requirements run: apt-get update && apt-get install -y git python3-dev python3-pytest diff --git a/wrap/pybind11/.github/workflows/labeler.yml b/wrap/pybind11/.github/workflows/labeler.yml index 858a4a0e26..2152abbcf9 100644 --- a/wrap/pybind11/.github/workflows/labeler.yml +++ b/wrap/pybind11/.github/workflows/labeler.yml @@ -14,7 +14,7 @@ jobs: pull-requests: write steps: - - uses: actions/labeler@main + - uses: actions/labeler@v5 if: > github.event.pull_request.merged == true && !startsWith(github.event.pull_request.title, 'chore(deps):') && diff --git a/wrap/pybind11/.github/workflows/pip.yml b/wrap/pybind11/.github/workflows/pip.yml index d6687b441c..a054ce6952 100644 --- a/wrap/pybind11/.github/workflows/pip.yml +++ b/wrap/pybind11/.github/workflows/pip.yml @@ -21,19 +21,18 @@ env: jobs: # This builds the sdists and wheels and makes sure the files are exactly as - # expected. Using Windows and Python 3.6, since that is often the most - # challenging matrix element. + # expected. test-packaging: - name: 🐍 3.6 • 📦 tests • windows-latest + name: 🐍 3.8 • 📦 tests • windows-latest runs-on: windows-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - - name: Setup 🐍 3.6 - uses: actions/setup-python@v4 + - name: Setup 🐍 3.8 + uses: actions/setup-python@v5 with: - python-version: 3.6 + python-version: 3.8 - name: Prepare env run: | @@ -50,10 +49,10 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Setup 🐍 3.8 - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: 3.8 @@ -73,13 +72,13 @@ jobs: run: twine check dist/* - name: Save standard package - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: standard path: dist/pybind11-* - name: Save global package - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: global path: dist/pybind11_global-* @@ -92,23 +91,27 @@ jobs: runs-on: ubuntu-latest if: github.event_name == 'release' && github.event.action == 'published' needs: [packaging] + environment: pypi + permissions: + id-token: write + attestations: write + contents: read steps: - - uses: actions/setup-python@v4 - with: - python-version: "3.x" - # Downloads all to directories matching the artifact names - - uses: actions/download-artifact@v3 + - uses: actions/download-artifact@v4 + + - name: Generate artifact attestation for sdist and wheel + uses: actions/attest-build-provenance@173725a1209d09b31f9d30a3890cf2757ebbff0d # v1.1.2 + with: + subject-path: "*/pybind11*" - name: Publish standard package uses: pypa/gh-action-pypi-publish@release/v1 with: - password: ${{ secrets.pypi_password }} packages-dir: standard/ - name: Publish global package uses: pypa/gh-action-pypi-publish@release/v1 with: - password: ${{ secrets.pypi_password_global }} packages-dir: global/ diff --git a/wrap/pybind11/.github/workflows/upstream.yml b/wrap/pybind11/.github/workflows/upstream.yml index dd8a1c9606..3892600381 100644 --- a/wrap/pybind11/.github/workflows/upstream.yml +++ b/wrap/pybind11/.github/workflows/upstream.yml @@ -13,30 +13,30 @@ concurrency: env: PIP_BREAK_SYSTEM_PACKAGES: 1 - PIP_ONLY_BINARY: ":all:" # For cmake: VERBOSE: 1 jobs: standard: - name: "🐍 3.12 latest • ubuntu-latest • x64" + name: "🐍 3.13 latest • ubuntu-latest • x64" runs-on: ubuntu-latest # Only runs when the 'python dev' label is selected if: "contains(github.event.pull_request.labels.*.name, 'python dev')" steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - - name: Setup Python 3.12 - uses: actions/setup-python@v4 + - name: Setup Python 3.13 + uses: actions/setup-python@v5 with: - python-version: "3.12-dev" + python-version: "3.13" + allow-prereleases: true - name: Setup Boost run: sudo apt-get install libboost-dev - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.14 + uses: jwlawson/actions-setup-cmake@v2.0 - name: Run pip installs run: | diff --git a/wrap/pybind11/.pre-commit-config.yaml b/wrap/pybind11/.pre-commit-config.yaml index 86ac965d96..3cec1ebe07 100644 --- a/wrap/pybind11/.pre-commit-config.yaml +++ b/wrap/pybind11/.pre-commit-config.yaml @@ -25,33 +25,28 @@ repos: # Clang format the codebase automatically - repo: https://github.com/pre-commit/mirrors-clang-format - rev: "v16.0.6" + rev: "v18.1.5" hooks: - id: clang-format types_or: [c++, c, cuda] -# Black, the code formatter, natively supports pre-commit -- repo: https://github.com/psf/black - rev: "23.3.0" # Keep in sync with blacken-docs - hooks: - - id: black - -# Ruff, the Python auto-correcting linter written in Rust +# Ruff, the Python auto-correcting linter/formatter written in Rust - repo: https://github.com/astral-sh/ruff-pre-commit - rev: v0.0.276 + rev: v0.4.7 hooks: - id: ruff args: ["--fix", "--show-fixes"] + - id: ruff-format # Check static types with mypy - repo: https://github.com/pre-commit/mirrors-mypy - rev: "v1.4.1" + rev: "v1.10.0" hooks: - id: mypy args: [] exclude: ^(tests|docs)/ additional_dependencies: - - markdown-it-py<3 # Drop this together with dropping Python 3.7 support. + - markdown-it-py - nox - rich - types-setuptools @@ -67,7 +62,7 @@ repos: # Standard hooks - repo: https://github.com/pre-commit/pre-commit-hooks - rev: "v4.4.0" + rev: "v4.6.0" hooks: - id: check-added-large-files - id: check-case-conflict @@ -83,22 +78,22 @@ repos: - id: trailing-whitespace # Also code format the docs -- repo: https://github.com/asottile/blacken-docs - rev: "1.14.0" +- repo: https://github.com/adamchainz/blacken-docs + rev: "1.16.0" hooks: - id: blacken-docs additional_dependencies: - - black==23.3.0 # keep in sync with black hook + - black==23.* # Changes tabs to spaces - repo: https://github.com/Lucas-C/pre-commit-hooks - rev: "v1.5.1" + rev: "v1.5.5" hooks: - id: remove-tabs # Avoid directional quotes - repo: https://github.com/sirosen/texthooks - rev: "0.5.0" + rev: "0.6.6" hooks: - id: fix-ligatures - id: fix-smartquotes @@ -124,15 +119,15 @@ repos: # Use tools/codespell_ignore_lines_from_errors.py # to rebuild .codespell-ignore-lines - repo: https://github.com/codespell-project/codespell - rev: "v2.2.5" + rev: "v2.3.0" hooks: - id: codespell exclude: ".supp$" - args: ["-x.codespell-ignore-lines", "-Lccompiler"] + args: ["-x.codespell-ignore-lines", "-Lccompiler,intstruct"] # Check for common shell mistakes - repo: https://github.com/shellcheck-py/shellcheck-py - rev: "v0.9.0.5" + rev: "v0.10.0.1" hooks: - id: shellcheck @@ -142,12 +137,20 @@ repos: - id: disallow-caps name: Disallow improper capitalization language: pygrep - entry: PyBind|Numpy|Cmake|CCache|PyTest + entry: PyBind|\bNumpy\b|Cmake|CCache|PyTest exclude: ^\.pre-commit-config.yaml$ # PyLint has native support - not always usable, but works for us - repo: https://github.com/PyCQA/pylint - rev: "v3.0.0a6" + rev: "v3.2.2" hooks: - id: pylint files: ^pybind11 + +# Check schemas on some of our YAML files +- repo: https://github.com/python-jsonschema/check-jsonschema + rev: 0.28.4 + hooks: + - id: check-readthedocs + - id: check-github-workflows + - id: check-dependabot diff --git a/wrap/pybind11/.readthedocs.yml b/wrap/pybind11/.readthedocs.yml index c9c61617ca..a2b802f73d 100644 --- a/wrap/pybind11/.readthedocs.yml +++ b/wrap/pybind11/.readthedocs.yml @@ -1,3 +1,20 @@ +# https://blog.readthedocs.com/migrate-configuration-v2/ + +version: 2 + +build: + os: ubuntu-22.04 + apt_packages: + - librsvg2-bin + tools: + python: "3.11" + +sphinx: + configuration: docs/conf.py + python: - version: 3 -requirements_file: docs/requirements.txt + install: + - requirements: docs/requirements.txt + +formats: + - pdf diff --git a/wrap/pybind11/CMakeLists.txt b/wrap/pybind11/CMakeLists.txt index 87ec103468..3526a1a66a 100644 --- a/wrap/pybind11/CMakeLists.txt +++ b/wrap/pybind11/CMakeLists.txt @@ -5,15 +5,25 @@ # All rights reserved. Use of this source code is governed by a # BSD-style license that can be found in the LICENSE file. +# Propagate this policy (FindPythonInterp removal) so it can be detected later +if(NOT CMAKE_VERSION VERSION_LESS "3.27") + cmake_policy(GET CMP0148 _pybind11_cmp0148) +endif() + cmake_minimum_required(VERSION 3.5) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) +endif() + +if(_pybind11_cmp0148) + cmake_policy(SET CMP0148 ${_pybind11_cmp0148}) + unset(_pybind11_cmp0148) endif() # Avoid infinite recursion if tests include this as a subdirectory @@ -82,33 +92,59 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR) set(pybind11_system "") set_property(GLOBAL PROPERTY USE_FOLDERS ON) + if(CMAKE_VERSION VERSION_LESS "3.18") + set(_pybind11_findpython_default OFF) + else() + set(_pybind11_findpython_default ON) + endif() else() set(PYBIND11_MASTER_PROJECT OFF) set(pybind11_system SYSTEM) + set(_pybind11_findpython_default OFF) endif() # Options option(PYBIND11_INSTALL "Install pybind11 header files?" ${PYBIND11_MASTER_PROJECT}) option(PYBIND11_TEST "Build pybind11 test suite?" ${PYBIND11_MASTER_PROJECT}) option(PYBIND11_NOPYTHON "Disable search for Python" OFF) +option(PYBIND11_DISABLE_HANDLE_TYPE_NAME_DEFAULT_IMPLEMENTATION + "To enforce that a handle_type_name<> specialization exists" OFF) option(PYBIND11_SIMPLE_GIL_MANAGEMENT "Use simpler GIL management logic that does not support disassociation" OFF) +option(PYBIND11_NUMPY_1_ONLY + "Disable NumPy 2 support to avoid changes to previous pybind11 versions." OFF) set(PYBIND11_INTERNALS_VERSION "" CACHE STRING "Override the ABI version, may be used to enable the unstable ABI.") +option(PYBIND11_USE_CROSSCOMPILING "Respect CMAKE_CROSSCOMPILING" OFF) +if(PYBIND11_DISABLE_HANDLE_TYPE_NAME_DEFAULT_IMPLEMENTATION) + add_compile_definitions(PYBIND11_DISABLE_HANDLE_TYPE_NAME_DEFAULT_IMPLEMENTATION) +endif() if(PYBIND11_SIMPLE_GIL_MANAGEMENT) add_compile_definitions(PYBIND11_SIMPLE_GIL_MANAGEMENT) endif() +if(PYBIND11_NUMPY_1_ONLY) + add_compile_definitions(PYBIND11_NUMPY_1_ONLY) +endif() cmake_dependent_option( USE_PYTHON_INCLUDE_DIR "Install pybind11 headers in Python include directory instead of default installation prefix" OFF "PYBIND11_INSTALL" OFF) -cmake_dependent_option(PYBIND11_FINDPYTHON "Force new FindPython" OFF +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). +if(PYBIND11_MASTER_PROJECT + AND PYBIND11_FINDPYTHON + AND DEFINED PYTHON_EXECUTABLE + AND NOT DEFINED Python_EXECUTABLE) + set(Python_EXECUTABLE "${PYTHON_EXECUTABLE}") +endif() + # NB: when adding a header don't forget to also add it to setup.py set(PYBIND11_HEADERS include/pybind11/detail/class.h @@ -132,6 +168,7 @@ set(PYBIND11_HEADERS include/pybind11/embed.h include/pybind11/eval.h include/pybind11/gil.h + include/pybind11/gil_safe_call_once.h include/pybind11/iostream.h include/pybind11/functional.h include/pybind11/numpy.h @@ -141,7 +178,8 @@ set(PYBIND11_HEADERS include/pybind11/stl.h include/pybind11/stl_bind.h include/pybind11/stl/filesystem.h - include/pybind11/type_caster_pyobject_ptr.h) + include/pybind11/type_caster_pyobject_ptr.h + include/pybind11/typing.h) # Compare with grep and warn if mismatched if(PYBIND11_MASTER_PROJECT AND NOT CMAKE_VERSION VERSION_LESS 3.12) @@ -262,6 +300,7 @@ if(PYBIND11_INSTALL) tools/pybind11Common.cmake tools/pybind11Tools.cmake tools/pybind11NewTools.cmake + tools/pybind11GuessPythonExtSuffix.cmake DESTINATION ${PYBIND11_CMAKECONFIG_INSTALL_DIR}) if(NOT PYBIND11_EXPORT_NAME) @@ -277,7 +316,21 @@ if(PYBIND11_INSTALL) # pkg-config support if(NOT prefix_for_pc_file) - set(prefix_for_pc_file "${CMAKE_INSTALL_PREFIX}") + if(IS_ABSOLUTE "${CMAKE_INSTALL_DATAROOTDIR}") + set(prefix_for_pc_file "${CMAKE_INSTALL_PREFIX}") + else() + set(pc_datarootdir "${CMAKE_INSTALL_DATAROOTDIR}") + if(CMAKE_VERSION VERSION_LESS 3.20) + set(prefix_for_pc_file "\${pcfiledir}/..") + while(pc_datarootdir) + get_filename_component(pc_datarootdir "${pc_datarootdir}" DIRECTORY) + string(APPEND prefix_for_pc_file "/..") + endwhile() + else() + cmake_path(RELATIVE_PATH CMAKE_INSTALL_PREFIX BASE_DIRECTORY CMAKE_INSTALL_DATAROOTDIR + OUTPUT_VARIABLE prefix_for_pc_file) + endif() + endif() endif() join_paths(includedir_for_pc_file "\${prefix}" "${CMAKE_INSTALL_INCLUDEDIR}") configure_file("${CMAKE_CURRENT_SOURCE_DIR}/tools/pybind11.pc.in" diff --git a/wrap/pybind11/README.rst b/wrap/pybind11/README.rst index 80213a4062..0d1e1d2913 100644 --- a/wrap/pybind11/README.rst +++ b/wrap/pybind11/README.rst @@ -34,12 +34,12 @@ 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.6+, 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 of the new C++11 language features (specifically: tuples, lambda -functions and variadic templates). Since its creation, this library has -grown beyond Boost.Python in many ways, leading to dramatically simpler -binding code in many common situations. +some C++11 language features (specifically: tuples, lambda functions and +variadic templates). Since its creation, this library has grown beyond +Boost.Python in many ways, leading to dramatically simpler binding code in many +common situations. Tutorial and reference documentation is provided at `pybind11.readthedocs.io `_. @@ -71,6 +71,7 @@ pybind11 can map the following core C++ features to Python: - Internal references with correct reference counting - C++ classes with virtual (and pure virtual) methods can be extended in Python +- Integrated NumPy support (NumPy 2 requires pybind11 2.12+) Goodies ------- @@ -78,7 +79,7 @@ Goodies In addition to the core functionality, pybind11 provides some extra goodies: -- Python 3.6+, 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 diff --git a/wrap/pybind11/docs/advanced/embedding.rst b/wrap/pybind11/docs/advanced/embedding.rst index e6a1686f87..cbed82158e 100644 --- a/wrap/pybind11/docs/advanced/embedding.rst +++ b/wrap/pybind11/docs/advanced/embedding.rst @@ -18,7 +18,7 @@ information, see :doc:`/compiling`. .. code-block:: cmake - cmake_minimum_required(VERSION 3.5...3.26) + cmake_minimum_required(VERSION 3.5...3.29) project(example) find_package(pybind11 REQUIRED) # or `add_subdirectory(pybind11)` diff --git a/wrap/pybind11/docs/advanced/exceptions.rst b/wrap/pybind11/docs/advanced/exceptions.rst index 53981dc08f..e20f42b5fe 100644 --- a/wrap/pybind11/docs/advanced/exceptions.rst +++ b/wrap/pybind11/docs/advanced/exceptions.rst @@ -127,8 +127,7 @@ before a global translator is tried. Inside the translator, ``std::rethrow_exception`` should be used within a try block to re-throw the exception. One or more catch clauses to catch the appropriate exceptions should then be used with each clause using -``PyErr_SetString`` to set a Python exception or ``ex(string)`` to set -the python exception to a custom exception type (see below). +``py::set_error()`` (see below). To declare a custom Python exception type, declare a ``py::exception`` variable and use this in the associated exception translator (note: it is often useful @@ -142,14 +141,16 @@ standard python RuntimeError: .. code-block:: cpp - static py::exception exc(m, "MyCustomError"); + PYBIND11_CONSTINIT static py::gil_safe_call_once_and_store exc_storage; + exc_storage.call_once_and_store_result( + [&]() { return py::exception(m, "MyCustomError"); }); py::register_exception_translator([](std::exception_ptr p) { try { if (p) std::rethrow_exception(p); } catch (const MyCustomException &e) { - exc(e.what()); + py::set_error(exc_storage.get_stored(), e.what()); } catch (const OtherException &e) { - PyErr_SetString(PyExc_RuntimeError, e.what()); + py::set_error(PyExc_RuntimeError, e.what()); } }); @@ -168,8 +169,7 @@ section. .. note:: - Call either ``PyErr_SetString`` or a custom exception's call - operator (``exc(string)``) for every exception caught in a custom exception + Call ``py::set_error()`` for every exception caught in a custom exception translator. Failure to do so will cause Python to crash with ``SystemError: error return without exception set``. @@ -200,7 +200,7 @@ If module1 has the following translator: try { if (p) std::rethrow_exception(p); } catch (const std::invalid_argument &e) { - PyErr_SetString("module1 handled this") + py::set_error(PyExc_ArgumentError, "module1 handled this"); } } @@ -212,7 +212,7 @@ and module2 has the following similar translator: try { if (p) std::rethrow_exception(p); } catch (const std::invalid_argument &e) { - PyErr_SetString("module2 handled this") + py::set_error(PyExc_ArgumentError, "module2 handled this"); } } @@ -312,11 +312,11 @@ error protocol, which is outlined here. After calling the Python C API, if Python returns an error, ``throw py::error_already_set();``, which allows pybind11 to deal with the exception and pass it back to the Python interpreter. This includes calls to -the error setting functions such as ``PyErr_SetString``. +the error setting functions such as ``py::set_error()``. .. code-block:: cpp - PyErr_SetString(PyExc_TypeError, "C API type error demo"); + py::set_error(PyExc_TypeError, "C API type error demo"); throw py::error_already_set(); // But it would be easier to simply... diff --git a/wrap/pybind11/docs/advanced/functions.rst b/wrap/pybind11/docs/advanced/functions.rst index 69e3d8a1df..372934b099 100644 --- a/wrap/pybind11/docs/advanced/functions.rst +++ b/wrap/pybind11/docs/advanced/functions.rst @@ -16,7 +16,7 @@ lifetime of objects managed by them. This can lead to issues when creating bindings for functions that return a non-trivial type. Just by looking at the type information, it is not clear whether Python should take charge of the returned value and eventually free its resources, or if this is handled on the -C++ side. For this reason, pybind11 provides a several *return value policy* +C++ side. For this reason, pybind11 provides several *return value policy* annotations that can be passed to the :func:`module_::def` and :func:`class_::def` functions. The default policy is :enum:`return_value_policy::automatic`. diff --git a/wrap/pybind11/docs/advanced/misc.rst b/wrap/pybind11/docs/advanced/misc.rst index 805ec838fc..ddd7f39370 100644 --- a/wrap/pybind11/docs/advanced/misc.rst +++ b/wrap/pybind11/docs/advanced/misc.rst @@ -398,3 +398,32 @@ before they are used as a parameter or return type of a function: pyFoo.def(py::init()); pyBar.def(py::init()); } + +Setting inner type hints in docstrings +====================================== + +When you use pybind11 wrappers for ``list``, ``dict``, and other generic python +types, the docstring will just display the generic type. You can convey the +inner types in the docstring by using a special 'typed' version of the generic +type. + +.. code-block:: cpp + + PYBIND11_MODULE(example, m) { + m.def("pass_list_of_str", [](py::typing::List arg) { + // arg can be used just like py::list + )); + } + +The resulting docstring will be ``pass_list_of_str(arg0: list[str]) -> None``. + +The following special types are available in ``pybind11/typing.h``: + +* ``py::Tuple`` +* ``py::Dict`` +* ``py::List`` +* ``py::Set`` +* ``py::Callable`` + +.. warning:: Just like in python, these are merely hints. They don't actually + enforce the types of their contents at runtime or compile time. diff --git a/wrap/pybind11/docs/advanced/pycpp/numpy.rst b/wrap/pybind11/docs/advanced/pycpp/numpy.rst index 07c969305d..d09a2cea2c 100644 --- a/wrap/pybind11/docs/advanced/pycpp/numpy.rst +++ b/wrap/pybind11/docs/advanced/pycpp/numpy.rst @@ -378,8 +378,6 @@ uses of ``py::array``: - ``.itemsize()`` returns the size of an item in bytes, i.e. ``sizeof(T)``. -- ``.ndim()`` returns the number of dimensions. - - ``.shape(n)`` returns the size of dimension ``n`` - ``.size()`` returns the total number of elements (i.e. the product of the shapes). diff --git a/wrap/pybind11/docs/benchmark.py b/wrap/pybind11/docs/benchmark.py index 2150b6ca78..a273674f45 100644 --- a/wrap/pybind11/docs/benchmark.py +++ b/wrap/pybind11/docs/benchmark.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import datetime as dt import os import random @@ -70,7 +72,7 @@ def generate_dummy_code_boost(nclasses=10): for codegen in [generate_dummy_code_pybind11, generate_dummy_code_boost]: print("{") - for i in range(0, 10): + for i in range(10): nclasses = 2**i with open("test.cpp", "w") as f: f.write(codegen(nclasses)) diff --git a/wrap/pybind11/docs/changelog.rst b/wrap/pybind11/docs/changelog.rst index add3fd66b6..ab6c713c16 100644 --- a/wrap/pybind11/docs/changelog.rst +++ b/wrap/pybind11/docs/changelog.rst @@ -10,8 +10,303 @@ Changes will be added here periodically from the "Suggested changelog entry" block in pull request descriptions. +IN DEVELOPMENT +-------------- + +Changes will be summarized here periodically. + +Version 2.13.1 (June 26, 2024) +------------------------------ + +New Features: + +* Add support for ``Typing.Callable[..., T]``. + `#5202 `_ + +Bug fixes: + +* Avoid aligned allocation in free-threaded build in order to support macOS + versions before 10.14. + `#5200 `_ + +Version 2.13.0 (June 25, 2024) +------------------------------ + +New Features: + +* Support free-threaded CPython (3.13t). Add ``py::mod_gil_not_used()`` tag to + indicate if a module supports running with the GIL disabled. + `#5148 `_ + +* Support for Python 3.6 was removed. (Official end-of-life: 2021-12-23). + `#5177 `_ + +* ``py::list`` gained a ``.clear()`` method. + `#5153 `_ + + +.. feat(types) + +* Support for ``Union``, ``Optional``, ``type[T]``, ``typing.TypeGuard``, + ``typing.TypeIs``, ``typing.Never``, ``typing.NoReturn`` and + ``typing.Literal`` was added to ``pybind11/typing.h``. + `#5166 `_ + `#5165 `_ + `#5194 `_ + `#5193 `_ + `#5192 `_ + + +.. feat(cmake) + +* In CMake, if ``PYBIND11_USE_CROSSCOMPILING`` is enabled, then + ``CMAKE_CROSSCOMPILING`` will be respected and will keep pybind11 from + accessing the interpreter during configuration. Several CMake variables will + be required in this case, but can be deduced from the environment variable + ``SETUPTOOLS_EXT_SUFFIX``. The default (currently ``OFF``) may be changed in + the future. + `#5083 `_ + + +Bug fixes: + +* A refcount bug (leading to heap-use-after-free) involving trampoline + functions with ``PyObject *`` return type was fixed. + `#5156 `_ + +* Return ``py::ssize_t`` from ``.ref_count()`` instead of ``int``. + `#5139 `_ + +* A subtle bug involving C++ types with unusual ``operator&`` overrides + was fixed. + `#5189 `_ + +* Support Python 3.13 with minor fix, add to CI. + `#5127 `_ + + +.. fix(cmake) + +* Fix mistake affecting old cmake and old boost. + `#5149 `_ + + +Documentation: + +* Build docs updated to feature scikit-build-core and meson-python, and updated + setuptools instructions. + `#5168 `_ + + +Tests: + +* Avoid immortal objects in tests. + `#5150 `_ + + +CI: + +* Compile against Python 3.13t in CI. + +* Use ``macos-13`` (Intel) for CI jobs for now (will drop Python 3.7 soon). + `#5109 `_ + +* Releases now have artifact attestations, visible at + https://github.com/pybind/pybind11/attestations. + `#5196 `_ + +Other: + +* Some cleanup in preparation for 3.13 support. + `#5137 `_ + +* Avoid a warning by ensuring an iterator end check is included in release mode. + `#5129 `_ + +* Bump max cmake to 3.29. + `#5075 `_ + +* Update docs and noxfile. + `#5071 `_ + + +Version 2.12.0 (March 27, 2024) +------------------------------- + +New Features: + +* ``pybind11`` now supports compiling for + `NumPy 2 `_. Most + code shouldn't change (see :ref:`upgrade-guide-2.12` for details). However, + if you experience issues you can define ``PYBIND11_NUMPY_1_ONLY`` to disable + the new support for now, but this will be removed in the future. + `#5050 `_ + +* ``pybind11/gil_safe_call_once.h`` was added (it needs to be included + explicitly). The primary use case is GIL-safe initialization of C++ + ``static`` variables. + `#4877 `_ + +* Support move-only iterators in ``py::make_iterator``, + ``py::make_key_iterator``, ``py::make_value_iterator``. + `#4834 `_ + +* Two simple ``py::set_error()`` functions were added and the documentation was + updated accordingly. In particular, ``py::exception<>::operator()`` was + deprecated (use one of the new functions instead). The documentation for + ``py::exception<>`` was further updated to not suggest code that may result + in undefined behavior. + `#4772 `_ + +Bug fixes: + +* Removes potential for Undefined Behavior during process teardown. + `#4897 `_ + +* Improve compatibility with the nvcc compiler (especially CUDA 12.1/12.2). + `#4893 `_ + +* ``pybind11/numpy.h`` now imports NumPy's ``multiarray`` and ``_internal`` + submodules with paths depending on the installed version of NumPy (for + compatibility with NumPy 2). + `#4857 `_ + +* Builtins collections names in docstrings are now consistently rendered in + lowercase (list, set, dict, tuple), in accordance with PEP 585. + `#4833 `_ + +* Added ``py::typing::Iterator``, ``py::typing::Iterable``. + `#4832 `_ + +* Render ``py::function`` as ``Callable`` in docstring. + `#4829 `_ + +* Also bump ``PYBIND11_INTERNALS_VERSION`` for MSVC, which unlocks two new + features without creating additional incompatibilities. + `#4819 `_ + +* Guard against crashes/corruptions caused by modules built with different MSVC + versions. + `#4779 `_ + +* A long-standing bug in the handling of Python multiple inheritance was fixed. + See PR #4762 for the rather complex details. + `#4762 `_ + +* Fix ``bind_map`` with ``using`` declarations. + `#4952 `_ + +* Qualify ``py::detail::concat`` usage to avoid ADL selecting one from + somewhere else, such as modernjson's concat. + `#4955 `_ + +* Use new PyCode API on Python 3.12+. + `#4916 `_ + +* Minor cleanup from warnings reported by Clazy. + `#4988 `_ + +* Remove typing and duplicate ``class_`` for ``KeysView``/``ValuesView``/``ItemsView``. + `#4985 `_ + +* Use ``PyObject_VisitManagedDict()`` and ``PyObject_ClearManagedDict()`` on Python 3.13 and newer. + `#4973 `_ + +* Update ``make_static_property_type()`` to make it compatible with Python 3.13. + `#4971 `_ + +.. fix(types) + +* Render typed iterators for ``make_iterator``, ``make_key_iterator``, + ``make_value_iterator``. + `#4876 `_ + +* Add several missing type name specializations. + `#5073 `_ + +* Change docstring render for ``py::buffer``, ``py::sequence`` and + ``py::handle`` (to ``Buffer``, ``Sequence``, ``Any``). + `#4831 `_ + +* Fixed ``base_enum.__str__`` docstring. + `#4827 `_ + +* Enforce single line docstring signatures. + `#4735 `_ + +* Special 'typed' wrappers now available in ``typing.h`` to annotate tuple, dict, + list, set, and function. + `#4259 `_ + +* Create ``handle_type_name`` specialization to type-hint variable length tuples. + `#5051 `_ + +.. fix(build) + +* Setting ``PYBIND11_FINDPYTHON`` to OFF will force the old FindPythonLibs mechanism to be used. + `#5042 `_ + +* Skip empty ``PYBIND11_PYTHON_EXECUTABLE_LAST`` for the first cmake run. + `#4856 `_ + +* Fix FindPython mode exports & avoid ``pkg_resources`` if + ``importlib.metadata`` available. + `#4941 `_ + +* ``Python_ADDITIONAL_VERSIONS`` (classic search) now includes 3.12. + `#4909 `_ + +* ``pybind11.pc`` is now relocatable by default as long as install destinations + are not absolute paths. + `#4830 `_ + +* Correctly detect CMake FindPython removal when used as a subdirectory. + `#4806 `_ + +* Don't require the libs component on CMake 3.18+ when using + PYBIND11_FINDPYTHON (fixes manylinux builds). + `#4805 `_ + +* ``pybind11_strip`` is no longer automatically applied when + ``CMAKE_BUILD_TYPE`` is unset. + `#4780 `_ + +* Support ``DEBUG_POSFIX`` correctly for debug builds. + `#4761 `_ + +* Hardcode lto/thin lto for Emscripten cross-compiles. + `#4642 `_ + +* Upgrade maximum supported CMake version to 3.27 to fix CMP0148 warnings. + `#4786 `_ + +Documentation: + +* Small fix to grammar in ``functions.rst``. + `#4791 `_ + +* Remove upper bound in example pyproject.toml for setuptools. + `#4774 `_ + +CI: + +* CI: Update NVHPC to 23.5 and Ubuntu 20.04. + `#4764 `_ + +* Test on PyPy 3.10. + `#4714 `_ + +Other: + +* Use Ruff formatter instead of Black. + `#4912 `_ + +* An ``assert()`` was added to help Coverty avoid generating a false positive. + `#4817 `_ + + Version 2.11.1 (July 17, 2023) ------------------------------ +------------------------------ Changes: @@ -26,7 +321,7 @@ Changes: Version 2.11.0 (July 14, 2023) ------------------------------ +------------------------------ New features: diff --git a/wrap/pybind11/docs/compiling.rst b/wrap/pybind11/docs/compiling.rst index 1fd098bec4..0b7c178b01 100644 --- a/wrap/pybind11/docs/compiling.rst +++ b/wrap/pybind11/docs/compiling.rst @@ -3,15 +3,123 @@ Build systems ############# +For an overview of Python packaging including compiled packaging with a pybind11 +example, along with a cookiecutter that includes several pybind11 options, see +the `Scientific Python Development Guide`_. + +.. _Scientific Python Development Guide: https://learn.scientific-python.org/development/guides/packaging-compiled/ + +.. scikit-build-core: + +Modules with CMake +================== + +A Python extension module can be created with just a few lines of code: + +.. code-block:: cmake + + cmake_minimum_required(VERSION 3.15...3.29) + project(example LANGUAGES CXX) + + set(PYBIND11_FINDPYTHON ON) + find_package(pybind11 CONFIG REQUIRED) + + pybind11_add_module(example example.cpp) + install(TARGET example DESTINATION .) + +(You use the ``add_subdirectory`` instead, see the example in :ref:`cmake`.) In +this example, the code is located in a file named :file:`example.cpp`. Either +method will import the pybind11 project which provides the +``pybind11_add_module`` function. It will take care of all the details needed +to build a Python extension module on any platform. + +To build with pip, build, cibuildwheel, uv, or other Python tools, you can +add a ``pyproject.toml`` file like this: + +.. code-block:: toml + + [build-system] + requires = ["scikit-build-core", "pybind11"] + build-backend = "scikit_build_core.build" + + [project] + name = "example" + version = "0.1.0" + +You don't need setuptools files like ``MANIFEST.in``, ``setup.py``, or +``setup.cfg``, as this is not setuptools. See `scikit-build-core`_ for details. +For projects you plan to upload to PyPI, be sure to fill out the ``[project]`` +table with other important metadata as well (see `Writing pyproject.toml`_). + +A working sample project can be found in the [scikit_build_example]_ +repository. An older and harder-to-maintain method is in [cmake_example]_. More +details about our cmake support can be found below in :ref:`cmake`. + +.. _scikit-build-core: https://scikit-build-core.readthedocs.io + +.. [scikit_build_example] https://github.com/pybind/scikit_build_example + +.. [cmake_example] https://github.com/pybind/cmake_example + +.. _modules-meson-python: + +Modules with meson-python +========================= + +You can also build a package with `Meson`_ using `meson-python`_, if you prefer +that. Your ``meson.build`` file would look something like this: + +.. _meson-example: + +.. code-block:: meson + + project( + 'example', + 'cpp', + version: '0.1.0', + default_options: [ + 'cpp_std=c++11', + ], + ) + + py = import('python').find_installation(pure: false) + pybind11_dep = dependency('pybind11') + + py.extension_module('example', + 'example.cpp', + install: true, + dependencies : [pybind11_dep], + ) + + +And you would need a ``pyproject.toml`` file like this: + +.. code-block:: toml + + [build-system] + requires = ["meson-python", "pybind11"] + build-backend = "mesonpy" + +Meson-python *requires* your project to be in git (or mercurial) as it uses it +for the SDist creation. For projects you plan to upload to PyPI, be sure to fill out the +``[project]`` table as well (see `Writing pyproject.toml`_). + + +.. _Writing pyproject.toml: https://packaging.python.org/en/latest/guides/writing-pyproject-toml + +.. _meson: https://mesonbuild.com + +.. _meson-python: https://meson-python.readthedocs.io/en/latest + .. _build-setuptools: -Building with setuptools -======================== +Modules with setuptools +======================= -For projects on PyPI, building with setuptools is the way to go. Sylvain Corlay -has kindly provided an example project which shows how to set up everything, -including automatic generation of documentation using Sphinx. Please refer to -the [python_example]_ repository. +For projects on PyPI, a historically popular option is setuptools. Sylvain +Corlay has kindly provided an example project which shows how to set up +everything, including automatic generation of documentation using Sphinx. +Please refer to the [python_example]_ repository. .. [python_example] https://github.com/pybind/python_example @@ -21,11 +129,11 @@ To use pybind11 inside your ``setup.py``, you have to have some system to ensure that ``pybind11`` is installed when you build your package. There are four possible ways to do this, and pybind11 supports all four: You can ask all users to install pybind11 beforehand (bad), you can use -:ref:`setup_helpers-pep518` (good, but very new and requires Pip 10), -:ref:`setup_helpers-setup_requires` (discouraged by Python packagers now that -PEP 518 is available, but it still works everywhere), or you can -:ref:`setup_helpers-copy-manually` (always works but you have to manually sync -your copy to get updates). +:ref:`setup_helpers-pep518` (good), ``setup_requires=`` (discouraged), or you +can :ref:`setup_helpers-copy-manually` (works but you have to manually sync +your copy to get updates). Third party packagers like conda-forge generally +strongly prefer the ``pyproject.toml`` method, as it gives them control over +the ``pybind11`` version, and they may apply patches, etc. An example of a ``setup.py`` using pybind11's helpers: @@ -122,70 +230,41 @@ version number that includes the number of commits since your last tag and a hash for a dirty directory. Another way to force a rebuild is purge your cache or use Pip's ``--no-cache-dir`` option. +You also need a ``MANIFEST.in`` file to include all relevant files so that you +can make an SDist. If you use `pypa-build`_, that will build an SDist then a +wheel from that SDist by default, so you can look inside those files (wheels +are just zip files with a ``.whl`` extension) to make sure you aren't missing +files. `check-manifest`_ (setuptools specific) or `check-sdist`_ (general) are +CLI tools that can compare the SDist contents with your source control. + .. [Ccache] https://ccache.dev .. [setuptools_scm] https://github.com/pypa/setuptools_scm .. _setup_helpers-pep518: -PEP 518 requirements (Pip 10+ required) ---------------------------------------- +Build requirements +------------------ -If you use `PEP 518's `_ -``pyproject.toml`` file, you can ensure that ``pybind11`` is available during -the compilation of your project. When this file exists, Pip will make a new -virtual environment, download just the packages listed here in ``requires=``, -and build a wheel (binary Python package). It will then throw away the -environment, and install your wheel. +With a ``pyproject.toml`` file, you can ensure that ``pybind11`` is available +during the compilation of your project. When this file exists, Pip will make a +new virtual environment, download just the packages listed here in +``requires=``, and build a wheel (binary Python package). It will then throw +away the environment, and install your wheel. Your ``pyproject.toml`` file will likely look something like this: .. code-block:: toml [build-system] - requires = ["setuptools>=42", "wheel", "pybind11~=2.6.1"] + requires = ["setuptools", "pybind11"] build-backend = "setuptools.build_meta" -.. note:: - - The main drawback to this method is that a `PEP 517`_ compliant build tool, - such as Pip 10+, is required for this approach to work; older versions of - Pip completely ignore this file. If you distribute binaries (called wheels - in Python) using something like `cibuildwheel`_, remember that ``setup.py`` - and ``pyproject.toml`` are not even contained in the wheel, so this high - Pip requirement is only for source builds, and will not affect users of - your binary wheels. If you are building SDists and wheels, then - `pypa-build`_ is the recommended official tool. - .. _PEP 517: https://www.python.org/dev/peps/pep-0517/ -.. _cibuildwheel: https://cibuildwheel.readthedocs.io -.. _pypa-build: https://pypa-build.readthedocs.io/en/latest/ - -.. _setup_helpers-setup_requires: - -Classic ``setup_requires`` --------------------------- - -If you want to support old versions of Pip with the classic -``setup_requires=["pybind11"]`` keyword argument to setup, which triggers a -two-phase ``setup.py`` run, then you will need to use something like this to -ensure the first pass works (which has not yet installed the ``setup_requires`` -packages, since it can't install something it does not know about): - -.. code-block:: python - - try: - from pybind11.setup_helpers import Pybind11Extension - except ImportError: - from setuptools import Extension as Pybind11Extension - - -It doesn't matter that the Extension class is not the enhanced subclass for the -first pass run; and the second pass will have the ``setup_requires`` -requirements. - -This is obviously more of a hack than the PEP 518 method, but it supports -ancient versions of Pip. +.. _cibuildwheel: https://cibuildwheel.pypa.io +.. _pypa-build: https://build.pypa.io/en/latest/ +.. _check-manifest: https://pypi.io/project/check-manifest +.. _check-sdist: https://pypi.io/project/check-sdist .. _setup_helpers-copy-manually: @@ -231,32 +310,22 @@ the C++ source file. Python is then able to find the module and load it. .. [cppimport] https://github.com/tbenthompson/cppimport + + .. _cmake: 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: - -.. code-block:: cmake - - cmake_minimum_required(VERSION 3.5...3.26) - project(example LANGUAGES CXX) - - add_subdirectory(pybind11) - pybind11_add_module(example example.cpp) +extension module can be created with just a few lines of code, as seen above in +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: -This assumes that the pybind11 repository is located in a subdirectory named -:file:`pybind11` and that the code is located in a file named :file:`example.cpp`. -The CMake command ``add_subdirectory`` will import the pybind11 project which -provides the ``pybind11_add_module`` function. It will take care of all the -details needed to build a Python extension module on any platform. -A working sample project, including a way to invoke CMake from :file:`setup.py` for -PyPI integration, can be found in the [cmake_example]_ repository. - -.. [cmake_example] https://github.com/pybind/cmake_example .. versionchanged:: 2.6 CMake 3.4+ is required. @@ -264,6 +333,7 @@ PyPI integration, can be found in the [cmake_example]_ repository. .. versionchanged:: 2.11 CMake 3.5+ is required. + Further information can be found at :doc:`cmake/index`. pybind11_add_module @@ -356,7 +426,7 @@ with ``PYTHON_EXECUTABLE``. For example: .. code-block:: bash - cmake -DPYBIND11_PYTHON_VERSION=3.6 .. + cmake -DPYBIND11_PYTHON_VERSION=3.7 .. # Another method: cmake -DPYTHON_EXECUTABLE=/path/to/python .. @@ -423,7 +493,7 @@ existing targets instead: cmake_minimum_required(VERSION 3.15...3.22) project(example LANGUAGES CXX) - find_package(Python 3.6 COMPONENTS Interpreter Development REQUIRED) + find_package(Python 3.7 COMPONENTS Interpreter Development REQUIRED) find_package(pybind11 CONFIG REQUIRED) # or add_subdirectory(pybind11) @@ -498,7 +568,7 @@ You can use these targets to build complex applications. For example, the .. code-block:: cmake - cmake_minimum_required(VERSION 3.5...3.26) + cmake_minimum_required(VERSION 3.5...3.29) project(example LANGUAGES CXX) find_package(pybind11 REQUIRED) # or add_subdirectory(pybind11) @@ -556,7 +626,7 @@ information about usage in C++, see :doc:`/advanced/embedding`. .. code-block:: cmake - cmake_minimum_required(VERSION 3.5...3.26) + cmake_minimum_required(VERSION 3.5...3.29) project(example LANGUAGES CXX) find_package(pybind11 REQUIRED) # or add_subdirectory(pybind11) @@ -616,6 +686,13 @@ Building with Bazel You can build with the Bazel build system using the `pybind11_bazel `_ repository. +Building with Meson +=================== + +You can use Meson, which has support for ``pybind11`` as a dependency (internally +relying on our ``pkg-config`` support). See the :ref:`module example above `. + + Generating binding code automatically ===================================== @@ -639,3 +716,11 @@ cross-project dependency management. Additionally, it is able to autogenerate customizable pybind11-based wrappers by parsing C++ header files. .. [robotpy-build] https://robotpy-build.readthedocs.io + +[litgen]_ is an automatic python bindings generator with a focus on generating +documented and discoverable bindings: bindings will nicely reproduce the documentation +found in headers. It is is based on srcML (srcml.org), a highly scalable, multi-language +parsing tool with a developer centric approach. The API that you want to expose to python +must be C++14 compatible (but your implementation can use more modern constructs). + +.. [litgen] https://pthom.github.io/litgen diff --git a/wrap/pybind11/docs/conf.py b/wrap/pybind11/docs/conf.py index 6e24751e9e..e5cba03826 100644 --- a/wrap/pybind11/docs/conf.py +++ b/wrap/pybind11/docs/conf.py @@ -11,6 +11,7 @@ # # All configuration values have a default; values that are commented out # serve to show the default. +from __future__ import annotations import os import re @@ -81,7 +82,7 @@ # # This is also used if you do content translation via gettext catalogs. # Usually you set "language" from the command line for these cases. -language = None +language = "en" # There are two options for replacing |today|: either, you set today to some # non-false value, then it is used: diff --git a/wrap/pybind11/docs/release.rst b/wrap/pybind11/docs/release.rst index 4950c3b887..47b5717cad 100644 --- a/wrap/pybind11/docs/release.rst +++ b/wrap/pybind11/docs/release.rst @@ -15,8 +15,8 @@ For example: For beta, ``PYBIND11_VERSION_PATCH`` should be ``Z.b1``. RC's can be ``Z.rc1``. Always include the dot (even though PEP 440 allows it to be dropped). For a -final release, this must be a simple integer. There is also a HEX version of -the version just below. +final release, this must be a simple integer. There is also +``PYBIND11_VERSION_HEX`` just below that needs to be updated. To release a new version of pybind11: @@ -26,53 +26,93 @@ If you don't have nox, you should either use ``pipx run nox`` instead, or use ``pipx install nox`` or ``brew install nox`` (Unix). - Update the version number - - Update ``PYBIND11_VERSION_MAJOR`` etc. in - ``include/pybind11/detail/common.h``. PATCH should be a simple integer. - - Update the version HEX just below, as well. - - Update ``pybind11/_version.py`` (match above) - - Run ``nox -s tests_packaging`` to ensure this was done correctly. - - Ensure that all the information in ``setup.cfg`` is up-to-date, like - supported Python versions. - - Add release date in ``docs/changelog.rst`` and integrate the output of - ``nox -s make_changelog``. - - Note that the ``make_changelog`` command inspects - `needs changelog `_. - - Manually clear the ``needs changelog`` labels using the GitHub web - interface (very easy: start by clicking the link above). - - ``git add`` and ``git commit``, ``git push``. **Ensure CI passes**. (If it - fails due to a known flake issue, either ignore or restart CI.) -- Add a release branch if this is a new minor version, or update the existing release branch if it is a patch version - - New branch: ``git checkout -b vX.Y``, ``git push -u origin vX.Y`` - - Update branch: ``git checkout vX.Y``, ``git merge ``, ``git push`` + + - Update ``PYBIND11_VERSION_MAJOR`` etc. in + ``include/pybind11/detail/common.h``. PATCH should be a simple integer. + + - Update ``PYBIND11_VERSION_HEX`` just below as well. + + - Update ``pybind11/_version.py`` (match above). + + - Run ``nox -s tests_packaging`` to ensure this was done correctly. + +- Ensure that all the information in ``setup.cfg`` is up-to-date, like + supported Python versions. + +- Add release date in ``docs/changelog.rst`` and integrate the output of + ``nox -s make_changelog``. + + - Note that the ``nox -s make_changelog`` command inspects + `needs changelog `_. + + - Manually clear the ``needs changelog`` labels using the GitHub web + interface (very easy: start by clicking the link above). + +- ``git add`` and ``git commit``, ``git push``. **Ensure CI passes**. (If it + fails due to a known flake issue, either ignore or restart CI.) + +- Add a release branch if this is a new MINOR version, or update the existing + release branch if it is a patch version + + - New branch: ``git checkout -b vX.Y``, ``git push -u origin vX.Y`` + + - Update branch: ``git checkout vX.Y``, ``git merge ``, ``git push`` + - Update tags (optional; if you skip this, the GitHub release makes a - non-annotated tag for you) - - ``git tag -a vX.Y.Z -m 'vX.Y.Z release'``. - - ``git push --tags``. + non-annotated tag for you) + + - ``git tag -a vX.Y.Z -m 'vX.Y.Z release'`` + + - ``grep ^__version__ pybind11/_version.py`` + + - Last-minute consistency check: same as tag? + + - ``git push --tags`` + - Update stable - - ``git checkout stable`` - - ``git merge master`` - - ``git push`` + + - ``git checkout stable`` + + - ``git merge -X theirs vX.Y.Z`` + + - ``git diff vX.Y.Z`` + + - Carefully review and reconcile any diffs. There should be none. + + - ``git push`` + - Make a GitHub release (this shows up in the UI, sends new release notifications to users watching releases, and also uploads PyPI packages). (Note: if you do not use an existing tag, this creates a new lightweight tag for you, so you could skip the above step.) - - GUI method: Under `releases `_ - click "Draft a new release" on the far right, fill in the tag name - (if you didn't tag above, it will be made here), fill in a release name - like "Version X.Y.Z", and copy-and-paste the markdown-formatted (!) changelog - into the description (usually ``cat docs/changelog.rst | pandoc -f rst -t gfm``). - Check "pre-release" if this is a beta/RC. - - CLI method: with ``gh`` installed, run ``gh release create vX.Y.Z -t "Version X.Y.Z"`` - If this is a pre-release, add ``-p``. + + - GUI method: Under `releases `_ + click "Draft a new release" on the far right, fill in the tag name + (if you didn't tag above, it will be made here), fill in a release name + like "Version X.Y.Z", and copy-and-paste the markdown-formatted (!) changelog + into the description. You can use ``cat docs/changelog.rst | pandoc -f rst -t gfm``, + then manually remove line breaks and strip links to PRs and issues, + e.g. to a bare ``#1234``, without the surrounding ``<...>_`` hyperlink markup. + Check "pre-release" if this is a beta/RC. + + - CLI method: with ``gh`` installed, run ``gh release create vX.Y.Z -t "Version X.Y.Z"`` + If this is a pre-release, add ``-p``. - Get back to work - - Make sure you are on master, not somewhere else: ``git checkout master`` - - Update version macros in ``include/pybind11/detail/common.h`` (set PATCH to - ``0.dev1`` and increment MINOR). - - Update ``_version.py`` to match - - Run ``nox -s tests_packaging`` to ensure this was done correctly. - - Add a spot for in-development updates in ``docs/changelog.rst``. - - ``git add``, ``git commit``, ``git push`` + + - Make sure you are on master, not somewhere else: ``git checkout master`` + + - Update version macros in ``include/pybind11/detail/common.h`` (set PATCH to + ``0.dev1`` and increment MINOR). + + - Update ``pybind11/_version.py`` to match. + + - Run ``nox -s tests_packaging`` to ensure this was done correctly. + + - If the release was a new MINOR version, add a new ``IN DEVELOPMENT`` + section in ``docs/changelog.rst``. + + - ``git add``, ``git commit``, ``git push`` If a version branch is updated, remember to set PATCH to ``1.dev1``. @@ -89,7 +129,11 @@ merge it if there are no issues. Manual packaging ^^^^^^^^^^^^^^^^ -If you need to manually upload releases, you can download the releases from the job artifacts and upload them with twine. You can also make the files locally (not recommended in general, as your local directory is more likely to be "dirty" and SDists love picking up random unrelated/hidden files); this is the procedure: +If you need to manually upload releases, you can download the releases from +the job artifacts and upload them with twine. You can also make the files +locally (not recommended in general, as your local directory is more likely +to be "dirty" and SDists love picking up random unrelated/hidden files); +this is the procedure: .. code-block:: bash diff --git a/wrap/pybind11/docs/requirements.in b/wrap/pybind11/docs/requirements.in new file mode 100644 index 0000000000..bec8f707a4 --- /dev/null +++ b/wrap/pybind11/docs/requirements.in @@ -0,0 +1,6 @@ +breathe +furo +sphinx +sphinx-copybutton +sphinxcontrib-moderncmakedomain +sphinxcontrib-svg2pdfconverter diff --git a/wrap/pybind11/docs/requirements.txt b/wrap/pybind11/docs/requirements.txt index d2a9ae1645..293db6a067 100644 --- a/wrap/pybind11/docs/requirements.txt +++ b/wrap/pybind11/docs/requirements.txt @@ -1,6 +1,275 @@ -breathe==4.34.0 -furo==2022.6.21 -sphinx==5.0.2 -sphinx-copybutton==0.5.0 -sphinxcontrib-moderncmakedomain==3.21.4 -sphinxcontrib-svg2pdfconverter==1.2.0 +# This file was autogenerated by uv via the following command: +# uv pip compile --generate-hashes docs/requirements.in -o docs/requirements.txt +alabaster==0.7.16 \ + --hash=sha256:75a8b99c28a5dad50dd7f8ccdd447a121ddb3892da9e53d1ca5cca3106d58d65 \ + --hash=sha256:b46733c07dce03ae4e150330b975c75737fa60f0a7c591b6c8bf4928a28e2c92 + # via sphinx +babel==2.14.0 \ + --hash=sha256:6919867db036398ba21eb5c7a0f6b28ab8cbc3ae7a73a44ebe34ae74a4e7d363 \ + --hash=sha256:efb1a25b7118e67ce3a259bed20545c29cb68be8ad2c784c83689981b7a57287 + # via sphinx +beautifulsoup4==4.12.3 \ + --hash=sha256:74e3d1928edc070d21748185c46e3fb33490f22f52a3addee9aee0f4f7781051 \ + --hash=sha256:b80878c9f40111313e55da8ba20bdba06d8fa3969fc68304167741bbf9e082ed + # via furo +breathe==4.35.0 \ + --hash=sha256:5165541c3c67b6c7adde8b3ecfe895c6f7844783c4076b6d8d287e4f33d62386 \ + --hash=sha256:52c581f42ca4310737f9e435e3851c3d1f15446205a85fbc272f1f97ed74f5be + # via -r requirements.in +certifi==2024.2.2 \ + --hash=sha256:0569859f95fc761b18b45ef421b1290a0f65f147e92a1e5eb3e635f9a5e4e66f \ + --hash=sha256:dc383c07b76109f368f6106eee2b593b04a011ea4d55f652c6ca24a754d1cdd1 + # via requests +charset-normalizer==3.3.2 \ + --hash=sha256:06435b539f889b1f6f4ac1758871aae42dc3a8c0e24ac9e60c2384973ad73027 \ + --hash=sha256:06a81e93cd441c56a9b65d8e1d043daeb97a3d0856d177d5c90ba85acb3db087 \ + --hash=sha256:0a55554a2fa0d408816b3b5cedf0045f4b8e1a6065aec45849de2d6f3f8e9786 \ + --hash=sha256:0b2b64d2bb6d3fb9112bafa732def486049e63de9618b5843bcdd081d8144cd8 \ + --hash=sha256:10955842570876604d404661fbccbc9c7e684caf432c09c715ec38fbae45ae09 \ + --hash=sha256:122c7fa62b130ed55f8f285bfd56d5f4b4a5b503609d181f9ad85e55c89f4185 \ + --hash=sha256:1ceae2f17a9c33cb48e3263960dc5fc8005351ee19db217e9b1bb15d28c02574 \ + --hash=sha256:1d3193f4a680c64b4b6a9115943538edb896edc190f0b222e73761716519268e \ + --hash=sha256:1f79682fbe303db92bc2b1136016a38a42e835d932bab5b3b1bfcfbf0640e519 \ + --hash=sha256:2127566c664442652f024c837091890cb1942c30937add288223dc895793f898 \ + --hash=sha256:22afcb9f253dac0696b5a4be4a1c0f8762f8239e21b99680099abd9b2b1b2269 \ + --hash=sha256:25baf083bf6f6b341f4121c2f3c548875ee6f5339300e08be3f2b2ba1721cdd3 \ + --hash=sha256:2e81c7b9c8979ce92ed306c249d46894776a909505d8f5a4ba55b14206e3222f \ + --hash=sha256:3287761bc4ee9e33561a7e058c72ac0938c4f57fe49a09eae428fd88aafe7bb6 \ + --hash=sha256:34d1c8da1e78d2e001f363791c98a272bb734000fcef47a491c1e3b0505657a8 \ + --hash=sha256:37e55c8e51c236f95b033f6fb391d7d7970ba5fe7ff453dad675e88cf303377a \ + --hash=sha256:3d47fa203a7bd9c5b6cee4736ee84ca03b8ef23193c0d1ca99b5089f72645c73 \ + --hash=sha256:3e4d1f6587322d2788836a99c69062fbb091331ec940e02d12d179c1d53e25fc \ + --hash=sha256:42cb296636fcc8b0644486d15c12376cb9fa75443e00fb25de0b8602e64c1714 \ + --hash=sha256:45485e01ff4d3630ec0d9617310448a8702f70e9c01906b0d0118bdf9d124cf2 \ + --hash=sha256:4a78b2b446bd7c934f5dcedc588903fb2f5eec172f3d29e52a9096a43722adfc \ + --hash=sha256:4ab2fe47fae9e0f9dee8c04187ce5d09f48eabe611be8259444906793ab7cbce \ + --hash=sha256:4d0d1650369165a14e14e1e47b372cfcb31d6ab44e6e33cb2d4e57265290044d \ + --hash=sha256:549a3a73da901d5bc3ce8d24e0600d1fa85524c10287f6004fbab87672bf3e1e \ + --hash=sha256:55086ee1064215781fff39a1af09518bc9255b50d6333f2e4c74ca09fac6a8f6 \ + --hash=sha256:572c3763a264ba47b3cf708a44ce965d98555f618ca42c926a9c1616d8f34269 \ + --hash=sha256:573f6eac48f4769d667c4442081b1794f52919e7edada77495aaed9236d13a96 \ + --hash=sha256:5b4c145409bef602a690e7cfad0a15a55c13320ff7a3ad7ca59c13bb8ba4d45d \ + --hash=sha256:6463effa3186ea09411d50efc7d85360b38d5f09b870c48e4600f63af490e56a \ + --hash=sha256:65f6f63034100ead094b8744b3b97965785388f308a64cf8d7c34f2f2e5be0c4 \ + --hash=sha256:663946639d296df6a2bb2aa51b60a2454ca1cb29835324c640dafb5ff2131a77 \ + --hash=sha256:6897af51655e3691ff853668779c7bad41579facacf5fd7253b0133308cf000d \ + --hash=sha256:68d1f8a9e9e37c1223b656399be5d6b448dea850bed7d0f87a8311f1ff3dabb0 \ + --hash=sha256:6ac7ffc7ad6d040517be39eb591cac5ff87416c2537df6ba3cba3bae290c0fed \ + --hash=sha256:6b3251890fff30ee142c44144871185dbe13b11bab478a88887a639655be1068 \ + --hash=sha256:6c4caeef8fa63d06bd437cd4bdcf3ffefe6738fb1b25951440d80dc7df8c03ac \ + --hash=sha256:6ef1d82a3af9d3eecdba2321dc1b3c238245d890843e040e41e470ffa64c3e25 \ + --hash=sha256:753f10e867343b4511128c6ed8c82f7bec3bd026875576dfd88483c5c73b2fd8 \ + --hash=sha256:7cd13a2e3ddeed6913a65e66e94b51d80a041145a026c27e6bb76c31a853c6ab \ + --hash=sha256:7ed9e526742851e8d5cc9e6cf41427dfc6068d4f5a3bb03659444b4cabf6bc26 \ + --hash=sha256:7f04c839ed0b6b98b1a7501a002144b76c18fb1c1850c8b98d458ac269e26ed2 \ + --hash=sha256:802fe99cca7457642125a8a88a084cef28ff0cf9407060f7b93dca5aa25480db \ + --hash=sha256:80402cd6ee291dcb72644d6eac93785fe2c8b9cb30893c1af5b8fdd753b9d40f \ + --hash=sha256:8465322196c8b4d7ab6d1e049e4c5cb460d0394da4a27d23cc242fbf0034b6b5 \ + --hash=sha256:86216b5cee4b06df986d214f664305142d9c76df9b6512be2738aa72a2048f99 \ + --hash=sha256:87d1351268731db79e0f8e745d92493ee2841c974128ef629dc518b937d9194c \ + --hash=sha256:8bdb58ff7ba23002a4c5808d608e4e6c687175724f54a5dade5fa8c67b604e4d \ + --hash=sha256:8c622a5fe39a48f78944a87d4fb8a53ee07344641b0562c540d840748571b811 \ + --hash=sha256:8d756e44e94489e49571086ef83b2bb8ce311e730092d2c34ca8f7d925cb20aa \ + --hash=sha256:8f4a014bc36d3c57402e2977dada34f9c12300af536839dc38c0beab8878f38a \ + --hash=sha256:9063e24fdb1e498ab71cb7419e24622516c4a04476b17a2dab57e8baa30d6e03 \ + --hash=sha256:90d558489962fd4918143277a773316e56c72da56ec7aa3dc3dbbe20fdfed15b \ + --hash=sha256:923c0c831b7cfcb071580d3f46c4baf50f174be571576556269530f4bbd79d04 \ + --hash=sha256:95f2a5796329323b8f0512e09dbb7a1860c46a39da62ecb2324f116fa8fdc85c \ + --hash=sha256:96b02a3dc4381e5494fad39be677abcb5e6634bf7b4fa83a6dd3112607547001 \ + --hash=sha256:9f96df6923e21816da7e0ad3fd47dd8f94b2a5ce594e00677c0013018b813458 \ + --hash=sha256:a10af20b82360ab00827f916a6058451b723b4e65030c5a18577c8b2de5b3389 \ + --hash=sha256:a50aebfa173e157099939b17f18600f72f84eed3049e743b68ad15bd69b6bf99 \ + --hash=sha256:a981a536974bbc7a512cf44ed14938cf01030a99e9b3a06dd59578882f06f985 \ + --hash=sha256:a9a8e9031d613fd2009c182b69c7b2c1ef8239a0efb1df3f7c8da66d5dd3d537 \ + --hash=sha256:ae5f4161f18c61806f411a13b0310bea87f987c7d2ecdbdaad0e94eb2e404238 \ + --hash=sha256:aed38f6e4fb3f5d6bf81bfa990a07806be9d83cf7bacef998ab1a9bd660a581f \ + --hash=sha256:b01b88d45a6fcb69667cd6d2f7a9aeb4bf53760d7fc536bf679ec94fe9f3ff3d \ + --hash=sha256:b261ccdec7821281dade748d088bb6e9b69e6d15b30652b74cbbac25e280b796 \ + --hash=sha256:b2b0a0c0517616b6869869f8c581d4eb2dd83a4d79e0ebcb7d373ef9956aeb0a \ + --hash=sha256:b4a23f61ce87adf89be746c8a8974fe1c823c891d8f86eb218bb957c924bb143 \ + --hash=sha256:bd8f7df7d12c2db9fab40bdd87a7c09b1530128315d047a086fa3ae3435cb3a8 \ + --hash=sha256:beb58fe5cdb101e3a055192ac291b7a21e3b7ef4f67fa1d74e331a7f2124341c \ + --hash=sha256:c002b4ffc0be611f0d9da932eb0f704fe2602a9a949d1f738e4c34c75b0863d5 \ + --hash=sha256:c083af607d2515612056a31f0a8d9e0fcb5876b7bfc0abad3ecd275bc4ebc2d5 \ + --hash=sha256:c180f51afb394e165eafe4ac2936a14bee3eb10debc9d9e4db8958fe36afe711 \ + --hash=sha256:c235ebd9baae02f1b77bcea61bce332cb4331dc3617d254df3323aa01ab47bd4 \ + --hash=sha256:cd70574b12bb8a4d2aaa0094515df2463cb429d8536cfb6c7ce983246983e5a6 \ + --hash=sha256:d0eccceffcb53201b5bfebb52600a5fb483a20b61da9dbc885f8b103cbe7598c \ + --hash=sha256:d965bba47ddeec8cd560687584e88cf699fd28f192ceb452d1d7ee807c5597b7 \ + --hash=sha256:db364eca23f876da6f9e16c9da0df51aa4f104a972735574842618b8c6d999d4 \ + --hash=sha256:ddbb2551d7e0102e7252db79ba445cdab71b26640817ab1e3e3648dad515003b \ + --hash=sha256:deb6be0ac38ece9ba87dea880e438f25ca3eddfac8b002a2ec3d9183a454e8ae \ + --hash=sha256:e06ed3eb3218bc64786f7db41917d4e686cc4856944f53d5bdf83a6884432e12 \ + --hash=sha256:e27ad930a842b4c5eb8ac0016b0a54f5aebbe679340c26101df33424142c143c \ + --hash=sha256:e537484df0d8f426ce2afb2d0f8e1c3d0b114b83f8850e5f2fbea0e797bd82ae \ + --hash=sha256:eb00ed941194665c332bf8e078baf037d6c35d7c4f3102ea2d4f16ca94a26dc8 \ + --hash=sha256:eb6904c354526e758fda7167b33005998fb68c46fbc10e013ca97f21ca5c8887 \ + --hash=sha256:eb8821e09e916165e160797a6c17edda0679379a4be5c716c260e836e122f54b \ + --hash=sha256:efcb3f6676480691518c177e3b465bcddf57cea040302f9f4e6e191af91174d4 \ + --hash=sha256:f27273b60488abe721a075bcca6d7f3964f9f6f067c8c4c605743023d7d3944f \ + --hash=sha256:f30c3cb33b24454a82faecaf01b19c18562b1e89558fb6c56de4d9118a032fd5 \ + --hash=sha256:fb69256e180cb6c8a894fee62b3afebae785babc1ee98b81cdf68bbca1987f33 \ + --hash=sha256:fd1abc0d89e30cc4e02e4064dc67fcc51bd941eb395c502aac3ec19fab46b519 \ + --hash=sha256:ff8fa367d09b717b2a17a052544193ad76cd49979c805768879cb63d9ca50561 + # via requests +docutils==0.20.1 \ + --hash=sha256:96f387a2c5562db4476f09f13bbab2192e764cac08ebbf3a34a95d9b1e4a59d6 \ + --hash=sha256:f08a4e276c3a1583a86dce3e34aba3fe04d02bba2dd51ed16106244e8a923e3b + # via + # breathe + # sphinx +furo==2024.1.29 \ + --hash=sha256:3548be2cef45a32f8cdc0272d415fcb3e5fa6a0eb4ddfe21df3ecf1fe45a13cf \ + --hash=sha256:4d6b2fe3f10a6e36eb9cc24c1e7beb38d7a23fc7b3c382867503b7fcac8a1e02 + # via -r requirements.in +idna==3.7 \ + --hash=sha256:028ff3aadf0609c1fd278d8ea3089299412a7a8b9bd005dd08b9f8285bcb5cfc \ + --hash=sha256:82fee1fc78add43492d3a1898bfa6d8a904cc97d8427f683ed8e798d07761aa0 + # via requests +imagesize==1.4.1 \ + --hash=sha256:0d8d18d08f840c19d0ee7ca1fd82490fdc3729b7ac93f49870406ddde8ef8d8b \ + --hash=sha256:69150444affb9cb0d5cc5a92b3676f0b2fb7cd9ae39e947a5e11a36b4497cd4a + # via sphinx +jinja2==3.1.4 \ + --hash=sha256:4a3aee7acbbe7303aede8e9648d13b8bf88a429282aa6122a993f0ac800cb369 \ + --hash=sha256:bc5dd2abb727a5319567b7a813e6a2e7318c39f4f487cfe6c89c6f9c7d25197d + # via sphinx +markupsafe==2.1.5 \ + --hash=sha256:00e046b6dd71aa03a41079792f8473dc494d564611a8f89bbbd7cb93295ebdcf \ + --hash=sha256:075202fa5b72c86ad32dc7d0b56024ebdbcf2048c0ba09f1cde31bfdd57bcfff \ + --hash=sha256:0e397ac966fdf721b2c528cf028494e86172b4feba51d65f81ffd65c63798f3f \ + --hash=sha256:17b950fccb810b3293638215058e432159d2b71005c74371d784862b7e4683f3 \ + --hash=sha256:1f3fbcb7ef1f16e48246f704ab79d79da8a46891e2da03f8783a5b6fa41a9532 \ + --hash=sha256:2174c595a0d73a3080ca3257b40096db99799265e1c27cc5a610743acd86d62f \ + --hash=sha256:2b7c57a4dfc4f16f7142221afe5ba4e093e09e728ca65c51f5620c9aaeb9a617 \ + --hash=sha256:2d2d793e36e230fd32babe143b04cec8a8b3eb8a3122d2aceb4a371e6b09b8df \ + --hash=sha256:30b600cf0a7ac9234b2638fbc0fb6158ba5bdcdf46aeb631ead21248b9affbc4 \ + --hash=sha256:397081c1a0bfb5124355710fe79478cdbeb39626492b15d399526ae53422b906 \ + --hash=sha256:3a57fdd7ce31c7ff06cdfbf31dafa96cc533c21e443d57f5b1ecc6cdc668ec7f \ + --hash=sha256:3c6b973f22eb18a789b1460b4b91bf04ae3f0c4234a0a6aa6b0a92f6f7b951d4 \ + --hash=sha256:3e53af139f8579a6d5f7b76549125f0d94d7e630761a2111bc431fd820e163b8 \ + --hash=sha256:4096e9de5c6fdf43fb4f04c26fb114f61ef0bf2e5604b6ee3019d51b69e8c371 \ + --hash=sha256:4275d846e41ecefa46e2015117a9f491e57a71ddd59bbead77e904dc02b1bed2 \ + --hash=sha256:4c31f53cdae6ecfa91a77820e8b151dba54ab528ba65dfd235c80b086d68a465 \ + --hash=sha256:4f11aa001c540f62c6166c7726f71f7573b52c68c31f014c25cc7901deea0b52 \ + --hash=sha256:5049256f536511ee3f7e1b3f87d1d1209d327e818e6ae1365e8653d7e3abb6a6 \ + --hash=sha256:58c98fee265677f63a4385256a6d7683ab1832f3ddd1e66fe948d5880c21a169 \ + --hash=sha256:598e3276b64aff0e7b3451b72e94fa3c238d452e7ddcd893c3ab324717456bad \ + --hash=sha256:5b7b716f97b52c5a14bffdf688f971b2d5ef4029127f1ad7a513973cfd818df2 \ + --hash=sha256:5dedb4db619ba5a2787a94d877bc8ffc0566f92a01c0ef214865e54ecc9ee5e0 \ + --hash=sha256:619bc166c4f2de5caa5a633b8b7326fbe98e0ccbfacabd87268a2b15ff73a029 \ + --hash=sha256:629ddd2ca402ae6dbedfceeba9c46d5f7b2a61d9749597d4307f943ef198fc1f \ + --hash=sha256:656f7526c69fac7f600bd1f400991cc282b417d17539a1b228617081106feb4a \ + --hash=sha256:6ec585f69cec0aa07d945b20805be741395e28ac1627333b1c5b0105962ffced \ + --hash=sha256:72b6be590cc35924b02c78ef34b467da4ba07e4e0f0454a2c5907f473fc50ce5 \ + --hash=sha256:7502934a33b54030eaf1194c21c692a534196063db72176b0c4028e140f8f32c \ + --hash=sha256:7a68b554d356a91cce1236aa7682dc01df0edba8d043fd1ce607c49dd3c1edcf \ + --hash=sha256:7b2e5a267c855eea6b4283940daa6e88a285f5f2a67f2220203786dfa59b37e9 \ + --hash=sha256:823b65d8706e32ad2df51ed89496147a42a2a6e01c13cfb6ffb8b1e92bc910bb \ + --hash=sha256:8590b4ae07a35970728874632fed7bd57b26b0102df2d2b233b6d9d82f6c62ad \ + --hash=sha256:8dd717634f5a044f860435c1d8c16a270ddf0ef8588d4887037c5028b859b0c3 \ + --hash=sha256:8dec4936e9c3100156f8a2dc89c4b88d5c435175ff03413b443469c7c8c5f4d1 \ + --hash=sha256:97cafb1f3cbcd3fd2b6fbfb99ae11cdb14deea0736fc2b0952ee177f2b813a46 \ + --hash=sha256:a17a92de5231666cfbe003f0e4b9b3a7ae3afb1ec2845aadc2bacc93ff85febc \ + --hash=sha256:a549b9c31bec33820e885335b451286e2969a2d9e24879f83fe904a5ce59d70a \ + --hash=sha256:ac07bad82163452a6884fe8fa0963fb98c2346ba78d779ec06bd7a6262132aee \ + --hash=sha256:ae2ad8ae6ebee9d2d94b17fb62763125f3f374c25618198f40cbb8b525411900 \ + --hash=sha256:b91c037585eba9095565a3556f611e3cbfaa42ca1e865f7b8015fe5c7336d5a5 \ + --hash=sha256:bc1667f8b83f48511b94671e0e441401371dfd0f0a795c7daa4a3cd1dde55bea \ + --hash=sha256:bec0a414d016ac1a18862a519e54b2fd0fc8bbfd6890376898a6c0891dd82e9f \ + --hash=sha256:bf50cd79a75d181c9181df03572cdce0fbb75cc353bc350712073108cba98de5 \ + --hash=sha256:bff1b4290a66b490a2f4719358c0cdcd9bafb6b8f061e45c7a2460866bf50c2e \ + --hash=sha256:c061bb86a71b42465156a3ee7bd58c8c2ceacdbeb95d05a99893e08b8467359a \ + --hash=sha256:c8b29db45f8fe46ad280a7294f5c3ec36dbac9491f2d1c17345be8e69cc5928f \ + --hash=sha256:ce409136744f6521e39fd8e2a24c53fa18ad67aa5bc7c2cf83645cce5b5c4e50 \ + --hash=sha256:d050b3361367a06d752db6ead6e7edeb0009be66bc3bae0ee9d97fb326badc2a \ + --hash=sha256:d283d37a890ba4c1ae73ffadf8046435c76e7bc2247bbb63c00bd1a709c6544b \ + --hash=sha256:d9fad5155d72433c921b782e58892377c44bd6252b5af2f67f16b194987338a4 \ + --hash=sha256:daa4ee5a243f0f20d528d939d06670a298dd39b1ad5f8a72a4275124a7819eff \ + --hash=sha256:db0b55e0f3cc0be60c1f19efdde9a637c32740486004f20d1cff53c3c0ece4d2 \ + --hash=sha256:e61659ba32cf2cf1481e575d0462554625196a1f2fc06a1c777d3f48e8865d46 \ + --hash=sha256:ea3d8a3d18833cf4304cd2fc9cbb1efe188ca9b5efef2bdac7adc20594a0e46b \ + --hash=sha256:ec6a563cff360b50eed26f13adc43e61bc0c04d94b8be985e6fb24b81f6dcfdf \ + --hash=sha256:f5dfb42c4604dddc8e4305050aa6deb084540643ed5804d7455b5df8fe16f5e5 \ + --hash=sha256:fa173ec60341d6bb97a89f5ea19c85c5643c1e7dedebc22f5181eb73573142c5 \ + --hash=sha256:fa9db3f79de01457b03d4f01b34cf91bc0048eb2c3846ff26f66687c2f6d16ab \ + --hash=sha256:fce659a462a1be54d2ffcacea5e3ba2d74daa74f30f5f143fe0c58636e355fdd \ + --hash=sha256:ffee1f21e5ef0d712f9033568f8344d5da8cc2869dbd08d87c84656e6a2d2f68 + # via jinja2 +packaging==24.0 \ + --hash=sha256:2ddfb553fdf02fb784c234c7ba6ccc288296ceabec964ad2eae3777778130bc5 \ + --hash=sha256:eb82c5e3e56209074766e6885bb04b8c38a0c015d0a30036ebe7ece34c9989e9 + # via sphinx +pygments==2.17.2 \ + --hash=sha256:b27c2826c47d0f3219f29554824c30c5e8945175d888647acd804ddd04af846c \ + --hash=sha256:da46cec9fd2de5be3a8a784f434e4c4ab670b4ff54d605c4c2717e9d49c4c367 + # via + # furo + # sphinx +requests==2.32.0 \ + --hash=sha256:f2c3881dddb70d056c5bd7600a4fae312b2a300e39be6a118d30b90bd27262b5 \ + --hash=sha256:fa5490319474c82ef1d2c9bc459d3652e3ae4ef4c4ebdd18a21145a47ca4b6b8 + # via sphinx +snowballstemmer==2.2.0 \ + --hash=sha256:09b16deb8547d3412ad7b590689584cd0fe25ec8db3be37788be3810cbf19cb1 \ + --hash=sha256:c8e1716e83cc398ae16824e5572ae04e0d9fc2c6b985fb0f900f5f0c96ecba1a + # via sphinx +soupsieve==2.5 \ + --hash=sha256:5663d5a7b3bfaeee0bc4372e7fc48f9cff4940b3eec54a6451cc5299f1097690 \ + --hash=sha256:eaa337ff55a1579b6549dc679565eac1e3d000563bcb1c8ab0d0fefbc0c2cdc7 + # via beautifulsoup4 +sphinx==7.2.6 \ + --hash=sha256:1e09160a40b956dc623c910118fa636da93bd3ca0b9876a7b3df90f07d691560 \ + --hash=sha256:9a5160e1ea90688d5963ba09a2dcd8bdd526620edbb65c328728f1b2228d5ab5 + # via + # -r requirements.in + # breathe + # furo + # sphinx-basic-ng + # sphinx-copybutton + # sphinxcontrib-moderncmakedomain + # sphinxcontrib-svg2pdfconverter +sphinx-basic-ng==1.0.0b2 \ + --hash=sha256:9ec55a47c90c8c002b5960c57492ec3021f5193cb26cebc2dc4ea226848651c9 \ + --hash=sha256:eb09aedbabfb650607e9b4b68c9d240b90b1e1be221d6ad71d61c52e29f7932b + # via furo +sphinx-copybutton==0.5.2 \ + --hash=sha256:4cf17c82fb9646d1bc9ca92ac280813a3b605d8c421225fd9913154103ee1fbd \ + --hash=sha256:fb543fd386d917746c9a2c50360c7905b605726b9355cd26e9974857afeae06e + # via -r requirements.in +sphinxcontrib-applehelp==1.0.8 \ + --hash=sha256:c40a4f96f3776c4393d933412053962fac2b84f4c99a7982ba42e09576a70619 \ + --hash=sha256:cb61eb0ec1b61f349e5cc36b2028e9e7ca765be05e49641c97241274753067b4 + # via sphinx +sphinxcontrib-devhelp==1.0.6 \ + --hash=sha256:6485d09629944511c893fa11355bda18b742b83a2b181f9a009f7e500595c90f \ + --hash=sha256:9893fd3f90506bc4b97bdb977ceb8fbd823989f4316b28c3841ec128544372d3 + # via sphinx +sphinxcontrib-htmlhelp==2.0.5 \ + --hash=sha256:0dc87637d5de53dd5eec3a6a01753b1ccf99494bd756aafecd74b4fa9e729015 \ + --hash=sha256:393f04f112b4d2f53d93448d4bce35842f62b307ccdc549ec1585e950bc35e04 + # via sphinx +sphinxcontrib-jsmath==1.0.1 \ + --hash=sha256:2ec2eaebfb78f3f2078e73666b1415417a116cc848b72e5172e596c871103178 \ + --hash=sha256:a9925e4a4587247ed2191a22df5f6970656cb8ca2bd6284309578f2153e0c4b8 + # via sphinx +sphinxcontrib-moderncmakedomain==3.27.0 \ + --hash=sha256:51e259e91f58d17cc0fac9307fd40106aa59d5acaa741887903fc3660361d1a1 \ + --hash=sha256:70a73e0e7cff1b117074e968ccb7f72383ed0f572414df0e216cea06914de988 + # via -r requirements.in +sphinxcontrib-qthelp==1.0.7 \ + --hash=sha256:053dedc38823a80a7209a80860b16b722e9e0209e32fea98c90e4e6624588ed6 \ + --hash=sha256:e2ae3b5c492d58fcbd73281fbd27e34b8393ec34a073c792642cd8e529288182 + # via sphinx +sphinxcontrib-serializinghtml==1.1.10 \ + --hash=sha256:326369b8df80a7d2d8d7f99aa5ac577f51ea51556ed974e7716cfd4fca3f6cb7 \ + --hash=sha256:93f3f5dc458b91b192fe10c397e324f262cf163d79f3282c158e8436a2c4511f + # via sphinx +sphinxcontrib-svg2pdfconverter==1.2.2 \ + --hash=sha256:04ec767b55780a6b18d89cc1a8ada6d900c6efde9d1683abdb98a49b144465ca \ + --hash=sha256:80a55ca61f70eae93efc65f3814f2f177c86ba55934a9f6c5022f1778b62146b + # via -r requirements.in +urllib3==2.2.2 \ + --hash=sha256:a448b2f64d686155468037e1ace9f2d2199776e17f0a46610480d311f73e3472 \ + --hash=sha256:dd505485549a7a552833da5e6063639d0d177c04f23bc3864e41e5dc5f612168 + # via requests diff --git a/wrap/pybind11/docs/upgrade.rst b/wrap/pybind11/docs/upgrade.rst index b13d21f5ec..17c26aaa93 100644 --- a/wrap/pybind11/docs/upgrade.rst +++ b/wrap/pybind11/docs/upgrade.rst @@ -8,6 +8,34 @@ to a new version. But it goes into more detail. This includes things like deprecated APIs and their replacements, build system changes, general code modernization and other useful information. +.. _upgrade-guide-2.12: + +v2.12 +===== + +NumPy support has been upgraded to support the 2.x series too. The two relevant +changes are that: + +* ``dtype.flags()`` is now a ``uint64`` and ``dtype.alignment()`` an + ``ssize_t`` (and NumPy may return an larger than integer value for + ``itemsize()`` in NumPy 2.x). + +* The long deprecated NumPy function ``PyArray_GetArrayParamsFromObject`` + 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. +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). + +If you want to only support NumPy 1.x for now and are having problems due to +the two internal changes listed above, you can define +``PYBIND11_NUMPY_1_ONLY`` to disable the new support for now. Make sure you +define this on all pybind11 compile units, since it could be a source of ODR +violations if used inconsistently. This option will be removed in the future, +so adapting your code is highly recommended. + + .. _upgrade-guide-2.11: v2.11 diff --git a/wrap/pybind11/include/pybind11/buffer_info.h b/wrap/pybind11/include/pybind11/buffer_info.h index b99ee8bef4..75aec0ba30 100644 --- a/wrap/pybind11/include/pybind11/buffer_info.h +++ b/wrap/pybind11/include/pybind11/buffer_info.h @@ -102,22 +102,22 @@ struct buffer_info { template buffer_info(const T *ptr, ssize_t size, bool readonly = true) : buffer_info( - const_cast(ptr), sizeof(T), format_descriptor::format(), size, readonly) {} + const_cast(ptr), sizeof(T), format_descriptor::format(), size, readonly) {} explicit buffer_info(Py_buffer *view, bool ownview = true) : buffer_info( - view->buf, - view->itemsize, - view->format, - view->ndim, - {view->shape, view->shape + view->ndim}, - /* Though buffer::request() requests PyBUF_STRIDES, ctypes objects - * ignore this flag and return a view with NULL strides. - * When strides are NULL, build them manually. */ - view->strides - ? std::vector(view->strides, view->strides + view->ndim) - : detail::c_strides({view->shape, view->shape + view->ndim}, view->itemsize), - (view->readonly != 0)) { + view->buf, + view->itemsize, + view->format, + view->ndim, + {view->shape, view->shape + view->ndim}, + /* Though buffer::request() requests PyBUF_STRIDES, ctypes objects + * ignore this flag and return a view with NULL strides. + * When strides are NULL, build them manually. */ + view->strides + ? std::vector(view->strides, view->strides + view->ndim) + : detail::c_strides({view->shape, view->shape + view->ndim}, view->itemsize), + (view->readonly != 0)) { // NOLINTNEXTLINE(cppcoreguidelines-prefer-member-initializer) this->m_view = view; // NOLINTNEXTLINE(cppcoreguidelines-prefer-member-initializer) @@ -176,7 +176,7 @@ struct buffer_info { detail::any_container &&strides_in, bool readonly) : buffer_info( - ptr, itemsize, format, ndim, std::move(shape_in), std::move(strides_in), readonly) {} + ptr, itemsize, format, ndim, std::move(shape_in), std::move(strides_in), readonly) {} Py_buffer *m_view = nullptr; bool ownview = false; diff --git a/wrap/pybind11/include/pybind11/cast.h b/wrap/pybind11/include/pybind11/cast.h index db39341180..624b8ebaca 100644 --- a/wrap/pybind11/include/pybind11/cast.h +++ b/wrap/pybind11/include/pybind11/cast.h @@ -42,13 +42,15 @@ using make_caster = type_caster>; // Shortcut for calling a caster's `cast_op_type` cast operator for casting a type_caster to a T template typename make_caster::template cast_op_type cast_op(make_caster &caster) { - return caster.operator typename make_caster::template cast_op_type(); + using result_t = typename make_caster::template cast_op_type; // See PR #4893 + return caster.operator result_t(); } template typename make_caster::template cast_op_type::type> cast_op(make_caster &&caster) { - return std::move(caster).operator typename make_caster:: - template cast_op_type::type>(); + using result_t = typename make_caster::template cast_op_type< + typename std::add_rvalue_reference::type>; // See PR #4893 + return std::move(caster).operator result_t(); } template @@ -325,8 +327,9 @@ class type_caster { value = false; return true; } - if (convert || (std::strcmp("numpy.bool_", Py_TYPE(src.ptr())->tp_name) == 0)) { - // (allow non-implicit conversion for numpy booleans) + if (convert || is_numpy_bool(src)) { + // (allow non-implicit conversion for numpy booleans), use strncmp + // since NumPy 1.x had an additional trailing underscore. Py_ssize_t res = -1; if (src.is_none()) { @@ -358,6 +361,15 @@ class type_caster { return handle(src ? Py_True : Py_False).inc_ref(); } PYBIND11_TYPE_CASTER(bool, const_name("bool")); + +private: + // Test if an object is a NumPy boolean (without fetching the type). + static inline bool is_numpy_bool(handle object) { + const char *type_name = Py_TYPE(object.ptr())->tp_name; + // Name changed to `numpy.bool` in NumPy 2, `numpy.bool_` is needed for 1.x support + return std::strcmp("numpy.bool", type_name) == 0 + || std::strcmp("numpy.bool_", type_name) == 0; + } }; // Helper class for UTF-{8,16,32} C++ stl strings: @@ -660,8 +672,9 @@ class tuple_caster { return cast(*src, policy, parent); } - static constexpr auto name - = const_name("Tuple[") + concat(make_caster::name...) + const_name("]"); + static constexpr auto name = const_name("tuple[") + + ::pybind11::detail::concat(make_caster::name...) + + const_name("]"); template using cast_op_type = type; @@ -869,10 +882,53 @@ struct is_holder_type template struct is_holder_type> : std::true_type {}; +#ifdef PYBIND11_DISABLE_HANDLE_TYPE_NAME_DEFAULT_IMPLEMENTATION // See PR #4888 + +// This leads to compilation errors if a specialization is missing. +template +struct handle_type_name; + +#else + template struct handle_type_name { static constexpr auto name = const_name(); }; + +#endif + +template <> +struct handle_type_name { + static constexpr auto name = const_name("object"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("list"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("dict"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("Union[set, frozenset]"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("set"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("frozenset"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("str"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("tuple"); +}; template <> struct handle_type_name { static constexpr auto name = const_name("bool"); @@ -882,6 +938,10 @@ struct handle_type_name { static constexpr auto name = const_name(PYBIND11_BYTES_NAME); }; template <> +struct handle_type_name { + static constexpr auto name = const_name("Buffer"); +}; +template <> struct handle_type_name { static constexpr auto name = const_name("int"); }; @@ -898,10 +958,50 @@ struct handle_type_name { static constexpr auto name = const_name("float"); }; template <> +struct handle_type_name { + static constexpr auto name = const_name("Callable"); +}; +template <> +struct handle_type_name { + static constexpr auto name = handle_type_name::name; +}; +template <> struct handle_type_name { static constexpr auto name = const_name("None"); }; template <> +struct handle_type_name { + static constexpr auto name = const_name("Sequence"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("bytearray"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("memoryview"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("slice"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("type"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("capsule"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("ellipsis"); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name("weakref"); +}; +template <> struct handle_type_name { static constexpr auto name = const_name("*args"); }; @@ -909,6 +1009,30 @@ template <> struct handle_type_name { static constexpr auto name = const_name("**kwargs"); }; +template <> +struct handle_type_name { + static constexpr auto name = const_name(); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name(); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name(); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name(); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name(); +}; +template <> +struct handle_type_name { + static constexpr auto name = const_name(); +}; template struct pyobject_caster { @@ -1215,13 +1339,24 @@ enable_if_t::value, T> cast_ref(object &&, // static_assert, even though if it's in dead code, so we provide a "trampoline" to pybind11::cast // that only does anything in cases where pybind11::cast is valid. template -enable_if_t::value, T> cast_safe(object &&) { +enable_if_t::value + && !detail::is_same_ignoring_cvref::value, + T> +cast_safe(object &&) { pybind11_fail("Internal error: cast_safe fallback invoked"); } template enable_if_t::value, void> cast_safe(object &&) {} template -enable_if_t, std::is_void>::value, T> +enable_if_t::value, PyObject *> +cast_safe(object &&o) { + return o.release().ptr(); +} +template +enable_if_t, + detail::is_same_ignoring_cvref, + std::is_void>::value, + T> cast_safe(object &&o) { return pybind11::cast(std::move(o)); } @@ -1377,7 +1512,15 @@ inline namespace literals { /** \rst String literal version of `arg` \endrst */ -constexpr arg operator"" _a(const char *name, size_t) { return arg(name); } +constexpr arg +#if !defined(__clang__) && defined(__GNUC__) && __GNUC__ < 5 +operator"" _a // gcc 4.8.5 insists on having a space (hard error). +#else +operator""_a // clang 17 generates a deprecation warning if there is a space. +#endif + (const char *name, size_t) { + return arg(name); +} } // namespace literals PYBIND11_NAMESPACE_BEGIN(detail) @@ -1438,7 +1581,8 @@ class argument_loader { static_assert(args_pos == -1 || args_pos == constexpr_first(), "py::args cannot be specified more than once"); - static constexpr auto arg_names = concat(type_descr(make_caster::name)...); + static constexpr auto arg_names + = ::pybind11::detail::concat(type_descr(make_caster::name)...); bool load_args(function_call &call) { return load_impl_sequence(call, indices{}); } diff --git a/wrap/pybind11/include/pybind11/detail/class.h b/wrap/pybind11/include/pybind11/detail/class.h index bc2b40c50a..d30621c88c 100644 --- a/wrap/pybind11/include/pybind11/detail/class.h +++ b/wrap/pybind11/include/pybind11/detail/class.h @@ -86,17 +86,16 @@ inline PyTypeObject *make_static_property_type() { type->tp_descr_get = pybind11_static_get; type->tp_descr_set = pybind11_static_set; - if (PyType_Ready(type) < 0) { - pybind11_fail("make_static_property_type(): failure in PyType_Ready()!"); - } - # if PY_VERSION_HEX >= 0x030C0000 - // PRE 3.12 FEATURE FREEZE. PLEASE REVIEW AFTER FREEZE. // Since Python-3.12 property-derived types are required to // have dynamic attributes (to set `__doc__`) enable_dynamic_attributes(heap_type); # endif + if (PyType_Ready(type) < 0) { + pybind11_fail("make_static_property_type(): failure in PyType_Ready()!"); + } + setattr((PyObject *) type, "__module__", str("pybind11_builtins")); PYBIND11_SET_OLDPY_QUALNAME(type, name_obj); @@ -189,12 +188,10 @@ extern "C" inline PyObject *pybind11_meta_call(PyObject *type, PyObject *args, P return nullptr; } - // This must be a pybind11 instance - auto *instance = reinterpret_cast(self); - // Ensure that the base __init__ function(s) were called - for (const auto &vh : values_and_holders(instance)) { - if (!vh.holder_constructed()) { + values_and_holders vhs(self); + for (const auto &vh : vhs) { + if (!vh.holder_constructed() && !vhs.is_redundant_value_and_holder(vh)) { PyErr_Format(PyExc_TypeError, "%.200s.__init__() must be called when overriding __init__", get_fully_qualified_tp_name(vh.type->type).c_str()); @@ -208,39 +205,40 @@ extern "C" inline PyObject *pybind11_meta_call(PyObject *type, PyObject *args, P /// Cleanup the type-info for a pybind11-registered type. extern "C" inline void pybind11_meta_dealloc(PyObject *obj) { - auto *type = (PyTypeObject *) obj; - auto &internals = get_internals(); - - // A pybind11-registered type will: - // 1) be found in internals.registered_types_py - // 2) have exactly one associated `detail::type_info` - auto found_type = internals.registered_types_py.find(type); - if (found_type != internals.registered_types_py.end() && found_type->second.size() == 1 - && found_type->second[0]->type == type) { - - auto *tinfo = found_type->second[0]; - auto tindex = std::type_index(*tinfo->cpptype); - internals.direct_conversions.erase(tindex); - - if (tinfo->module_local) { - get_local_internals().registered_types_cpp.erase(tindex); - } else { - internals.registered_types_cpp.erase(tindex); - } - internals.registered_types_py.erase(tinfo->type); - - // Actually just `std::erase_if`, but that's only available in C++20 - auto &cache = internals.inactive_override_cache; - for (auto it = cache.begin(), last = cache.end(); it != last;) { - if (it->first == (PyObject *) tinfo->type) { - it = cache.erase(it); + with_internals([obj](internals &internals) { + auto *type = (PyTypeObject *) obj; + + // A pybind11-registered type will: + // 1) be found in internals.registered_types_py + // 2) have exactly one associated `detail::type_info` + auto found_type = internals.registered_types_py.find(type); + if (found_type != internals.registered_types_py.end() && found_type->second.size() == 1 + && found_type->second[0]->type == type) { + + auto *tinfo = found_type->second[0]; + auto tindex = std::type_index(*tinfo->cpptype); + internals.direct_conversions.erase(tindex); + + if (tinfo->module_local) { + get_local_internals().registered_types_cpp.erase(tindex); } else { - ++it; + internals.registered_types_cpp.erase(tindex); + } + internals.registered_types_py.erase(tinfo->type); + + // Actually just `std::erase_if`, but that's only available in C++20 + auto &cache = internals.inactive_override_cache; + for (auto it = cache.begin(), last = cache.end(); it != last;) { + if (it->first == (PyObject *) tinfo->type) { + it = cache.erase(it); + } else { + ++it; + } } - } - delete tinfo; - } + delete tinfo; + } + }); PyType_Type.tp_dealloc(obj); } @@ -313,19 +311,20 @@ inline void traverse_offset_bases(void *valueptr, } inline bool register_instance_impl(void *ptr, instance *self) { - get_internals().registered_instances.emplace(ptr, self); + with_instance_map(ptr, [&](instance_map &instances) { instances.emplace(ptr, self); }); return true; // unused, but gives the same signature as the deregister func } inline bool deregister_instance_impl(void *ptr, instance *self) { - auto ®istered_instances = get_internals().registered_instances; - auto range = registered_instances.equal_range(ptr); - for (auto it = range.first; it != range.second; ++it) { - if (self == it->second) { - registered_instances.erase(it); - return true; + return with_instance_map(ptr, [&](instance_map &instances) { + auto range = instances.equal_range(ptr); + for (auto it = range.first; it != range.second; ++it) { + if (self == it->second) { + instances.erase(it); + return true; + } } - } - return false; + return false; + }); } inline void register_instance(instance *self, void *valptr, const type_info *tinfo) { @@ -375,28 +374,37 @@ extern "C" inline PyObject *pybind11_object_new(PyTypeObject *type, PyObject *, extern "C" inline int pybind11_object_init(PyObject *self, PyObject *, PyObject *) { PyTypeObject *type = Py_TYPE(self); std::string msg = get_fully_qualified_tp_name(type) + ": No constructor defined!"; - PyErr_SetString(PyExc_TypeError, msg.c_str()); + set_error(PyExc_TypeError, msg.c_str()); return -1; } inline void add_patient(PyObject *nurse, PyObject *patient) { - auto &internals = get_internals(); auto *instance = reinterpret_cast(nurse); instance->has_patients = true; Py_INCREF(patient); - internals.patients[nurse].push_back(patient); + + with_internals([&](internals &internals) { internals.patients[nurse].push_back(patient); }); } inline void clear_patients(PyObject *self) { auto *instance = reinterpret_cast(self); - auto &internals = get_internals(); - auto pos = internals.patients.find(self); - assert(pos != internals.patients.end()); - // Clearing the patients can cause more Python code to run, which - // can invalidate the iterator. Extract the vector of patients - // from the unordered_map first. - auto patients = std::move(pos->second); - internals.patients.erase(pos); + std::vector patients; + + with_internals([&](internals &internals) { + auto pos = internals.patients.find(self); + + if (pos == internals.patients.end()) { + pybind11_fail( + "FATAL: Internal consistency check failed: Invalid clear_patients() call."); + } + + // Clearing the patients can cause more Python code to run, which + // can invalidate the iterator. Extract the vector of patients + // from the unordered_map first. + patients = std::move(pos->second); + internals.patients.erase(pos); + }); + instance->has_patients = false; for (PyObject *&patient : patients) { Py_CLEAR(patient); @@ -522,8 +530,12 @@ inline PyObject *make_object_base_type(PyTypeObject *metaclass) { /// dynamic_attr: Allow the garbage collector to traverse the internal instance `__dict__`. extern "C" inline int pybind11_traverse(PyObject *self, visitproc visit, void *arg) { +#if PY_VERSION_HEX >= 0x030D0000 + PyObject_VisitManagedDict(self, visit, arg); +#else PyObject *&dict = *_PyObject_GetDictPtr(self); Py_VISIT(dict); +#endif // https://docs.python.org/3/c-api/typeobj.html#c.PyTypeObject.tp_traverse #if PY_VERSION_HEX >= 0x03090000 Py_VISIT(Py_TYPE(self)); @@ -533,8 +545,12 @@ extern "C" inline int pybind11_traverse(PyObject *self, visitproc visit, void *a /// dynamic_attr: Allow the GC to clear the dictionary. extern "C" inline int pybind11_clear(PyObject *self) { +#if PY_VERSION_HEX >= 0x030D0000 + PyObject_ClearManagedDict(self); +#else PyObject *&dict = *_PyObject_GetDictPtr(self); Py_CLEAR(dict); +#endif return 0; } @@ -551,17 +567,9 @@ inline void enable_dynamic_attributes(PyHeapTypeObject *heap_type) { type->tp_traverse = pybind11_traverse; type->tp_clear = pybind11_clear; - static PyGetSetDef getset[] = {{ -#if PY_VERSION_HEX < 0x03070000 - const_cast("__dict__"), -#else - "__dict__", -#endif - PyObject_GenericGetDict, - PyObject_GenericSetDict, - nullptr, - nullptr}, - {nullptr, nullptr, nullptr, nullptr, nullptr}}; + static PyGetSetDef getset[] + = {{"__dict__", PyObject_GenericGetDict, PyObject_GenericSetDict, nullptr, nullptr}, + {nullptr, nullptr, nullptr, nullptr, nullptr}}; type->tp_getset = getset; } @@ -579,7 +587,7 @@ extern "C" inline int pybind11_getbuffer(PyObject *obj, Py_buffer *view, int fla if (view) { view->obj = nullptr; } - PyErr_SetString(PyExc_BufferError, "pybind11_getbuffer(): Internal error"); + set_error(PyExc_BufferError, "pybind11_getbuffer(): Internal error"); return -1; } std::memset(view, 0, sizeof(Py_buffer)); @@ -587,7 +595,7 @@ 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 - PyErr_SetString(PyExc_BufferError, "Writable buffer requested for readonly storage"); + set_error(PyExc_BufferError, "Writable buffer requested for readonly storage"); return -1; } view->obj = obj; @@ -653,10 +661,13 @@ inline PyObject *make_new_python_type(const type_record &rec) { char *tp_doc = nullptr; if (rec.doc && options::show_user_defined_docstrings()) { - /* Allocate memory for docstring (using PyObject_MALLOC, since - Python will free this later on) */ + /* Allocate memory for docstring (Python will free this later on) */ size_t size = std::strlen(rec.doc) + 1; +#if PY_VERSION_HEX >= 0x030D0000 + tp_doc = (char *) PyMem_MALLOC(size); +#else tp_doc = (char *) PyObject_MALLOC(size); +#endif std::memcpy((void *) tp_doc, rec.doc, size); } diff --git a/wrap/pybind11/include/pybind11/detail/common.h b/wrap/pybind11/include/pybind11/detail/common.h index 31a54c773a..e37152a9a3 100644 --- a/wrap/pybind11/include/pybind11/detail/common.h +++ b/wrap/pybind11/include/pybind11/detail/common.h @@ -10,12 +10,12 @@ #pragma once #define PYBIND11_VERSION_MAJOR 2 -#define PYBIND11_VERSION_MINOR 11 +#define PYBIND11_VERSION_MINOR 13 #define PYBIND11_VERSION_PATCH 1 // Similar to Python's convention: https://docs.python.org/3/c-api/apiabiversion.html // Additional convention: 0xD = dev -#define PYBIND11_VERSION_HEX 0x020B0100 +#define PYBIND11_VERSION_HEX 0x020D0100 // Define some generic pybind11 helper macros for warning management. // @@ -118,6 +118,14 @@ # endif #endif +#if defined(PYBIND11_CPP20) +# define PYBIND11_CONSTINIT constinit +# define PYBIND11_DTOR_CONSTEXPR constexpr +#else +# define PYBIND11_CONSTINIT +# define PYBIND11_DTOR_CONSTEXPR +#endif + // Compiler version assertions #if defined(__INTEL_COMPILER) # if __INTEL_COMPILER < 1800 @@ -264,9 +272,8 @@ PYBIND11_WARNING_DISABLE_MSVC(4505) #endif #include -// Reminder: WITH_THREAD is always defined if PY_VERSION_HEX >= 0x03070000 -#if PY_VERSION_HEX < 0x03060000 -# error "PYTHON < 3.6 IS UNSUPPORTED. pybind11 v2.9 was the last to support Python 2 and 3.5." +#if PY_VERSION_HEX < 0x03070000 +# error "PYTHON < 3.7 IS UNSUPPORTED. pybind11 v2.12 was the last to support Python 3.6." #endif #include #include @@ -288,6 +295,10 @@ PYBIND11_WARNING_DISABLE_MSVC(4505) # undef copysign #endif +#if defined(PYBIND11_NUMPY_1_ONLY) +# define PYBIND11_INTERNAL_NUMPY_1_ONLY_DETECTED +#endif + #if defined(PYPY_VERSION) && !defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) # define PYBIND11_SIMPLE_GIL_MANAGEMENT #endif @@ -399,7 +410,7 @@ PYBIND11_WARNING_POP return nullptr; \ } \ catch (const std::exception &e) { \ - PyErr_SetString(PyExc_ImportError, e.what()); \ + ::pybind11::set_error(PyExc_ImportError, e.what()); \ return nullptr; \ } @@ -452,7 +463,7 @@ PYBIND11_WARNING_POP }); } \endrst */ -#define PYBIND11_MODULE(name, variable) \ +#define PYBIND11_MODULE(name, variable, ...) \ static ::pybind11::module_::module_def PYBIND11_CONCAT(pybind11_module_def_, name) \ PYBIND11_MAYBE_UNUSED; \ PYBIND11_MAYBE_UNUSED \ @@ -461,7 +472,10 @@ PYBIND11_WARNING_POP PYBIND11_CHECK_PYTHON_VERSION \ PYBIND11_ENSURE_INTERNALS_READY \ auto m = ::pybind11::module_::create_extension_module( \ - PYBIND11_TOSTRING(name), nullptr, &PYBIND11_CONCAT(pybind11_module_def_, name)); \ + PYBIND11_TOSTRING(name), \ + nullptr, \ + &PYBIND11_CONCAT(pybind11_module_def_, name), \ + ##__VA_ARGS__); \ try { \ PYBIND11_CONCAT(pybind11_init_, name)(m); \ return m.ptr(); \ @@ -913,8 +927,7 @@ using is_template_base_of = decltype(is_template_base_of_impl::check((intrinsic_t *) nullptr)); #else struct is_template_base_of - : decltype(is_template_base_of_impl::check((intrinsic_t *) nullptr)) { -}; + : decltype(is_template_base_of_impl::check((intrinsic_t *) nullptr)){}; #endif /// Check if T is an instantiation of the template `Class`. For example: @@ -1096,14 +1109,14 @@ struct overload_cast_impl { } template - 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 - 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; } }; diff --git a/wrap/pybind11/include/pybind11/detail/descr.h b/wrap/pybind11/include/pybind11/detail/descr.h index 635614b0d6..7d546311e7 100644 --- a/wrap/pybind11/include/pybind11/detail/descr.h +++ b/wrap/pybind11/include/pybind11/detail/descr.h @@ -156,8 +156,9 @@ constexpr auto concat(const descr &d, const Args &...args) { } #else template -constexpr auto concat(const descr &d, const Args &...args) - -> decltype(std::declval>() + concat(args...)) { +constexpr auto concat(const descr &d, + const Args &...args) -> decltype(std::declval>() + + concat(args...)) { return d + const_name(", ") + concat(args...); } #endif diff --git a/wrap/pybind11/include/pybind11/detail/init.h b/wrap/pybind11/include/pybind11/detail/init.h index e21171688c..4509bd131e 100644 --- a/wrap/pybind11/include/pybind11/detail/init.h +++ b/wrap/pybind11/include/pybind11/detail/init.h @@ -65,7 +65,7 @@ constexpr bool is_alias(void *) { } // Constructs and returns a new object; if the given arguments don't map to a constructor, we fall -// back to brace aggregate initiailization so that for aggregate initialization can be used with +// back to brace aggregate initialization so that for aggregate initialization can be used with // py::init, e.g. `py::init` to initialize a `struct T { int a; int b; }`. For // non-aggregate types, we need to use an ordinary T(...) constructor (invoking as `T{...}` usually // works, but will not do the expected thing when `T` has an `initializer_list` constructor). diff --git a/wrap/pybind11/include/pybind11/detail/internals.h b/wrap/pybind11/include/pybind11/detail/internals.h index aaa7f8686e..e61c1687fc 100644 --- a/wrap/pybind11/include/pybind11/detail/internals.h +++ b/wrap/pybind11/include/pybind11/detail/internals.h @@ -11,13 +11,15 @@ #include "common.h" -#if defined(WITH_THREAD) && defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) +#if defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) # include "../gil.h" #endif #include "../pytypes.h" #include +#include +#include /// Tracks the `internals` and `type_info` ABI version independent of the main library version. /// @@ -34,8 +36,9 @@ /// further ABI-incompatible changes may be made before the ABI is officially /// changed to the new version. #ifndef PYBIND11_INTERNALS_VERSION -# if PY_VERSION_HEX >= 0x030C0000 +# 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 @@ -61,60 +64,41 @@ inline PyObject *make_object_base_type(PyTypeObject *metaclass); // The old Python Thread Local Storage (TLS) API is deprecated in Python 3.7 in favor of the new // Thread Specific Storage (TSS) API. -#if PY_VERSION_HEX >= 0x03070000 // Avoid unnecessary allocation of `Py_tss_t`, since we cannot use // `Py_LIMITED_API` anyway. -# if PYBIND11_INTERNALS_VERSION > 4 -# define PYBIND11_TLS_KEY_REF Py_tss_t & -# if defined(__GNUC__) && !defined(__INTEL_COMPILER) -// Clang on macOS warns due to `Py_tss_NEEDS_INIT` not specifying an initializer -// for every field. -# 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)) +#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_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) +# 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 -// Usually an int but a long on Cygwin64 with Python 3.x -# define PYBIND11_TLS_KEY_REF decltype(PyThread_create_key()) -# define PYBIND11_TLS_KEY_INIT(var) PYBIND11_TLS_KEY_REF var = 0; -# define PYBIND11_TLS_KEY_CREATE(var) (((var) = PyThread_create_key()) != -1) -# define PYBIND11_TLS_GET_VALUE(key) PyThread_get_key_value((key)) -# if defined(PYPY_VERSION) -// On CPython < 3.4 and on PyPy, `PyThread_set_key_value` strangely does not set -// the value if it has already been set. Instead, it must first be deleted and -// then set again. -inline void tls_replace_value(PYBIND11_TLS_KEY_REF key, void *value) { - PyThread_delete_key_value(key); - PyThread_set_key_value(key, value); -} -# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_delete_key_value(key) -# define PYBIND11_TLS_REPLACE_VALUE(key, value) \ - ::pybind11::detail::tls_replace_value((key), (value)) -# else -# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_set_key_value((key), nullptr) -# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_set_key_value((key), (value)) -# endif -# define PYBIND11_TLS_FREE(key) (void) key +# 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 // Python loads modules by default with dlopen with the RTLD_LOCAL flag; under libc++ and possibly @@ -162,15 +146,33 @@ struct override_hash { } }; +using instance_map = std::unordered_multimap; + +// Instance map shards are used to reduce mutex contention in free-threaded Python. +struct instance_map_shard { + std::mutex mutex; + instance_map registered_instances; + // alignas(64) would be better, but causes compile errors in macOS before 10.14 (see #5200) + char padding[64 - (sizeof(std::mutex) + sizeof(instance_map)) % 64]; +}; + /// Internal data structure used to track registered instances and types. /// Whenever binary incompatible changes are made to this structure, /// `PYBIND11_INTERNALS_VERSION` must be incremented. struct internals { +#ifdef Py_GIL_DISABLED + std::mutex mutex; +#endif // std::type_index -> pybind11's type information type_map registered_types_cpp; // PyTypeObject* -> base type_info(s) std::unordered_map> registered_types_py; - std::unordered_multimap registered_instances; // void * -> instance* +#ifdef Py_GIL_DISABLED + std::unique_ptr instance_shards; // void * -> instance* + size_t instance_shards_mask; +#else + instance_map registered_instances; // void * -> instance* +#endif std::unordered_set, override_hash> inactive_override_cache; type_map> direct_conversions; @@ -186,28 +188,27 @@ struct internals { PyTypeObject *static_property_type; PyTypeObject *default_metaclass; PyObject *instance_base; -#if defined(WITH_THREAD) // Unused if PYBIND11_SIMPLE_GIL_MANAGEMENT is defined: PYBIND11_TLS_KEY_INIT(tstate) -# if PYBIND11_INTERNALS_VERSION > 4 +#if PYBIND11_INTERNALS_VERSION > 4 PYBIND11_TLS_KEY_INIT(loader_life_support_tls_key) -# endif // PYBIND11_INTERNALS_VERSION > 4 +#endif // PYBIND11_INTERNALS_VERSION > 4 // Unused if PYBIND11_SIMPLE_GIL_MANAGEMENT is defined: PyInterpreterState *istate = nullptr; -# if PYBIND11_INTERNALS_VERSION > 4 +#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 +#endif internals() = default; internals(const internals &other) = delete; internals &operator=(const internals &other) = delete; ~internals() { -# if PYBIND11_INTERNALS_VERSION > 4 +#if PYBIND11_INTERNALS_VERSION > 4 PYBIND11_TLS_FREE(loader_life_support_tls_key); -# endif // PYBIND11_INTERNALS_VERSION > 4 +#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 @@ -218,7 +219,6 @@ struct internals { // that the `tstate` be allocated with the CPython allocator. PYBIND11_TLS_FREE(tstate); } -#endif }; /// Additional type information which does not fit into the PyTypeObject. @@ -291,31 +291,30 @@ struct type_info { #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 -# if defined(WITH_THREAD) -# define PYBIND11_INTERNALS_KIND "" -# else -# define PYBIND11_INTERNALS_KIND "_without_thread" -# endif +# define PYBIND11_INTERNALS_KIND "" #endif #define PYBIND11_INTERNALS_ID \ "__pybind11_internals_v" PYBIND11_TOSTRING(PYBIND11_INTERNALS_VERSION) \ - PYBIND11_INTERNALS_KIND PYBIND11_COMPILER_TYPE PYBIND11_STDLIB PYBIND11_BUILD_ABI \ - PYBIND11_BUILD_TYPE "__" + PYBIND11_INTERNALS_KIND PYBIND11_COMPILER_TYPE PYBIND11_STDLIB \ + PYBIND11_BUILD_ABI PYBIND11_BUILD_TYPE "__" #define PYBIND11_MODULE_LOCAL_ID \ "__pybind11_module_local_v" PYBIND11_TOSTRING(PYBIND11_INTERNALS_VERSION) \ - PYBIND11_INTERNALS_KIND PYBIND11_COMPILER_TYPE PYBIND11_STDLIB PYBIND11_BUILD_ABI \ - PYBIND11_BUILD_TYPE "__" + PYBIND11_INTERNALS_KIND PYBIND11_COMPILER_TYPE PYBIND11_STDLIB \ + PYBIND11_BUILD_ABI PYBIND11_BUILD_TYPE "__" /// Each module locally stores a pointer to the `internals` data. The data /// itself is shared among modules with the same `PYBIND11_INTERNALS_ID`. @@ -352,7 +351,7 @@ inline bool raise_err(PyObject *exc_type, const char *msg) { raise_from(exc_type, msg); return true; } - PyErr_SetString(exc_type, msg); + set_error(exc_type, msg); return false; } @@ -447,22 +446,39 @@ inline object get_python_state_dict() { #endif if (!state_dict) { raise_from(PyExc_SystemError, "pybind11::detail::get_python_state_dict() FAILED"); + throw error_already_set(); } return state_dict; } inline object get_internals_obj_from_state_dict(handle state_dict) { - return reinterpret_borrow(dict_getitemstring(state_dict.ptr(), PYBIND11_INTERNALS_ID)); + return reinterpret_steal( + dict_getitemstringref(state_dict.ptr(), PYBIND11_INTERNALS_ID)); } inline internals **get_internals_pp_from_capsule(handle obj) { void *raw_ptr = PyCapsule_GetPointer(obj.ptr(), /*name=*/nullptr); if (raw_ptr == nullptr) { raise_from(PyExc_SystemError, "pybind11::detail::get_internals_pp_from_capsule() FAILED"); + throw error_already_set(); } return static_cast(raw_ptr); } +inline uint64_t round_up_to_next_pow2(uint64_t x) { + // Round-up to the next power of two. + // See https://graphics.stanford.edu/~seander/bithacks.html#RoundUpPowerOf2 + x--; + x |= (x >> 1); + x |= (x >> 2); + x |= (x >> 4); + x |= (x >> 8); + x |= (x >> 16); + x |= (x >> 32); + x++; + return x; +} + /// Return a reference to the current `internals` data PYBIND11_NOINLINE internals &get_internals() { auto **&internals_pp = get_internals_pp(); @@ -470,10 +486,9 @@ PYBIND11_NOINLINE internals &get_internals() { return **internals_pp; } -#if defined(WITH_THREAD) -# if defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) +#if defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) gil_scoped_acquire gil; -# else +#else // Ensure that the GIL is held since we will need to make Python calls. // Cannot use py::gil_scoped_acquire here since that constructor calls get_internals. struct gil_scoped_acquire_local { @@ -483,7 +498,6 @@ PYBIND11_NOINLINE internals &get_internals() { ~gil_scoped_acquire_local() { PyGILState_Release(state); } const PyGILState_STATE state; } gil; -# endif #endif error_scope err_scope; @@ -508,7 +522,6 @@ PYBIND11_NOINLINE internals &get_internals() { } auto *&internals_ptr = *internals_pp; internals_ptr = new internals(); -#if defined(WITH_THREAD) PyThreadState *tstate = PyThreadState_Get(); // NOLINTNEXTLINE(bugprone-assignment-in-if-condition) @@ -517,20 +530,29 @@ PYBIND11_NOINLINE internals &get_internals() { } PYBIND11_TLS_REPLACE_VALUE(internals_ptr->tstate, tstate); -# if PYBIND11_INTERNALS_VERSION > 4 +#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; #endif + internals_ptr->istate = tstate->interp; state_dict[PYBIND11_INTERNALS_ID] = capsule(internals_pp); internals_ptr->registered_exception_translators.push_front(&translate_exception); internals_ptr->static_property_type = make_static_property_type(); internals_ptr->default_metaclass = make_default_metaclass(); internals_ptr->instance_base = make_object_base_type(internals_ptr->default_metaclass); +#ifdef Py_GIL_DISABLED + // Scale proportional to the number of cores. 2x is a heuristic to reduce contention. + auto num_shards + = static_cast(round_up_to_next_pow2(2 * std::thread::hardware_concurrency())); + if (num_shards == 0) { + num_shards = 1; + } + internals_ptr->instance_shards.reset(new instance_map_shard[num_shards]); + internals_ptr->instance_shards_mask = num_shards - 1; +#endif // Py_GIL_DISABLED } return **internals_pp; } @@ -544,7 +566,7 @@ PYBIND11_NOINLINE internals &get_internals() { struct local_internals { type_map registered_types_cpp; std::forward_list registered_exception_translators; -#if defined(WITH_THREAD) && PYBIND11_INTERNALS_VERSION == 4 +#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 @@ -577,7 +599,7 @@ struct local_internals { loader_life_support_tls_key = static_cast(ptr)->loader_life_support_tls_key; } -#endif // defined(WITH_THREAD) && PYBIND11_INTERNALS_VERSION == 4 +#endif // PYBIND11_INTERNALS_VERSION == 4 }; /// Works like `get_internals`, but for things which are locally registered. @@ -591,13 +613,80 @@ inline local_internals &get_local_internals() { return *locals; } +#ifdef Py_GIL_DISABLED +# define PYBIND11_LOCK_INTERNALS(internals) std::unique_lock lock((internals).mutex) +#else +# define PYBIND11_LOCK_INTERNALS(internals) +#endif + +template +inline auto with_internals(const F &cb) -> decltype(cb(get_internals())) { + auto &internals = get_internals(); + PYBIND11_LOCK_INTERNALS(internals); + return cb(internals); +} + +inline std::uint64_t mix64(std::uint64_t z) { + // David Stafford's variant 13 of the MurmurHash3 finalizer popularized + // by the SplitMix PRNG. + // https://zimbry.blogspot.com/2011/09/better-bit-mixing-improving-on.html + z = (z ^ (z >> 30)) * 0xbf58476d1ce4e5b9; + z = (z ^ (z >> 27)) * 0x94d049bb133111eb; + return z ^ (z >> 31); +} + +template +inline auto with_instance_map(const void *ptr, + const F &cb) -> decltype(cb(std::declval())) { + auto &internals = get_internals(); + +#ifdef Py_GIL_DISABLED + // Hash address to compute shard, but ignore low bits. We'd like allocations + // from the same thread/core to map to the same shard and allocations from + // other threads/cores to map to other shards. Using the high bits is a good + // heuristic because memory allocators often have a per-thread + // arena/superblock/segment from which smaller allocations are served. + auto addr = reinterpret_cast(ptr); + auto hash = mix64(static_cast(addr >> 20)); + auto idx = static_cast(hash & internals.instance_shards_mask); + + auto &shard = internals.instance_shards[idx]; + std::unique_lock lock(shard.mutex); + return cb(shard.registered_instances); +#else + (void) ptr; + return cb(internals.registered_instances); +#endif +} + +// Returns the number of registered instances for testing purposes. The result may not be +// consistent if other threads are registering or unregistering instances concurrently. +inline size_t num_registered_instances() { + auto &internals = get_internals(); +#ifdef Py_GIL_DISABLED + size_t count = 0; + for (size_t i = 0; i <= internals.instance_shards_mask; ++i) { + auto &shard = internals.instance_shards[i]; + std::unique_lock lock(shard.mutex); + count += shard.registered_instances.size(); + } + return count; +#else + return internals.registered_instances.size(); +#endif +} + /// Constructs a std::string with the given arguments, stores it in `internals`, and returns its /// `c_str()`. Such strings objects have a long storage duration -- the internal strings are only /// cleared when the program exits or after interpreter shutdown (when embedding), and so are /// suitable for c-style strings needed by Python internals (such as PyTypeObject's tp_name). template const char *c_str(Args &&...args) { - auto &strings = get_internals().static_strings; + // GCC 4.8 doesn't like parameter unpack within lambda capture, so use + // PYBIND11_LOCK_INTERNALS. + auto &internals = get_internals(); + PYBIND11_LOCK_INTERNALS(internals); + auto &strings = internals.static_strings; strings.emplace_front(std::forward(args)...); return strings.front().c_str(); } @@ -627,15 +716,18 @@ PYBIND11_NAMESPACE_END(detail) /// pybind11 version) running in the current interpreter. Names starting with underscores /// are reserved for internal usage. Returns `nullptr` if no matching entry was found. PYBIND11_NOINLINE void *get_shared_data(const std::string &name) { - auto &internals = detail::get_internals(); - auto it = internals.shared_data.find(name); - return it != internals.shared_data.end() ? it->second : nullptr; + return detail::with_internals([&](detail::internals &internals) { + auto it = internals.shared_data.find(name); + return it != internals.shared_data.end() ? it->second : nullptr; + }); } /// Set the shared data that can be later recovered by `get_shared_data()`. PYBIND11_NOINLINE void *set_shared_data(const std::string &name, void *data) { - detail::get_internals().shared_data[name] = data; - return data; + return detail::with_internals([&](detail::internals &internals) { + internals.shared_data[name] = data; + return data; + }); } /// Returns a typed reference to a shared data entry (by using `get_shared_data()`) if @@ -643,14 +735,15 @@ PYBIND11_NOINLINE void *set_shared_data(const std::string &name, void *data) { /// added to the shared data under the given name and a reference to it is returned. template T &get_or_create_shared_data(const std::string &name) { - auto &internals = detail::get_internals(); - auto it = internals.shared_data.find(name); - T *ptr = (T *) (it != internals.shared_data.end() ? it->second : nullptr); - if (!ptr) { - ptr = new T(); - internals.shared_data[name] = ptr; - } - return *ptr; + return *detail::with_internals([&](detail::internals &internals) { + auto it = internals.shared_data.find(name); + T *ptr = (T *) (it != internals.shared_data.end() ? it->second : nullptr); + if (!ptr) { + ptr = new T(); + internals.shared_data[name] = ptr; + } + return ptr; + }); } PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/pybind11/include/pybind11/detail/type_caster_base.h b/wrap/pybind11/include/pybind11/detail/type_caster_base.h index 16387506cf..fd8c81b9ac 100644 --- a/wrap/pybind11/include/pybind11/detail/type_caster_base.h +++ b/wrap/pybind11/include/pybind11/detail/type_caster_base.h @@ -36,14 +36,13 @@ class loader_life_support { loader_life_support *parent = nullptr; std::unordered_set keep_alive; -#if defined(WITH_THREAD) // Store stack pointer in thread-local storage. static PYBIND11_TLS_KEY_REF get_stack_tls_key() { -# if PYBIND11_INTERNALS_VERSION == 4 +#if PYBIND11_INTERNALS_VERSION == 4 return get_local_internals().loader_life_support_tls_key; -# else +#else return get_internals().loader_life_support_tls_key; -# endif +#endif } static loader_life_support *get_stack_top() { return static_cast(PYBIND11_TLS_GET_VALUE(get_stack_tls_key())); @@ -51,15 +50,6 @@ class loader_life_support { static void set_stack_top(loader_life_support *value) { PYBIND11_TLS_REPLACE_VALUE(get_stack_tls_key(), value); } -#else - // Use single global variable for stack. - static loader_life_support **get_stack_pp() { - static loader_life_support *global_stack = nullptr; - return global_stack; - } - static loader_life_support *get_stack_top() { return *get_stack_pp(); } - static void set_stack_top(loader_life_support *value) { *get_stack_pp() = value; } -#endif public: /// A new patient frame is created when a function is entered @@ -102,8 +92,22 @@ class loader_life_support { inline std::pair all_type_info_get_cache(PyTypeObject *type); +// Band-aid workaround to fix a subtle but serious bug in a minimalistic fashion. See PR #4762. +inline void all_type_info_add_base_most_derived_first(std::vector &bases, + type_info *addl_base) { + for (auto it = bases.begin(); it != bases.end(); it++) { + type_info *existing_base = *it; + if (PyType_IsSubtype(addl_base->type, existing_base->type) != 0) { + bases.insert(it, addl_base); + return; + } + } + bases.push_back(addl_base); +} + // Populates a just-created cache entry. PYBIND11_NOINLINE void all_type_info_populate(PyTypeObject *t, std::vector &bases) { + assert(bases.empty()); std::vector check; for (handle parent : reinterpret_borrow(t->tp_bases)) { check.push_back((PyTypeObject *) parent.ptr()); @@ -136,7 +140,7 @@ PYBIND11_NOINLINE void all_type_info_populate(PyTypeObject *t, std::vectortp_bases) { @@ -203,12 +207,15 @@ inline detail::type_info *get_local_type_info(const std::type_index &tp) { } inline detail::type_info *get_global_type_info(const std::type_index &tp) { - auto &types = get_internals().registered_types_cpp; - auto it = types.find(tp); - if (it != types.end()) { - return it->second; - } - return nullptr; + return with_internals([&](internals &internals) { + detail::type_info *type_info = nullptr; + auto &types = internals.registered_types_cpp; + auto it = types.find(tp); + if (it != types.end()) { + type_info = it->second; + } + return type_info; + }); } /// Return the type info for a given C++ type; on lookup failure can either throw or return @@ -239,15 +246,17 @@ PYBIND11_NOINLINE handle get_type_handle(const std::type_info &tp, bool throw_if // 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) { - auto it_instances = get_internals().registered_instances.equal_range(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)) { - return handle((PyObject *) it_i->second).inc_ref(); + return with_instance_map(src, [&](instance_map &instances) { + auto it_instances = instances.equal_range(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)) { + return handle((PyObject *) it_i->second).inc_ref(); + } } } - } - return handle(); + return handle(); + }); } struct value_and_holder { @@ -322,18 +331,29 @@ struct values_and_holders { explicit values_and_holders(instance *inst) : inst{inst}, tinfo(all_type_info(Py_TYPE(inst))) {} + explicit values_and_holders(PyObject *obj) + : inst{nullptr}, tinfo(all_type_info(Py_TYPE(obj))) { + if (!tinfo.empty()) { + inst = reinterpret_cast(obj); + } + } + struct iterator { private: instance *inst = nullptr; const type_vec *types = nullptr; value_and_holder curr; friend struct values_and_holders; - iterator(instance *inst, const type_vec *tinfo) - : inst{inst}, types{tinfo}, - curr(inst /* instance */, - types->empty() ? nullptr : (*types)[0] /* type info */, - 0, /* vpos: (non-simple types only): the first vptr comes first */ - 0 /* index */) {} + iterator(instance *inst, const type_vec *tinfo) : inst{inst}, types{tinfo} { + if (inst != nullptr) { + assert(!types->empty()); + curr = value_and_holder( + inst /* instance */, + (*types)[0] /* type info */, + 0, /* vpos: (non-simple types only): the first vptr comes first */ + 0 /* index */); + } + } // Past-the-end iterator: explicit iterator(size_t end) : curr(end) {} @@ -364,6 +384,16 @@ struct values_and_holders { } size_t size() { return tinfo.size(); } + + // Band-aid workaround to fix a subtle but serious bug in a minimalistic fashion. See PR #4762. + bool is_redundant_value_and_holder(const value_and_holder &vh) { + for (size_t i = 0; i < vh.index; i++) { + if (PyType_IsSubtype(tinfo[i]->type, tinfo[vh.index]->type) != 0) { + return true; + } + } + return false; + } }; /** @@ -471,23 +501,26 @@ PYBIND11_NOINLINE bool isinstance_generic(handle obj, const std::type_info &tp) } PYBIND11_NOINLINE handle get_object_handle(const void *ptr, const detail::type_info *type) { - auto &instances = get_internals().registered_instances; - auto range = instances.equal_range(ptr); - for (auto it = range.first; it != range.second; ++it) { - for (const auto &vh : values_and_holders(it->second)) { - if (vh.type == type) { - return handle((PyObject *) it->second); + return with_instance_map(ptr, [&](instance_map &instances) { + auto range = instances.equal_range(ptr); + for (auto it = range.first; it != range.second; ++it) { + for (const auto &vh : values_and_holders(it->second)) { + if (vh.type == type) { + return handle((PyObject *) it->second); + } } } - } - return handle(); + return handle(); + }); } inline PyThreadState *get_thread_state_unchecked() { #if defined(PYPY_VERSION) return PyThreadState_GET(); -#else +#elif PY_VERSION_HEX < 0x030D0000 return _PyThreadState_UncheckedGet(); +#else + return PyThreadState_GetUnchecked(); #endif } @@ -786,7 +819,7 @@ class type_caster_generic { std::string tname = rtti_type ? rtti_type->name() : cast_type.name(); detail::clean_type_id(tname); std::string msg = "Unregistered type : " + tname; - PyErr_SetString(PyExc_TypeError, msg.c_str()); + set_error(PyExc_TypeError, msg.c_str()); return {nullptr, nullptr}; } @@ -1074,11 +1107,11 @@ class type_caster_base : public type_caster_generic { || policy == return_value_policy::automatic_reference) { policy = return_value_policy::copy; } - return cast(&src, policy, parent); + return cast(std::addressof(src), policy, parent); } static handle cast(itype &&src, return_value_policy, handle parent) { - return cast(&src, return_value_policy::move, parent); + return cast(std::addressof(src), return_value_policy::move, parent); } // Returns a (pointer, type_info) pair taking care of necessary type lookup for a @@ -1147,14 +1180,14 @@ class type_caster_base : public type_caster_generic { 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 ::value>> - static auto make_copy_constructor(const T *) - -> decltype(new T(std::declval()), Constructor{}) { + static auto make_copy_constructor(const T *) -> decltype(new T(std::declval()), + Constructor{}) { return [](const void *arg) -> void * { return new T(*reinterpret_cast(arg)); }; } template ::value>> - static auto make_move_constructor(const T *) - -> decltype(new T(std::declval()), Constructor{}) { + static auto make_move_constructor(const T *) -> decltype(new T(std::declval()), + Constructor{}) { return [](const void *arg) -> void * { return new T(std::move(*const_cast(reinterpret_cast(arg)))); }; @@ -1164,13 +1197,17 @@ class type_caster_base : public type_caster_generic { static Constructor make_move_constructor(...) { return nullptr; } }; +inline std::string quote_cpp_type_name(const std::string &cpp_type_name) { + return cpp_type_name; // No-op for now. See PR #4888 +} + PYBIND11_NOINLINE std::string type_info_description(const std::type_info &ti) { if (auto *type_data = get_type_info(ti)) { handle th((PyObject *) type_data->type); return th.attr("__module__").cast() + '.' + th.attr("__qualname__").cast(); } - return clean_type_id(ti.name()); + return quote_cpp_type_name(clean_type_id(ti.name())); } PYBIND11_NAMESPACE_END(detail) diff --git a/wrap/pybind11/include/pybind11/eigen/tensor.h b/wrap/pybind11/include/pybind11/eigen/tensor.h index 25d12baca1..d4ed6c0ca8 100644 --- a/wrap/pybind11/include/pybind11/eigen/tensor.h +++ b/wrap/pybind11/include/pybind11/eigen/tensor.h @@ -70,7 +70,7 @@ struct eigen_tensor_helper struct helper> { - static constexpr auto value = concat(const_name(((void) Is, "?"))...); + static constexpr auto value = ::pybind11::detail::concat(const_name(((void) Is, "?"))...); }; static constexpr auto dimensions_descriptor @@ -104,7 +104,8 @@ struct eigen_tensor_helper< return get_shape() == shape; } - static constexpr auto dimensions_descriptor = concat(const_name()...); + static constexpr auto dimensions_descriptor + = ::pybind11::detail::concat(const_name()...); template static Type *alloc(Args &&...args) { diff --git a/wrap/pybind11/include/pybind11/embed.h b/wrap/pybind11/include/pybind11/embed.h index caa14f4a05..9d29eb8249 100644 --- a/wrap/pybind11/include/pybind11/embed.h +++ b/wrap/pybind11/include/pybind11/embed.h @@ -103,9 +103,6 @@ inline void initialize_interpreter_pre_pyconfig(bool init_signal_handlers, bool add_program_dir_to_path) { detail::precheck_interpreter(); Py_InitializeEx(init_signal_handlers ? 1 : 0); -# if defined(WITH_THREAD) && PY_VERSION_HEX < 0x03070000 - PyEval_InitThreads(); -# endif // 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. diff --git a/wrap/pybind11/include/pybind11/functional.h b/wrap/pybind11/include/pybind11/functional.h index 87ec4d10cb..6856119cde 100644 --- a/wrap/pybind11/include/pybind11/functional.h +++ b/wrap/pybind11/include/pybind11/functional.h @@ -128,7 +128,8 @@ struct type_caster> { } PYBIND11_TYPE_CASTER(type, - const_name("Callable[[") + concat(make_caster::name...) + const_name("Callable[[") + + ::pybind11::detail::concat(make_caster::name...) + const_name("], ") + make_caster::name + const_name("]")); }; diff --git a/wrap/pybind11/include/pybind11/gil.h b/wrap/pybind11/include/pybind11/gil.h index 570a5581d5..6b0edaee4e 100644 --- a/wrap/pybind11/include/pybind11/gil.h +++ b/wrap/pybind11/include/pybind11/gil.h @@ -11,7 +11,9 @@ #include "detail/common.h" -#if defined(WITH_THREAD) && !defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) +#include + +#if !defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) # include "detail/internals.h" #endif @@ -24,9 +26,7 @@ PyThreadState *get_thread_state_unchecked(); PYBIND11_NAMESPACE_END(detail) -#if defined(WITH_THREAD) - -# if !defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) +#if !defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) /* The functions below essentially reproduce the PyGILState_* API using a RAII * pattern, but there are a few important differences: @@ -67,11 +67,11 @@ class gil_scoped_acquire { if (!tstate) { tstate = PyThreadState_New(internals.istate); -# if defined(PYBIND11_DETAILED_ERROR_MESSAGES) +# if defined(PYBIND11_DETAILED_ERROR_MESSAGES) if (!tstate) { pybind11_fail("scoped_acquire: could not create thread state!"); } -# endif +# endif tstate->gilstate_counter = 0; PYBIND11_TLS_REPLACE_VALUE(internals.tstate, tstate); } else { @@ -92,20 +92,20 @@ class gil_scoped_acquire { PYBIND11_NOINLINE void dec_ref() { --tstate->gilstate_counter; -# if defined(PYBIND11_DETAILED_ERROR_MESSAGES) +# if defined(PYBIND11_DETAILED_ERROR_MESSAGES) if (detail::get_thread_state_unchecked() != tstate) { pybind11_fail("scoped_acquire::dec_ref(): thread state must be current!"); } if (tstate->gilstate_counter < 0) { pybind11_fail("scoped_acquire::dec_ref(): reference count underflow!"); } -# endif +# endif if (tstate->gilstate_counter == 0) { -# if defined(PYBIND11_DETAILED_ERROR_MESSAGES) +# if defined(PYBIND11_DETAILED_ERROR_MESSAGES) if (!release) { pybind11_fail("scoped_acquire::dec_ref(): internal error!"); } -# endif +# endif PyThreadState_Clear(tstate); if (active) { PyThreadState_DeleteCurrent(); @@ -137,7 +137,9 @@ class gil_scoped_acquire { class gil_scoped_release { public: + // PRECONDITION: The GIL must be held when this constructor is called. explicit gil_scoped_release(bool disassoc = false) : disassoc(disassoc) { + assert(PyGILState_Check()); // `get_internals()` must be called here unconditionally in order to initialize // `internals.tstate` for subsequent `gil_scoped_acquire` calls. Otherwise, an // initialization race could occur as multiple threads try `gil_scoped_acquire`. @@ -184,7 +186,7 @@ class gil_scoped_release { bool active = true; }; -# else // PYBIND11_SIMPLE_GIL_MANAGEMENT +#else // PYBIND11_SIMPLE_GIL_MANAGEMENT class gil_scoped_acquire { PyGILState_STATE state; @@ -201,39 +203,17 @@ class gil_scoped_release { PyThreadState *state; public: - gil_scoped_release() : state{PyEval_SaveThread()} {} - gil_scoped_release(const gil_scoped_release &) = delete; - gil_scoped_release &operator=(const gil_scoped_release &) = delete; - ~gil_scoped_release() { PyEval_RestoreThread(state); } - void disarm() {} -}; - -# endif // PYBIND11_SIMPLE_GIL_MANAGEMENT - -#else // WITH_THREAD - -class gil_scoped_acquire { -public: - gil_scoped_acquire() { - // Trick to suppress `unused variable` error messages (at call sites). - (void) (this != (this + 1)); - } - gil_scoped_acquire(const gil_scoped_acquire &) = delete; - gil_scoped_acquire &operator=(const gil_scoped_acquire &) = delete; - void disarm() {} -}; - -class gil_scoped_release { -public: + // PRECONDITION: The GIL must be held when this constructor is called. gil_scoped_release() { - // Trick to suppress `unused variable` error messages (at call sites). - (void) (this != (this + 1)); + assert(PyGILState_Check()); + state = PyEval_SaveThread(); } gil_scoped_release(const gil_scoped_release &) = delete; gil_scoped_release &operator=(const gil_scoped_release &) = delete; + ~gil_scoped_release() { PyEval_RestoreThread(state); } void disarm() {} }; -#endif // WITH_THREAD +#endif // PYBIND11_SIMPLE_GIL_MANAGEMENT PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/pybind11/include/pybind11/gil_safe_call_once.h b/wrap/pybind11/include/pybind11/gil_safe_call_once.h new file mode 100644 index 0000000000..eaf84d16e8 --- /dev/null +++ b/wrap/pybind11/include/pybind11/gil_safe_call_once.h @@ -0,0 +1,91 @@ +// Copyright (c) 2023 The pybind Community. + +#pragma once + +#include "detail/common.h" +#include "gil.h" + +#include +#include + +PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +// Use the `gil_safe_call_once_and_store` class below instead of the naive +// +// static auto imported_obj = py::module_::import("module_name"); // BAD, DO NOT USE! +// +// which has two serious issues: +// +// 1. Py_DECREF() calls potentially after the Python interpreter was finalized already, and +// 2. deadlocks in multi-threaded processes (because of missing lock ordering). +// +// The following alternative avoids both problems: +// +// PYBIND11_CONSTINIT static py::gil_safe_call_once_and_store storage; +// auto &imported_obj = storage // Do NOT make this `static`! +// .call_once_and_store_result([]() { +// return py::module_::import("module_name"); +// }) +// .get_stored(); +// +// The parameter of `call_once_and_store_result()` must be callable. It can make +// CPython API calls, and in particular, it can temporarily release the GIL. +// +// `T` can be any C++ type, it does not have to involve CPython API types. +// +// The behavior with regard to signals, e.g. `SIGINT` (`KeyboardInterrupt`), +// is not ideal. If the main thread is the one to actually run the `Callable`, +// then a `KeyboardInterrupt` will interrupt it if it is running normal Python +// code. The situation is different if a non-main thread runs the +// `Callable`, and then the main thread starts waiting for it to complete: +// a `KeyboardInterrupt` will not interrupt the non-main thread, but it will +// 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. +template +class gil_safe_call_once_and_store { +public: + // PRECONDITION: The GIL must be held when `call_once_and_store_result()` is called. + template + gil_safe_call_once_and_store &call_once_and_store_result(Callable &&fn) { + if (!is_initialized_) { // This read is guarded by the GIL. + // Multiple threads may enter here, because the GIL is released in the next line and + // CPython API calls in the `fn()` call below may release and reacquire the GIL. + gil_scoped_release gil_rel; // Needed to establish lock ordering. + std::call_once(once_flag_, [&] { + // Only one thread will ever enter here. + gil_scoped_acquire gil_acq; + ::new (storage_) T(fn()); // fn may release, but will reacquire, the GIL. + is_initialized_ = true; // This write is guarded by the GIL. + }); + // All threads will observe `is_initialized_` as true here. + } + // Intentionally not returning `T &` to ensure the calling code is self-documenting. + return *this; + } + + // This must only be called after `call_once_and_store_result()` was called. + T &get_stored() { + assert(is_initialized_); + PYBIND11_WARNING_PUSH +#if !defined(__clang__) && defined(__GNUC__) && __GNUC__ < 5 + // Needed for gcc 4.8.5 + PYBIND11_WARNING_DISABLE_GCC("-Wstrict-aliasing") +#endif + return *reinterpret_cast(storage_); + PYBIND11_WARNING_POP + } + + constexpr gil_safe_call_once_and_store() = default; + PYBIND11_DTOR_CONSTEXPR ~gil_safe_call_once_and_store() = default; + +private: + alignas(T) char storage_[sizeof(T)] = {}; + std::once_flag once_flag_ = {}; + bool is_initialized_ = false; + // The `is_initialized_`-`storage_` pair is very similar to `std::optional`, + // but the latter does not have the triviality properties of former, + // therefore `std::optional` is not a viable alternative here. +}; + +PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/pybind11/include/pybind11/numpy.h b/wrap/pybind11/include/pybind11/numpy.h index 36077ec04d..05ef3918b1 100644 --- a/wrap/pybind11/include/pybind11/numpy.h +++ b/wrap/pybind11/include/pybind11/numpy.h @@ -10,7 +10,10 @@ #pragma once #include "pybind11.h" +#include "detail/common.h" #include "complex.h" +#include "gil_safe_call_once.h" +#include "pytypes.h" #include #include @@ -26,10 +29,15 @@ #include #include +#if defined(PYBIND11_NUMPY_1_ONLY) && !defined(PYBIND11_INTERNAL_NUMPY_1_ONLY_DETECTED) +# error PYBIND11_NUMPY_1_ONLY must be defined before any pybind11 header is included. +#endif + /* This will be true on all flat address space platforms and allows us to reduce the whole npy_intp / ssize_t / Py_intptr_t business down to just ssize_t for all size and dimension types (e.g. shape, strides, indexing), instead of inflicting this - upon the library user. */ + upon the library user. + Note that NumPy 2 now uses ssize_t for `npy_intp` to simplify this. */ static_assert(sizeof(::pybind11::ssize_t) == sizeof(Py_intptr_t), "ssize_t != Py_intptr_t"); static_assert(std::is_signed::value, "Py_intptr_t must be signed"); // We now can reinterpret_cast between py::ssize_t and Py_intptr_t (MSVC + PyPy cares) @@ -38,10 +46,16 @@ PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) PYBIND11_WARNING_DISABLE_MSVC(4127) +class dtype; // Forward declaration class array; // Forward declaration PYBIND11_NAMESPACE_BEGIN(detail) +template <> +struct handle_type_name { + static constexpr auto name = const_name("numpy.dtype"); +}; + template <> struct handle_type_name { static constexpr auto name = const_name("numpy.ndarray"); @@ -50,7 +64,8 @@ struct handle_type_name { template struct npy_format_descriptor; -struct PyArrayDescr_Proxy { +/* NumPy 1 proxy (always includes legacy fields) */ +struct PyArrayDescr1_Proxy { PyObject_HEAD PyObject *typeobj; char kind; @@ -65,6 +80,43 @@ struct PyArrayDescr_Proxy { PyObject *names; }; +#ifndef PYBIND11_NUMPY_1_ONLY +struct PyArrayDescr_Proxy { + PyObject_HEAD + PyObject *typeobj; + char kind; + char type; + char byteorder; + char _former_flags; + int type_num; + /* Additional fields are NumPy version specific. */ +}; +#else +/* NumPy 1.x only, we can expose all fields */ +using PyArrayDescr_Proxy = PyArrayDescr1_Proxy; +#endif + +/* NumPy 2 proxy, including legacy fields */ +struct PyArrayDescr2_Proxy { + PyObject_HEAD + PyObject *typeobj; + char kind; + char type; + char byteorder; + char _former_flags; + int type_num; + std::uint64_t flags; + ssize_t elsize; + ssize_t alignment; + PyObject *metadata; + Py_hash_t hash; + void *reserved_null[2]; + /* The following fields only exist if 0 <= type_num < 2056 */ + char *subarray; + PyObject *fields; + PyObject *names; +}; + struct PyArray_Proxy { PyObject_HEAD char *data; @@ -120,6 +172,28 @@ inline numpy_internals &get_numpy_internals() { return *ptr; } +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(); + +#ifdef PYBIND11_NUMPY_1_ONLY + if (major_version >= 2) { + throw std::runtime_error( + "This extension was built with PYBIND11_NUMPY_1_ONLY defined, " + "but NumPy 2 is used in this process. For NumPy2 compatibility, " + "this extension needs to be rebuilt without the PYBIND11_NUMPY_1_ONLY define."); + } +#endif + /* `numpy.core` was renamed to `numpy._core` in NumPy 2.0 as it officially + became a private module. */ + std::string numpy_core_path = major_version >= 2 ? "numpy._core" : "numpy.core"; + return module_::import((numpy_core_path + "." + submodule_name).c_str()); +} + template struct same_size { template @@ -186,14 +260,16 @@ struct npy_api { NPY_ULONG_, NPY_ULONGLONG_, NPY_UINT_), }; + unsigned int PyArray_RUNTIME_VERSION_; + struct PyArray_Dims { Py_intptr_t *ptr; int len; }; static npy_api &get() { - static npy_api api = lookup(); - return api; + PYBIND11_CONSTINIT static gil_safe_call_once_and_store storage; + return storage.call_once_and_store_result(lookup).get_stored(); } bool PyArray_Check_(PyObject *obj) const { @@ -224,6 +300,7 @@ struct npy_api { PyObject *(*PyArray_FromAny_)(PyObject *, PyObject *, int, int, int, PyObject *); int (*PyArray_DescrConverter_)(PyObject *, PyObject **); bool (*PyArray_EquivTypes_)(PyObject *, PyObject *); +#ifdef PYBIND11_NUMPY_1_ONLY int (*PyArray_GetArrayParamsFromObject_)(PyObject *, PyObject *, unsigned char, @@ -232,6 +309,7 @@ struct npy_api { Py_intptr_t *, PyObject **, PyObject *); +#endif PyObject *(*PyArray_Squeeze_)(PyObject *); // Unused. Not removed because that affects ABI of the class. int (*PyArray_SetBaseObject_)(PyObject *, PyObject *); @@ -249,7 +327,8 @@ struct npy_api { API_PyArray_DescrFromScalar = 57, API_PyArray_FromAny = 69, API_PyArray_Resize = 80, - API_PyArray_CopyInto = 82, + // CopyInto was slot 82 and 50 was effectively an alias. NumPy 2 removed 82. + API_PyArray_CopyInto = 50, API_PyArray_NewCopy = 85, API_PyArray_NewFromDescr = 94, API_PyArray_DescrNewFromType = 96, @@ -258,18 +337,25 @@ struct npy_api { API_PyArray_View = 137, API_PyArray_DescrConverter = 174, API_PyArray_EquivTypes = 182, +#ifdef PYBIND11_NUMPY_1_ONLY API_PyArray_GetArrayParamsFromObject = 278, +#endif API_PyArray_SetBaseObject = 282 }; static npy_api lookup() { - module_ m = module_::import("numpy.core.multiarray"); + module_ m = detail::import_numpy_core_submodule("multiarray"); auto c = m.attr("_ARRAY_API"); void **api_ptr = (void **) PyCapsule_GetPointer(c.ptr(), nullptr); + if (api_ptr == nullptr) { + raise_from(PyExc_SystemError, "FAILURE obtaining numpy _ARRAY_API pointer."); + throw error_already_set(); + } npy_api api; #define DECL_NPY_API(Func) api.Func##_ = (decltype(api.Func##_)) api_ptr[API_##Func]; DECL_NPY_API(PyArray_GetNDArrayCFeatureVersion); - if (api.PyArray_GetNDArrayCFeatureVersion_() < 0x7) { + api.PyArray_RUNTIME_VERSION_ = api.PyArray_GetNDArrayCFeatureVersion_(); + if (api.PyArray_RUNTIME_VERSION_ < 0x7) { pybind11_fail("pybind11 numpy support requires numpy >= 1.7.0"); } DECL_NPY_API(PyArray_Type); @@ -288,7 +374,9 @@ struct npy_api { DECL_NPY_API(PyArray_View); DECL_NPY_API(PyArray_DescrConverter); DECL_NPY_API(PyArray_EquivTypes); +#ifdef PYBIND11_NUMPY_1_ONLY DECL_NPY_API(PyArray_GetArrayParamsFromObject); +#endif DECL_NPY_API(PyArray_SetBaseObject); #undef DECL_NPY_API @@ -310,6 +398,14 @@ inline const PyArrayDescr_Proxy *array_descriptor_proxy(const PyObject *ptr) { return reinterpret_cast(ptr); } +inline const PyArrayDescr1_Proxy *array_descriptor1_proxy(const PyObject *ptr) { + return reinterpret_cast(ptr); +} + +inline const PyArrayDescr2_Proxy *array_descriptor2_proxy(const PyObject *ptr) { + return reinterpret_cast(ptr); +} + inline bool check_flags(const void *ptr, int flag) { return (flag == (array_proxy(ptr)->flags & flag)); } @@ -350,7 +446,7 @@ struct array_info> { } static constexpr auto extents = const_name::is_array>( - concat(const_name(), array_info::extents), const_name()); + ::pybind11::detail::concat(const_name(), array_info::extents), const_name()); }; // For numpy we have special handling for arrays of characters, so we don't include // the size in the array extents. @@ -589,10 +685,32 @@ class dtype : public object { } /// Size of the data type in bytes. +#ifdef PYBIND11_NUMPY_1_ONLY ssize_t itemsize() const { return detail::array_descriptor_proxy(m_ptr)->elsize; } +#else + ssize_t itemsize() const { + if (detail::npy_api::get().PyArray_RUNTIME_VERSION_ < 0x12) { + return detail::array_descriptor1_proxy(m_ptr)->elsize; + } + return detail::array_descriptor2_proxy(m_ptr)->elsize; + } +#endif /// Returns true for structured data types. +#ifdef PYBIND11_NUMPY_1_ONLY bool has_fields() const { return detail::array_descriptor_proxy(m_ptr)->names != nullptr; } +#else + bool has_fields() const { + if (detail::npy_api::get().PyArray_RUNTIME_VERSION_ < 0x12) { + return detail::array_descriptor1_proxy(m_ptr)->names != nullptr; + } + const auto *proxy = detail::array_descriptor2_proxy(m_ptr); + if (proxy->type_num < 0 || proxy->type_num >= 2056) { + return false; + } + return proxy->names != nullptr; + } +#endif /// Single-character code for dtype's kind. /// For example, floating point types are 'f' and integral types are 'i'. @@ -618,20 +736,39 @@ class dtype : public object { /// Single character for byteorder char byteorder() const { return detail::array_descriptor_proxy(m_ptr)->byteorder; } - /// Alignment of the data type +/// Alignment of the data type +#ifdef PYBIND11_NUMPY_1_ONLY int alignment() const { return detail::array_descriptor_proxy(m_ptr)->alignment; } +#else + ssize_t alignment() const { + if (detail::npy_api::get().PyArray_RUNTIME_VERSION_ < 0x12) { + return detail::array_descriptor1_proxy(m_ptr)->alignment; + } + return detail::array_descriptor2_proxy(m_ptr)->alignment; + } +#endif - /// Flags for the array descriptor +/// Flags for the array descriptor +#ifdef PYBIND11_NUMPY_1_ONLY char flags() const { return detail::array_descriptor_proxy(m_ptr)->flags; } +#else + std::uint64_t flags() const { + if (detail::npy_api::get().PyArray_RUNTIME_VERSION_ < 0x12) { + return (unsigned char) detail::array_descriptor1_proxy(m_ptr)->flags; + } + return detail::array_descriptor2_proxy(m_ptr)->flags; + } +#endif private: - static object _dtype_from_pep3118() { - static PyObject *obj = module_::import("numpy.core._internal") - .attr("_dtype_from_pep3118") - .cast() - .release() - .ptr(); - return reinterpret_borrow(obj); + static object &_dtype_from_pep3118() { + PYBIND11_CONSTINIT static gil_safe_call_once_and_store storage; + return storage + .call_once_and_store_result([]() { + return detail::import_numpy_core_submodule("_internal") + .attr("_dtype_from_pep3118"); + }) + .get_stored(); } dtype strip_padding(ssize_t itemsize) { @@ -788,9 +925,7 @@ class array : public buffer { } /// Byte size of a single element - ssize_t itemsize() const { - return detail::array_descriptor_proxy(detail::array_proxy(m_ptr)->descr)->elsize; - } + ssize_t itemsize() const { return dtype().itemsize(); } /// Total number of bytes ssize_t nbytes() const { return size() * itemsize(); } @@ -1008,7 +1143,7 @@ class array : public buffer { /// Create array from any object -- always returns a new reference static PyObject *raw_array(PyObject *ptr, int ExtraFlags = 0) { if (ptr == nullptr) { - PyErr_SetString(PyExc_ValueError, "cannot create a pybind11::array from a nullptr"); + set_error(PyExc_ValueError, "cannot create a pybind11::array from a nullptr"); return nullptr; } return detail::npy_api::get().PyArray_FromAny_( @@ -1155,7 +1290,7 @@ class array_t : public array { /// Create array from any object -- always returns a new reference static PyObject *raw_array_t(PyObject *ptr) { if (ptr == nullptr) { - PyErr_SetString(PyExc_ValueError, "cannot create a pybind11::array_t from a nullptr"); + set_error(PyExc_ValueError, "cannot create a pybind11::array_t from a nullptr"); return nullptr; } return detail::npy_api::get().PyArray_FromAny_(ptr, @@ -1418,7 +1553,9 @@ PYBIND11_NOINLINE void register_structured_dtype(any_container auto tindex = std::type_index(tinfo); numpy_internals.registered_dtypes[tindex] = {dtype_ptr, std::move(format_str)}; - get_internals().direct_conversions[tindex].push_back(direct_converter); + with_internals([tindex, &direct_converter](internals &internals) { + internals.direct_conversions[tindex].push_back(direct_converter); + }); } template diff --git a/wrap/pybind11/include/pybind11/pybind11.h b/wrap/pybind11/include/pybind11/pybind11.h index 3bce1a01ba..74919a7d52 100644 --- a/wrap/pybind11/include/pybind11/pybind11.h +++ b/wrap/pybind11/include/pybind11/pybind11.h @@ -14,7 +14,9 @@ #include "detail/init.h" #include "attr.h" #include "gil.h" +#include "gil_safe_call_once.h" #include "options.h" +#include "typing.h" #include #include @@ -52,6 +54,47 @@ PYBIND11_WARNING_DISABLE_MSVC(4127) PYBIND11_NAMESPACE_BEGIN(detail) +inline std::string replace_newlines_and_squash(const char *text) { + const char *whitespaces = " \t\n\r\f\v"; + std::string result(text); + bool previous_is_whitespace = false; + + if (result.size() >= 2) { + // Do not modify string representations + char first_char = result[0]; + char last_char = result[result.size() - 1]; + if (first_char == last_char && first_char == '\'') { + return result; + } + } + result.clear(); + + // Replace characters in whitespaces array with spaces and squash consecutive spaces + while (*text != '\0') { + if (std::strchr(whitespaces, *text)) { + if (!previous_is_whitespace) { + result += ' '; + previous_is_whitespace = true; + } + } else { + result += *text; + previous_is_whitespace = false; + } + ++text; + } + + // Strip leading and trailing whitespaces + const size_t str_begin = result.find_first_not_of(whitespaces); + if (str_begin == std::string::npos) { + return ""; + } + + const size_t str_end = result.find_last_not_of(whitespaces); + const size_t str_range = str_end - str_begin + 1; + + return result.substr(str_begin, str_range); +} + // Apply all the extensions translators from a list // Return true if one of the translators completed without raising an exception // itself. Return of false indicates that if there are other translators @@ -424,7 +467,7 @@ class cpp_function : public function { // Write default value if available. if (!is_starred && arg_index < rec->args.size() && rec->args[arg_index].descr) { signature += " = "; - signature += rec->args[arg_index].descr; + signature += detail::replace_newlines_and_squash(rec->args[arg_index].descr); } // Separator for positional-only arguments (placed after the // argument, rather than before like * @@ -449,9 +492,7 @@ class cpp_function : public function { signature += rec->scope.attr("__module__").cast() + "." + rec->scope.attr("__qualname__").cast(); } else { - std::string tname(t->name()); - detail::clean_type_id(tname); - signature += tname; + signature += detail::quote_cpp_type_name(detail::clean_type_id(t->name())); } } else { signature += c; @@ -680,7 +721,7 @@ class cpp_function : public function { /* Iterator over the list of potentially admissible overloads */ const function_record *overloads = reinterpret_cast( PyCapsule_GetPointer(self, get_function_record_capsule_name())), - *it = overloads; + *current_overload = overloads; assert(overloads != nullptr); /* Need to know how many arguments + keyword arguments there are to pick the right @@ -694,9 +735,8 @@ class cpp_function : public function { if (overloads->is_constructor) { if (!parent || !PyObject_TypeCheck(parent.ptr(), (PyTypeObject *) overloads->scope.ptr())) { - PyErr_SetString( - PyExc_TypeError, - "__init__(self, ...) called with invalid or missing `self` argument"); + set_error(PyExc_TypeError, + "__init__(self, ...) called with invalid or missing `self` argument"); return nullptr; } @@ -719,9 +759,10 @@ class cpp_function : public function { std::vector second_pass; // However, if there are no overloads, we can just skip the no-convert pass entirely - const bool overloaded = it != nullptr && it->next != nullptr; + const bool overloaded + = current_overload != nullptr && current_overload->next != nullptr; - for (; it != nullptr; it = it->next) { + for (; current_overload != nullptr; current_overload = current_overload->next) { /* For each overload: 1. Copy all positional arguments we were given, also checking to make sure that @@ -742,7 +783,7 @@ class cpp_function : public function { a result other than PYBIND11_TRY_NEXT_OVERLOAD. */ - const function_record &func = *it; + const function_record &func = *current_overload; size_t num_args = func.nargs; // Number of positional arguments that we need if (func.has_args) { --num_args; // (but don't count py::args @@ -980,10 +1021,10 @@ class cpp_function : public function { } if (result.ptr() != PYBIND11_TRY_NEXT_OVERLOAD) { - // The error reporting logic below expects 'it' to be valid, as it would be - // if we'd encountered this failure in the first-pass loop. + // The error reporting logic below expects 'current_overload' to be valid, + // as it would be if we'd encountered this failure in the first-pass loop. if (!result) { - it = &call.func; + current_overload = &call.func; } break; } @@ -1007,24 +1048,30 @@ class cpp_function : public function { A translator may choose to do one of the following: - - catch the exception and call PyErr_SetString or PyErr_SetObject + - catch the exception and call py::set_error() to set a standard (or custom) Python exception, or - do nothing and let the exception fall through to the next translator, or - delegate translation to the next translator by throwing a new type of exception. */ - auto &local_exception_translators - = get_local_internals().registered_exception_translators; - if (detail::apply_exception_translators(local_exception_translators)) { - return nullptr; - } - auto &exception_translators = get_internals().registered_exception_translators; - if (detail::apply_exception_translators(exception_translators)) { + 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) { return nullptr; } - PyErr_SetString(PyExc_SystemError, - "Exception escaped from default exception translator!"); + set_error(PyExc_SystemError, "Exception escaped from default exception translator!"); return nullptr; } @@ -1102,7 +1149,7 @@ class cpp_function : public function { } msg += "kwargs: "; bool first = true; - for (auto kwarg : kwargs) { + for (const auto &kwarg : kwargs) { if (first) { first = false; } else { @@ -1125,20 +1172,21 @@ class cpp_function : public function { raise_from(PyExc_TypeError, msg.c_str()); return nullptr; } - PyErr_SetString(PyExc_TypeError, msg.c_str()); + set_error(PyExc_TypeError, msg.c_str()); return nullptr; } if (!result) { std::string msg = "Unable to convert function return value to a " "Python type! The signature was\n\t"; - msg += it->signature; + assert(current_overload != nullptr); + msg += current_overload->signature; append_note_if_missing_header_is_suspected(msg); // Attach additional error info to the exception if supported if (PyErr_Occurred()) { raise_from(PyExc_TypeError, msg.c_str()); return nullptr; } - PyErr_SetString(PyExc_TypeError, msg.c_str()); + set_error(PyExc_TypeError, msg.c_str()); return nullptr; } if (overloads->is_constructor && !self_value_and_holder.holder_constructed()) { @@ -1149,6 +1197,25 @@ class cpp_function : public function { } }; +PYBIND11_NAMESPACE_BEGIN(detail) + +template <> +struct handle_type_name { + static constexpr auto name = const_name("Callable"); +}; + +PYBIND11_NAMESPACE_END(detail) + +// Use to activate Py_MOD_GIL_NOT_USED. +class mod_gil_not_used { +public: + explicit mod_gil_not_used(bool flag = true) : flag_(flag) {} + bool flag() const { return flag_; } + +private: + bool flag_; +}; + /// Wrapper for Python extension modules class module_ : public object { public: @@ -1249,7 +1316,11 @@ class module_ : public object { ``def`` should point to a statically allocated module_def. \endrst */ - static module_ create_extension_module(const char *name, const char *doc, module_def *def) { + static module_ create_extension_module(const char *name, + const char *doc, + module_def *def, + mod_gil_not_used gil_not_used + = mod_gil_not_used(false)) { // module_def is PyModuleDef // Placement new (not an allocation). def = new (def) @@ -1269,6 +1340,11 @@ class module_ : public object { } pybind11_fail("Internal error in module_::create_extension_module()"); } + if (gil_not_used.flag()) { +#ifdef Py_GIL_DISABLED + PyUnstable_Module_SetGIL(m, Py_MOD_GIL_NOT_USED); +#endif + } // TODO: Should be reinterpret_steal for Python 3, but Python also steals it again when // returned from PyInit_... // For Python 2, reinterpret_borrow was correct. @@ -1276,6 +1352,15 @@ class module_ : public object { } }; +PYBIND11_NAMESPACE_BEGIN(detail) + +template <> +struct handle_type_name { + static constexpr auto name = const_name("module"); +}; + +PYBIND11_NAMESPACE_END(detail) + // When inside a namespace (or anywhere as long as it's not the first item on a line), // C++20 allows "module" to be used. This is provided for backward compatibility, and for // simplicity, if someone wants to use py::module for example, that is perfectly safe. @@ -1285,8 +1370,14 @@ using module = module_; /// Return a dictionary representing the global variables in the current execution frame, /// or ``__main__.__dict__`` if there is no frame (usually when the interpreter is embedded). inline dict globals() { +#if PY_VERSION_HEX >= 0x030d0000 + PyObject *p = PyEval_GetFrameGlobals(); + return p ? reinterpret_steal(p) + : reinterpret_borrow(module_::import("__main__").attr("__dict__").ptr()); +#else PyObject *p = PyEval_GetGlobals(); return reinterpret_borrow(p ? p : module_::import("__main__").attr("__dict__").ptr()); +#endif } template ()>> @@ -1332,15 +1423,16 @@ class generic_type : public object { tinfo->default_holder = rec.default_holder; tinfo->module_local = rec.module_local; - auto &internals = get_internals(); - auto tindex = std::type_index(*rec.type); - tinfo->direct_conversions = &internals.direct_conversions[tindex]; - if (rec.module_local) { - get_local_internals().registered_types_cpp[tindex] = tinfo; - } else { - internals.registered_types_cpp[tindex] = tinfo; - } - internals.registered_types_py[(PyTypeObject *) m_ptr] = {tinfo}; + with_internals([&](internals &internals) { + auto tindex = std::type_index(*rec.type); + tinfo->direct_conversions = &internals.direct_conversions[tindex]; + if (rec.module_local) { + get_local_internals().registered_types_cpp[tindex] = tinfo; + } else { + internals.registered_types_cpp[tindex] = tinfo; + } + internals.registered_types_py[(PyTypeObject *) m_ptr] = {tinfo}; + }); if (rec.bases.size() > 1 || rec.multiple_inheritance) { mark_parents_nonsimple(tinfo->type); @@ -1553,10 +1645,12 @@ class class_ : public detail::generic_type { generic_type::initialize(record); if (has_alias) { - auto &instances = record.module_local ? get_local_internals().registered_types_cpp - : get_internals().registered_types_cpp; - instances[std::type_index(typeid(type_alias))] - = instances[std::type_index(typeid(type))]; + with_internals([&](internals &internals) { + auto &instances = record.module_local ? get_local_internals().registered_types_cpp + : internals.registered_types_cpp; + instances[std::type_index(typeid(type_alias))] + = instances[std::type_index(typeid(type))]; + }); } } @@ -1977,7 +2071,7 @@ struct enum_base { object type_name = type::handle_of(arg).attr("__name__"); return pybind11::str("{}.{}").format(std::move(type_name), enum_name(arg)); }, - name("name"), + name("__str__"), is_method(m_base)); if (options::show_enum_members_docstring()) { @@ -2271,28 +2365,32 @@ keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret) { inline std::pair all_type_info_get_cache(PyTypeObject *type) { - auto res = get_internals() - .registered_types_py + auto res = with_internals([type](internals &internals) { + return internals + .registered_types_py #ifdef __cpp_lib_unordered_map_try_emplace - .try_emplace(type); + .try_emplace(type); #else - .emplace(type, std::vector()); + .emplace(type, std::vector()); #endif + }); if (res.second) { // New cache entry created; set up a weak reference to automatically remove it if the type // gets destroyed: weakref((PyObject *) type, cpp_function([type](handle wr) { - get_internals().registered_types_py.erase(type); - - // TODO consolidate the erasure code in pybind11_meta_dealloc() in class.h - auto &cache = get_internals().inactive_override_cache; - for (auto it = cache.begin(), last = cache.end(); it != last;) { - if (it->first == reinterpret_cast(type)) { - it = cache.erase(it); - } else { - ++it; + with_internals([type](internals &internals) { + internals.registered_types_py.erase(type); + + // TODO consolidate the erasure code in pybind11_meta_dealloc() in class.h + auto &cache = internals.inactive_override_cache; + for (auto it = cache.begin(), last = cache.end(); it != last;) { + if (it->first == reinterpret_cast(type)) { + it = cache.erase(it); + } else { + ++it; + } } - } + }); wr.dec_ref(); })) @@ -2395,7 +2493,7 @@ iterator make_iterator_impl(Iterator first, Sentinel last, Extra &&...extra) { Policy); } - return cast(state{first, last, true}); + return cast(state{std::forward(first), std::forward(last), true}); } PYBIND11_NAMESPACE_END(detail) @@ -2406,13 +2504,15 @@ template ::result_type, typename... Extra> -iterator make_iterator(Iterator first, Sentinel last, Extra &&...extra) { +typing::Iterator make_iterator(Iterator first, Sentinel last, Extra &&...extra) { return detail::make_iterator_impl, Policy, Iterator, Sentinel, ValueType, - Extra...>(first, last, std::forward(extra)...); + Extra...>(std::forward(first), + std::forward(last), + std::forward(extra)...); } /// Makes a python iterator over the keys (`.first`) of a iterator over pairs from a @@ -2422,13 +2522,15 @@ template ::result_type, typename... Extra> -iterator make_key_iterator(Iterator first, Sentinel last, Extra &&...extra) { +typing::Iterator make_key_iterator(Iterator first, Sentinel last, Extra &&...extra) { return detail::make_iterator_impl, Policy, Iterator, Sentinel, KeyType, - Extra...>(first, last, std::forward(extra)...); + Extra...>(std::forward(first), + std::forward(last), + std::forward(extra)...); } /// Makes a python iterator over the values (`.second`) of a iterator over pairs from a @@ -2438,21 +2540,25 @@ template ::result_type, typename... Extra> -iterator make_value_iterator(Iterator first, Sentinel last, Extra &&...extra) { +typing::Iterator make_value_iterator(Iterator first, Sentinel last, Extra &&...extra) { return detail::make_iterator_impl, Policy, Iterator, Sentinel, ValueType, - Extra...>(first, last, std::forward(extra)...); + Extra...>(std::forward(first), + std::forward(last), + std::forward(extra)...); } /// Makes an iterator over values of an stl container or other container supporting /// `std::begin()`/`std::end()` template ()))>::result_type, typename... Extra> -iterator make_iterator(Type &value, Extra &&...extra) { +typing::Iterator make_iterator(Type &value, Extra &&...extra) { return make_iterator( std::begin(value), std::end(value), std::forward(extra)...); } @@ -2461,8 +2567,10 @@ iterator make_iterator(Type &value, Extra &&...extra) { /// `std::begin()`/`std::end()` template ()))>::result_type, typename... Extra> -iterator make_key_iterator(Type &value, Extra &&...extra) { +typing::Iterator make_key_iterator(Type &value, Extra &&...extra) { return make_key_iterator( std::begin(value), std::end(value), std::forward(extra)...); } @@ -2471,8 +2579,10 @@ iterator make_key_iterator(Type &value, Extra &&...extra) { /// `std::begin()`/`std::end()` template ()))>::result_type, typename... Extra> -iterator make_value_iterator(Type &value, Extra &&...extra) { +typing::Iterator make_value_iterator(Type &value, Extra &&...extra) { return make_value_iterator( std::begin(value), std::end(value), std::forward(extra)...); } @@ -2485,7 +2595,11 @@ void implicitly_convertible() { ~set_flag() { flag = false; } }; auto implicit_caster = [](PyObject *obj, PyTypeObject *type) -> PyObject * { +#ifdef Py_GIL_DISABLED + thread_local bool currently_used = false; +#else static bool currently_used = false; +#endif if (currently_used) { // implicit conversions are non-reentrant return nullptr; } @@ -2510,8 +2624,10 @@ void implicitly_convertible() { } inline void register_exception_translator(ExceptionTranslator &&translator) { - detail::get_internals().registered_exception_translators.push_front( - std::forward(translator)); + detail::with_internals([&](detail::internals &internals) { + internals.registered_exception_translators.push_front( + std::forward(translator)); + }); } /** @@ -2521,14 +2637,17 @@ inline void register_exception_translator(ExceptionTranslator &&translator) { * the exception. */ inline void register_local_exception_translator(ExceptionTranslator &&translator) { - detail::get_local_internals().registered_exception_translators.push_front( - std::forward(translator)); + detail::with_internals([&](detail::internals &internals) { + (void) internals; + detail::get_local_internals().registered_exception_translators.push_front( + std::forward(translator)); + }); } /** * Wrapper to generate a new Python exception type. * - * This should only be used with PyErr_SetString for now. + * This should only be used with py::set_error() for now. * It is not (yet) possible to use as a py::base. * Template type argument is reserved for future use. */ @@ -2549,27 +2668,25 @@ class exception : public object { } // Sets the current python exception to this exception object with the given message - void operator()(const char *message) { PyErr_SetString(m_ptr, message); } + PYBIND11_DEPRECATED("Please use py::set_error() instead " + "(https://github.com/pybind/pybind11/pull/4772)") + void operator()(const char *message) const { set_error(*this, message); } }; PYBIND11_NAMESPACE_BEGIN(detail) -// Returns a reference to a function-local static exception object used in the simple -// register_exception approach below. (It would be simpler to have the static local variable -// directly in register_exception, but that makes clang <3.5 segfault - issue #1349). -template -exception &get_exception_object() { - static exception ex; - return ex; -} + +template <> +struct handle_type_name> { + static constexpr auto name = const_name("Exception"); +}; // Helper function for register_exception and register_local_exception template exception & register_exception_impl(handle scope, const char *name, handle base, bool isLocal) { - auto &ex = detail::get_exception_object(); - if (!ex) { - ex = exception(scope, name, base); - } + PYBIND11_CONSTINIT static gil_safe_call_once_and_store> exc_storage; + exc_storage.call_once_and_store_result( + [&]() { return exception(scope, name, base); }); auto register_func = isLocal ? ®ister_local_exception_translator : ®ister_exception_translator; @@ -2581,10 +2698,10 @@ register_exception_impl(handle scope, const char *name, handle base, bool isLoca try { std::rethrow_exception(p); } catch (const CppException &e) { - detail::get_exception_object()(e.what()); + set_error(exc_storage.get_stored(), e.what()); } }); - return ex; + return exc_storage.get_stored(); } PYBIND11_NAMESPACE_END(detail) @@ -2681,14 +2798,19 @@ get_type_override(const void *this_ptr, const type_info *this_type, const char * /* Cache functions that aren't overridden in Python to avoid many costly Python dictionary lookups below */ - auto &cache = get_internals().inactive_override_cache; - if (cache.find(key) != cache.end()) { + bool not_overridden = with_internals([&key](internals &internals) { + auto &cache = internals.inactive_override_cache; + return cache.find(key) != cache.end(); + }); + if (not_overridden) { return function(); } function override = getattr(self, name, function()); if (override.is_cpp_function()) { - cache.insert(std::move(key)); + with_internals([&](internals &internals) { + internals.inactive_override_cache.insert(std::move(key)); + }); return function(); } @@ -2701,12 +2823,22 @@ get_type_override(const void *this_ptr, const type_info *this_type, const char * PyCodeObject *f_code = PyFrame_GetCode(frame); // f_code is guaranteed to not be NULL if ((std::string) str(f_code->co_name) == name && f_code->co_argcount > 0) { +# if PY_VERSION_HEX >= 0x030d0000 + PyObject *locals = PyEval_GetFrameLocals(); +# else PyObject *locals = PyEval_GetLocals(); + Py_XINCREF(locals); +# endif if (locals != nullptr) { +# if PY_VERSION_HEX >= 0x030b0000 + PyObject *co_varnames = PyCode_GetVarnames(f_code); +# else PyObject *co_varnames = PyObject_GetAttrString((PyObject *) f_code, "co_varnames"); +# endif PyObject *self_arg = PyTuple_GET_ITEM(co_varnames, 0); Py_DECREF(co_varnames); PyObject *self_caller = dict_getitem(locals, self_arg); + Py_DECREF(locals); if (self_caller == self.ptr()) { Py_DECREF(f_code); Py_DECREF(frame); @@ -2783,10 +2915,14 @@ function get_override(const T *this_ptr, const char *name) { = pybind11::get_override(static_cast(this), name); \ if (override) { \ auto o = override(__VA_ARGS__); \ - if (pybind11::detail::cast_is_temporary_value_reference::value) { \ + PYBIND11_WARNING_PUSH \ + PYBIND11_WARNING_DISABLE_MSVC(4127) \ + if (pybind11::detail::cast_is_temporary_value_reference::value \ + && !pybind11::detail::is_same_ignoring_cvref::value) { \ static pybind11::detail::override_caster_t caster; \ return pybind11::detail::cast_ref(std::move(o), caster); \ } \ + PYBIND11_WARNING_POP \ return pybind11::detail::cast_safe(std::move(o)); \ } \ } while (false) diff --git a/wrap/pybind11/include/pybind11/pytypes.h b/wrap/pybind11/include/pybind11/pytypes.h index 64aad63476..f26c307a87 100644 --- a/wrap/pybind11/include/pybind11/pytypes.h +++ b/wrap/pybind11/include/pybind11/pytypes.h @@ -59,6 +59,7 @@ struct sequence_item; struct list_item; struct tuple_item; } // namespace accessor_policies +// PLEASE KEEP handle_type_name SPECIALIZATIONS IN SYNC. using obj_attr_accessor = accessor; using str_attr_accessor = accessor; using item_accessor = accessor; @@ -182,7 +183,15 @@ class object_api : public pyobject_tag { str_attr_accessor doc() const; /// Return the object's current reference count - int ref_count() const { return static_cast(Py_REFCNT(derived().ptr())); } + ssize_t ref_count() const { +#ifdef PYPY_VERSION + // PyPy uses the top few bits for REFCNT_FROM_PYPY & REFCNT_FROM_PYPY_LIGHT + // Following pybind11 2.12.1 and older behavior and removing this part + return static_cast(static_cast(Py_REFCNT(derived().ptr()))); +#else + return Py_REFCNT(derived().ptr()); +#endif + } // TODO PYBIND11_DEPRECATED( // "Call py::type::handle_of(h) or py::type::of(h) instead of h.get_type()") @@ -305,19 +314,19 @@ class handle : public detail::object_api { "https://pybind11.readthedocs.io/en/stable/advanced/" "misc.html#common-sources-of-global-interpreter-lock-errors for debugging advice.\n" "If you are convinced there is no bug in your code, you can #define " - "PYBIND11_NO_ASSERT_GIL_HELD_INCREF_DECREF" + "PYBIND11_NO_ASSERT_GIL_HELD_INCREF_DECREF " "to disable this check. In that case you have to ensure this #define is consistently " "used for all translation units linked into a given pybind11 extension, otherwise " "there will be ODR violations.", function_name.c_str()); - fflush(stderr); if (Py_TYPE(m_ptr)->tp_name != nullptr) { fprintf(stderr, - "The failing %s call was triggered on a %s object.\n", + " The failing %s call was triggered on a %s object.", function_name.c_str(), Py_TYPE(m_ptr)->tp_name); - fflush(stderr); } + fprintf(stderr, "\n"); + fflush(stderr); throw std::runtime_error(function_name + " PyGILState_Check() failure."); } #endif @@ -334,6 +343,14 @@ class handle : public detail::object_api { #endif }; +inline void set_error(const handle &type, const char *message) { + PyErr_SetString(type.ptr(), message); +} + +inline void set_error(const handle &type, const handle &value) { + PyErr_SetObject(type.ptr(), value.ptr()); +} + /** \rst Holds a reference to a Python object (with reference counting) @@ -963,6 +980,23 @@ inline PyObject *dict_getitem(PyObject *v, PyObject *key) { return rv; } +inline PyObject *dict_getitemstringref(PyObject *v, const char *key) { +#if PY_VERSION_HEX >= 0x030D0000 + PyObject *rv; + if (PyDict_GetItemStringRef(v, key, &rv) < 0) { + throw error_already_set(); + } + return rv; +#else + PyObject *rv = dict_getitemstring(v, key); + if (rv == nullptr && PyErr_Occurred()) { + throw error_already_set(); + } + Py_XINCREF(rv); + return rv; +#endif +} + // Helper aliases/functions to support implicit casting of values given to python // accessors/methods. When given a pyobject, this simply returns the pyobject as-is; for other C++ // type, the value goes through pybind11::cast(obj) to convert it to an `object`. @@ -1612,7 +1646,15 @@ inline namespace literals { /** \rst String literal version of `str` \endrst */ -inline str operator"" _s(const char *s, size_t size) { return {s, size}; } +inline str +#if !defined(__clang__) && defined(__GNUC__) && __GNUC__ < 5 +operator"" _s // gcc 4.8.5 insists on having a space (hard error). +#else +operator""_s // clang 17 generates a deprecation warning if there is a space. +#endif + (const char *s, size_t size) { + return {s, size}; +} } // namespace literals /// \addtogroup pytypes @@ -2158,6 +2200,11 @@ class list : public object { throw error_already_set(); } } + void clear() /* py-non-const */ { + if (PyList_SetSlice(m_ptr, 0, PyList_Size(m_ptr), nullptr) == -1) { + throw error_already_set(); + } + } }; class args : public tuple { diff --git a/wrap/pybind11/include/pybind11/stl.h b/wrap/pybind11/include/pybind11/stl.h index f39f44f7c9..71bc5902ef 100644 --- a/wrap/pybind11/include/pybind11/stl.h +++ b/wrap/pybind11/include/pybind11/stl.h @@ -100,7 +100,7 @@ struct set_caster { return s.release(); } - PYBIND11_TYPE_CASTER(type, const_name("Set[") + key_conv::name + const_name("]")); + PYBIND11_TYPE_CASTER(type, const_name("set[") + key_conv::name + const_name("]")); }; template @@ -157,7 +157,7 @@ struct map_caster { } PYBIND11_TYPE_CASTER(Type, - const_name("Dict[") + key_conv::name + const_name(", ") + value_conv::name + const_name("dict[") + key_conv::name + const_name(", ") + value_conv::name + const_name("]")); }; @@ -172,7 +172,7 @@ struct list_caster { auto s = reinterpret_borrow(src); value.clear(); reserve_maybe(s, &value); - for (auto it : s) { + for (const auto &it : s) { value_conv conv; if (!conv.load(it, convert)) { return false; @@ -208,7 +208,7 @@ struct list_caster { return l.release(); } - PYBIND11_TYPE_CASTER(Type, const_name("List[") + value_conv::name + const_name("]")); + PYBIND11_TYPE_CASTER(Type, const_name("list[") + value_conv::name + const_name("]")); }; template @@ -247,7 +247,7 @@ struct array_caster { return false; } size_t ctr = 0; - for (auto it : l) { + for (const auto &it : l) { value_conv conv; if (!conv.load(it, convert)) { return false; @@ -274,7 +274,7 @@ struct array_caster { PYBIND11_TYPE_CASTER(ArrayType, const_name(const_name(""), const_name("Annotated[")) - + const_name("List[") + value_conv::name + const_name("]") + + const_name("list[") + value_conv::name + const_name("]") + const_name(const_name(""), const_name(", FixedSize(") + const_name() + const_name(")]"))); @@ -421,7 +421,8 @@ struct variant_caster> { using Type = V; PYBIND11_TYPE_CASTER(Type, - const_name("Union[") + detail::concat(make_caster::name...) + const_name("Union[") + + ::pybind11::detail::concat(make_caster::name...) + const_name("]")); }; diff --git a/wrap/pybind11/include/pybind11/stl/filesystem.h b/wrap/pybind11/include/pybind11/stl/filesystem.h index e26f421776..85c131efe4 100644 --- a/wrap/pybind11/include/pybind11/stl/filesystem.h +++ b/wrap/pybind11/include/pybind11/stl/filesystem.h @@ -14,8 +14,7 @@ #ifdef __has_include # if defined(PYBIND11_CPP17) -# if __has_include() && \ - PY_VERSION_HEX >= 0x03060000 +# if __has_include() # include # define PYBIND11_HAS_FILESYSTEM 1 # elif __has_include() diff --git a/wrap/pybind11/include/pybind11/stl_bind.h b/wrap/pybind11/include/pybind11/stl_bind.h index 49f1b77821..66c452ea79 100644 --- a/wrap/pybind11/include/pybind11/stl_bind.h +++ b/wrap/pybind11/include/pybind11/stl_bind.h @@ -158,8 +158,7 @@ void vector_modifiers( return v.release(); })); - cl.def( - "clear", [](Vector &v) { v.clear(); }, "Clear the contents"); + cl.def("clear", [](Vector &v) { v.clear(); }, "Clear the contents"); cl.def( "extend", @@ -525,7 +524,7 @@ class_ bind_vector(handle scope, std::string const &name, A [](const Vector &v) -> bool { return !v.empty(); }, "Check whether the list is nonempty"); - cl.def("__len__", &Vector::size); + cl.def("__len__", [](const Vector &vec) { return vec.size(); }); #if 0 // C++ style functions deprecated, leaving it here as an example @@ -645,49 +644,50 @@ auto map_if_insertion_operator(Class_ &cl, std::string const &name) "Return the canonical string representation of this map."); } -template struct keys_view { virtual size_t len() = 0; virtual iterator iter() = 0; - virtual bool contains(const KeyType &k) = 0; - virtual bool contains(const object &k) = 0; + virtual bool contains(const handle &k) = 0; virtual ~keys_view() = default; }; -template struct values_view { virtual size_t len() = 0; virtual iterator iter() = 0; virtual ~values_view() = default; }; -template struct items_view { virtual size_t len() = 0; virtual iterator iter() = 0; virtual ~items_view() = default; }; -template -struct KeysViewImpl : public KeysView { +template +struct KeysViewImpl : public detail::keys_view { explicit KeysViewImpl(Map &map) : map(map) {} size_t len() override { return map.size(); } iterator iter() override { return make_key_iterator(map.begin(), map.end()); } - bool contains(const typename Map::key_type &k) override { return map.find(k) != map.end(); } - bool contains(const object &) override { return false; } + bool contains(const handle &k) override { + try { + return map.find(k.template cast()) != map.end(); + } catch (const cast_error &) { + return false; + } + } Map ↦ }; -template -struct ValuesViewImpl : public ValuesView { +template +struct ValuesViewImpl : public detail::values_view { explicit ValuesViewImpl(Map &map) : map(map) {} size_t len() override { return map.size(); } iterator iter() override { return make_value_iterator(map.begin(), map.end()); } Map ↦ }; -template -struct ItemsViewImpl : public ItemsView { +template +struct ItemsViewImpl : public detail::items_view { explicit ItemsViewImpl(Map &map) : map(map) {} size_t len() override { return map.size(); } iterator iter() override { return make_iterator(map.begin(), map.end()); } @@ -700,11 +700,9 @@ template , typename... class_ bind_map(handle scope, const std::string &name, Args &&...args) { using KeyType = typename Map::key_type; using MappedType = typename Map::mapped_type; - using StrippedKeyType = detail::remove_cvref_t; - using StrippedMappedType = detail::remove_cvref_t; - using KeysView = detail::keys_view; - using ValuesView = detail::values_view; - using ItemsView = detail::items_view; + using KeysView = detail::keys_view; + using ValuesView = detail::values_view; + using ItemsView = detail::items_view; using Class_ = class_; // If either type is a non-module-local bound type then make the map binding non-local as well; @@ -718,39 +716,20 @@ class_ bind_map(handle scope, const std::string &name, Args && } Class_ cl(scope, name.c_str(), pybind11::module_local(local), std::forward(args)...); - static constexpr auto key_type_descr = detail::make_caster::name; - static constexpr auto mapped_type_descr = detail::make_caster::name; - std::string key_type_name(key_type_descr.text), mapped_type_name(mapped_type_descr.text); - - // If key type isn't properly wrapped, fall back to C++ names - if (key_type_name == "%") { - key_type_name = detail::type_info_description(typeid(KeyType)); - } - // Similarly for value type: - if (mapped_type_name == "%") { - mapped_type_name = detail::type_info_description(typeid(MappedType)); - } - // Wrap KeysView[KeyType] if it wasn't already wrapped + // Wrap KeysView if it wasn't already wrapped if (!detail::get_type_info(typeid(KeysView))) { - class_ keys_view( - scope, ("KeysView[" + key_type_name + "]").c_str(), pybind11::module_local(local)); + class_ keys_view(scope, "KeysView", pybind11::module_local(local)); keys_view.def("__len__", &KeysView::len); keys_view.def("__iter__", &KeysView::iter, keep_alive<0, 1>() /* Essential: keep view alive while iterator exists */ ); - keys_view.def("__contains__", - static_cast(&KeysView::contains)); - // Fallback for when the object is not of the key type - keys_view.def("__contains__", - static_cast(&KeysView::contains)); + keys_view.def("__contains__", &KeysView::contains); } // Similarly for ValuesView: if (!detail::get_type_info(typeid(ValuesView))) { - class_ values_view(scope, - ("ValuesView[" + mapped_type_name + "]").c_str(), - pybind11::module_local(local)); + class_ values_view(scope, "ValuesView", pybind11::module_local(local)); values_view.def("__len__", &ValuesView::len); values_view.def("__iter__", &ValuesView::iter, @@ -759,10 +738,7 @@ class_ bind_map(handle scope, const std::string &name, Args && } // Similarly for ItemsView: if (!detail::get_type_info(typeid(ItemsView))) { - class_ items_view( - scope, - ("ItemsView[" + key_type_name + ", ").append(mapped_type_name + "]").c_str(), - pybind11::module_local(local)); + class_ items_view(scope, "ItemsView", pybind11::module_local(local)); items_view.def("__len__", &ItemsView::len); items_view.def("__iter__", &ItemsView::iter, @@ -788,25 +764,19 @@ class_ bind_map(handle scope, const std::string &name, Args && cl.def( "keys", - [](Map &m) { - return std::unique_ptr(new detail::KeysViewImpl(m)); - }, + [](Map &m) { return std::unique_ptr(new detail::KeysViewImpl(m)); }, keep_alive<0, 1>() /* Essential: keep map alive while view exists */ ); cl.def( "values", - [](Map &m) { - return std::unique_ptr(new detail::ValuesViewImpl(m)); - }, + [](Map &m) { return std::unique_ptr(new detail::ValuesViewImpl(m)); }, keep_alive<0, 1>() /* Essential: keep map alive while view exists */ ); cl.def( "items", - [](Map &m) { - return std::unique_ptr(new detail::ItemsViewImpl(m)); - }, + [](Map &m) { return std::unique_ptr(new detail::ItemsViewImpl(m)); }, keep_alive<0, 1>() /* Essential: keep map alive while view exists */ ); @@ -843,7 +813,8 @@ class_ bind_map(handle scope, const std::string &name, Args && m.erase(it); }); - cl.def("__len__", &Map::size); + // Always use a lambda in case of `using` declaration + cl.def("__len__", [](const Map &m) { return m.size(); }); return cl; } diff --git a/wrap/pybind11/include/pybind11/typing.h b/wrap/pybind11/include/pybind11/typing.h new file mode 100644 index 0000000000..1442cdc7f1 --- /dev/null +++ b/wrap/pybind11/include/pybind11/typing.h @@ -0,0 +1,239 @@ +/* + pybind11/typing.h: Convenience wrapper classes for basic Python types + with more explicit annotations. + + Copyright (c) 2023 Dustin Spicuzza + + 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 "cast.h" +#include "pytypes.h" + +PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +PYBIND11_NAMESPACE_BEGIN(typing) + +/* + The following types can be used to direct pybind11-generated docstrings + to have have more explicit types (e.g., `list[str]` instead of `list`). + Just use these in place of existing types. + + There is no additional enforcement of types at runtime. +*/ + +template +class Tuple : public tuple { + using tuple::tuple; +}; + +template +class Dict : public dict { + using dict::dict; +}; + +template +class List : public list { + using list::list; +}; + +template +class Set : public set { + using set::set; +}; + +template +class Iterable : public iterable { + using iterable::iterable; +}; + +template +class Iterator : public iterator { + using iterator::iterator; +}; + +template +class Callable; + +template +class Callable : public function { + using function::function; +}; + +template +class Type : public type { + using type::type; +}; + +template +class Union : public object { + PYBIND11_OBJECT_DEFAULT(Union, object, PyObject_Type) + using object::object; +}; + +template +class Optional : public object { + PYBIND11_OBJECT_DEFAULT(Optional, object, PyObject_Type) + using object::object; +}; + +template +class TypeGuard : public bool_ { + using bool_::bool_; +}; + +template +class TypeIs : public bool_ { + using bool_::bool_; +}; + +class NoReturn : public none { + using none::none; +}; + +class Never : public none { + using none::none; +}; + +#if defined(__cpp_nontype_template_parameter_class) +template +struct StringLiteral { + constexpr StringLiteral(const char (&str)[N]) { std::copy_n(str, N, name); } + char name[N]; +}; + +template +class Literal : public object { + PYBIND11_OBJECT_DEFAULT(Literal, object, PyObject_Type) +}; + +// Example syntax for creating a TypeVar. +// typedef typing::TypeVar<"T"> TypeVarT; +template +class TypeVar : public object { + PYBIND11_OBJECT_DEFAULT(TypeVar, object, PyObject_Type) + using object::object; +}; +#endif + +PYBIND11_NAMESPACE_END(typing) + +PYBIND11_NAMESPACE_BEGIN(detail) + +template +struct handle_type_name> { + static constexpr auto name = const_name("tuple[") + + ::pybind11::detail::concat(make_caster::name...) + + const_name("]"); +}; + +template <> +struct handle_type_name> { + // PEP 484 specifies this syntax for an empty tuple + static constexpr auto name = const_name("tuple[()]"); +}; + +template +struct handle_type_name> { + // PEP 484 specifies this syntax for a variable-length tuple + static constexpr auto name + = const_name("tuple[") + make_caster::name + const_name(", ...]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("dict[") + make_caster::name + const_name(", ") + + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("list[") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("set[") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("Iterable[") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("Iterator[") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + using retval_type = conditional_t::value, void_type, Return>; + static constexpr auto name + = const_name("Callable[[") + ::pybind11::detail::concat(make_caster::name...) + + const_name("], ") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + // PEP 484 specifies this syntax for defining only return types of callables + using retval_type = conditional_t::value, void_type, Return>; + static constexpr auto name + = const_name("Callable[..., ") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("type[") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("Union[") + + ::pybind11::detail::concat(make_caster::name...) + + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("Optional[") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("TypeGuard[") + make_caster::name + const_name("]"); +}; + +template +struct handle_type_name> { + static constexpr auto name = const_name("TypeIs[") + make_caster::name + const_name("]"); +}; + +template <> +struct handle_type_name { + static constexpr auto name = const_name("NoReturn"); +}; + +template <> +struct handle_type_name { + static constexpr auto name = const_name("Never"); +}; + +#if defined(__cpp_nontype_template_parameter_class) +template +struct handle_type_name> { + static constexpr auto name = const_name("Literal[") + + pybind11::detail::concat(const_name(Literals.name)...) + + const_name("]"); +}; +template +struct handle_type_name> { + static constexpr auto name = const_name(StrLit.name); +}; +#endif + +PYBIND11_NAMESPACE_END(detail) +PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/pybind11/noxfile.py b/wrap/pybind11/noxfile.py index 021ced2453..e9a2fa8fee 100644 --- a/wrap/pybind11/noxfile.py +++ b/wrap/pybind11/noxfile.py @@ -1,24 +1,12 @@ -import os +from __future__ import annotations + +import argparse import nox -nox.needs_version = ">=2022.1.7" +nox.needs_version = ">=2024.3.2" nox.options.sessions = ["lint", "tests", "tests_packaging"] - -PYTHON_VERSIONS = [ - "3.6", - "3.7", - "3.8", - "3.9", - "3.10", - "3.11", - "pypy3.7", - "pypy3.8", - "pypy3.9", -] - -if os.environ.get("CI", None): - nox.options.error_on_missing_interpreters = True +nox.options.default_venv_backend = "uv|virtualenv" @nox.session(reuse_venv=True) @@ -30,7 +18,7 @@ def lint(session: nox.Session) -> None: session.run("pre-commit", "run", "-a", *session.posargs) -@nox.session(python=PYTHON_VERSIONS) +@nox.session def tests(session: nox.Session) -> None: """ Run the tests (requires a compiler). @@ -57,30 +45,42 @@ def tests_packaging(session: nox.Session) -> None: Run the packaging tests. """ - session.install("-r", "tests/requirements.txt", "--prefer-binary") + session.install("-r", "tests/requirements.txt", "pip") session.run("pytest", "tests/extra_python_package", *session.posargs) @nox.session(reuse_venv=True) def docs(session: nox.Session) -> None: """ - Build the docs. Pass "serve" to serve. + Build the docs. Pass --non-interactive to avoid serving. """ - session.install("-r", "docs/requirements.txt") - session.chdir("docs") + parser = argparse.ArgumentParser() + parser.add_argument( + "-b", dest="builder", default="html", help="Build target (default: html)" + ) + args, posargs = parser.parse_known_args(session.posargs) + serve = args.builder == "html" and session.interactive - if "pdf" in session.posargs: - session.run("sphinx-build", "-M", "latexpdf", ".", "_build") - return + extra_installs = ["sphinx-autobuild"] if serve else [] + session.install("-r", "docs/requirements.txt", *extra_installs) + session.chdir("docs") - session.run("sphinx-build", "-M", "html", ".", "_build") + shared_args = ( + "-n", # nitpicky mode + "-T", # full tracebacks + f"-b={args.builder}", + ".", + f"_build/{args.builder}", + *posargs, + ) - if "serve" in session.posargs: - session.log("Launching docs at http://localhost:8000/ - use Ctrl-C to quit") - session.run("python", "-m", "http.server", "8000", "-d", "_build/html") - elif session.posargs: - session.error("Unsupported argument to docs") + if serve: + session.run( + "sphinx-autobuild", "--open-browser", "--ignore=.build", *shared_args + ) + else: + session.run("sphinx-build", "--keep-going", *shared_args) @nox.session(reuse_venv=True) diff --git a/wrap/pybind11/pybind11/__init__.py b/wrap/pybind11/pybind11/__init__.py index 7c10b30578..b14660caeb 100644 --- a/wrap/pybind11/pybind11/__init__.py +++ b/wrap/pybind11/pybind11/__init__.py @@ -1,7 +1,9 @@ +from __future__ import annotations + import sys -if sys.version_info < (3, 6): # noqa: UP036 - msg = "pybind11 does not support Python < 3.6. 2.9 was the last release supporting Python 2.7 and 3.5." +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) diff --git a/wrap/pybind11/pybind11/__main__.py b/wrap/pybind11/pybind11/__main__.py index 180665c23c..b656ce6fee 100644 --- a/wrap/pybind11/pybind11/__main__.py +++ b/wrap/pybind11/pybind11/__main__.py @@ -1,4 +1,5 @@ # pylint: disable=missing-function-docstring +from __future__ import annotations import argparse import sys diff --git a/wrap/pybind11/pybind11/_version.py b/wrap/pybind11/pybind11/_version.py index 9280fa054e..18b72c07cb 100644 --- a/wrap/pybind11/pybind11/_version.py +++ b/wrap/pybind11/pybind11/_version.py @@ -1,12 +1,12 @@ -from typing import Union +from __future__ import annotations -def _to_int(s: str) -> Union[int, str]: +def _to_int(s: str) -> int | str: try: return int(s) except ValueError: return s -__version__ = "2.11.1" +__version__ = "2.13.1" version_info = tuple(_to_int(s) for s in __version__.split(".")) diff --git a/wrap/pybind11/pybind11/commands.py b/wrap/pybind11/pybind11/commands.py index b11690f46b..d535b6cca4 100644 --- a/wrap/pybind11/pybind11/commands.py +++ b/wrap/pybind11/pybind11/commands.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import os DIR = os.path.abspath(os.path.dirname(__file__)) diff --git a/wrap/pybind11/pybind11/setup_helpers.py b/wrap/pybind11/pybind11/setup_helpers.py index aeeee9dcfa..ced506f8c2 100644 --- a/wrap/pybind11/pybind11/setup_helpers.py +++ b/wrap/pybind11/pybind11/setup_helpers.py @@ -36,6 +36,7 @@ # # If you copy this file in, you don't # need the .pyi file; it's just an interface file for static type checkers. +from __future__ import annotations import contextlib import os @@ -52,7 +53,6 @@ from typing import ( Any, Callable, - Dict, Iterable, Iterator, List, @@ -66,7 +66,9 @@ from setuptools import Extension as _Extension from setuptools.command.build_ext import build_ext as _build_ext except ImportError: - from distutils.command.build_ext import build_ext as _build_ext # type: ignore[assignment] + from distutils.command.build_ext import ( # type: ignore[assignment] + build_ext as _build_ext, + ) from distutils.extension import Extension as _Extension # type: ignore[assignment] import distutils.ccompiler @@ -111,10 +113,10 @@ class Pybind11Extension(_Extension): # flags are prepended, so that they can be further overridden, e.g. by # ``extra_compile_args=["-g"]``. - def _add_cflags(self, flags: List[str]) -> None: + def _add_cflags(self, flags: list[str]) -> None: self.extra_compile_args[:0] = flags - def _add_ldflags(self, flags: List[str]) -> None: + def _add_ldflags(self, flags: list[str]) -> None: self.extra_link_args[:0] = flags def __init__(self, *args: Any, **kwargs: Any) -> None: @@ -248,7 +250,7 @@ def has_flag(compiler: Any, flag: str) -> bool: @lru_cache() -def auto_cpp_level(compiler: Any) -> Union[str, int]: +def auto_cpp_level(compiler: Any) -> str | int: """ Return the max supported C++ std level (17, 14, or 11). Returns latest on Windows. """ @@ -286,8 +288,8 @@ def build_extensions(self) -> None: def intree_extensions( - paths: Iterable[str], package_dir: Optional[Dict[str, str]] = None -) -> List[Pybind11Extension]: + paths: Iterable[str], package_dir: dict[str, str] | None = None +) -> list[Pybind11Extension]: """ Generate Pybind11Extensions from source files directly located in a Python source tree. @@ -351,7 +353,7 @@ def no_recompile(obg: str, src: str) -> bool: # noqa: ARG001 distutils.ccompiler.CCompiler, List[str], Optional[str], - Optional[Union[Tuple[str], Tuple[str, Optional[str]]]], + Optional[List[Union[Tuple[str], Tuple[str, Optional[str]]]]], Optional[List[str]], bool, Optional[List[str]], @@ -407,7 +409,7 @@ class ParallelCompile: def __init__( self, - envvar: Optional[str] = None, + envvar: str | None = None, default: int = 0, max: int = 0, # pylint: disable=redefined-builtin needs_recompile: Callable[[str, str], bool] = no_recompile, @@ -416,7 +418,7 @@ def __init__( self.default = default self.max = max self.needs_recompile = needs_recompile - self._old: List[CCompilerMethod] = [] + self._old: list[CCompilerMethod] = [] def function(self) -> CCompilerMethod: """ @@ -425,14 +427,14 @@ def function(self) -> CCompilerMethod: def compile_function( compiler: distutils.ccompiler.CCompiler, - sources: List[str], - output_dir: Optional[str] = None, - macros: Optional[Union[Tuple[str], Tuple[str, Optional[str]]]] = None, - include_dirs: Optional[List[str]] = None, + sources: list[str], + output_dir: str | None = None, + macros: list[tuple[str] | tuple[str, str | None]] | None = None, + include_dirs: list[str] | None = None, debug: bool = False, - extra_preargs: Optional[List[str]] = None, - extra_postargs: Optional[List[str]] = None, - depends: Optional[List[str]] = None, + extra_preargs: list[str] | None = None, + extra_postargs: list[str] | None = None, + depends: list[str] | None = None, ) -> Any: # These lines are directly from distutils.ccompiler.CCompiler macros, objects, extra_postargs, pp_opts, build = compiler._setup_compile( # type: ignore[attr-defined] diff --git a/wrap/pybind11/pyproject.toml b/wrap/pybind11/pyproject.toml index 59c15ea636..71e7f56178 100644 --- a/wrap/pybind11/pyproject.toml +++ b/wrap/pybind11/pyproject.toml @@ -19,9 +19,8 @@ ignore = [ [tool.mypy] files = ["pybind11"] -python_version = "3.6" +python_version = "3.8" strict = true -show_error_codes = true enable_error_code = ["ignore-without-code", "redundant-expr", "truthy-bool"] warn_unreachable = true @@ -30,20 +29,8 @@ module = ["ghapi.*"] ignore_missing_imports = true -[tool.pytest.ini_options] -minversion = "6.0" -addopts = ["-ra", "--showlocals", "--strict-markers", "--strict-config"] -xfail_strict = true -filterwarnings = ["error"] -log_cli_level = "info" -testpaths = [ - "tests", -] -timeout=300 - - [tool.pylint] -master.py-version = "3.6" +master.py-version = "3.7" reports.output-format = "colorized" messages_control.disable = [ "design", @@ -57,10 +44,12 @@ messages_control.disable = [ "unused-argument", # covered by Ruff ARG ] - [tool.ruff] -select = [ - "E", "F", "W", # flake8 +target-version = "py37" +src = ["src"] + +[tool.ruff.lint] +extend-select = [ "B", # flake8-bugbear "I", # isort "N", # pep8-naming @@ -68,7 +57,6 @@ select = [ "C4", # flake8-comprehensions "EM", # flake8-errmsg "ICN", # flake8-import-conventions - "ISC", # flake8-implicit-str-concat "PGH", # pygrep-hooks "PIE", # flake8-pie "PL", # pylint @@ -86,13 +74,14 @@ ignore = [ "PT004", # Fixture that doesn't return needs underscore (no, it is fine) "SIM118", # iter(x) is not always the same as iter(x.keys()) ] -target-version = "py37" -src = ["src"] unfixable = ["T20"] -exclude = [] -line-length = 120 isort.known-first-party = ["env", "pybind11_cross_module_tests", "pybind11_tests"] +isort.required-imports = ["from __future__ import annotations"] -[tool.ruff.per-file-ignores] -"tests/**" = ["EM", "N"] + +[tool.ruff.lint.per-file-ignores] +"tests/**" = ["EM", "N", "E721"] "tests/test_call_policies.py" = ["PLC1901"] + +[tool.repo-review] +ignore = ["PP"] diff --git a/wrap/pybind11/setup.cfg b/wrap/pybind11/setup.cfg index 92e6c953a9..2beca780f9 100644 --- a/wrap/pybind11/setup.cfg +++ b/wrap/pybind11/setup.cfg @@ -14,13 +14,13 @@ classifiers = Topic :: Utilities Programming Language :: C++ Programming Language :: Python :: 3 :: Only - Programming Language :: Python :: 3.6 Programming Language :: Python :: 3.7 Programming Language :: Python :: 3.8 Programming Language :: Python :: 3.9 Programming Language :: Python :: 3.10 Programming Language :: Python :: 3.11 Programming Language :: Python :: 3.12 + Programming Language :: Python :: 3.13 License :: OSI Approved :: BSD License Programming Language :: Python :: Implementation :: PyPy Programming Language :: Python :: Implementation :: CPython @@ -39,5 +39,5 @@ project_urls = Chat = https://gitter.im/pybind/Lobby [options] -python_requires = >=3.6 +python_requires = >=3.7 zip_safe = False diff --git a/wrap/pybind11/setup.py b/wrap/pybind11/setup.py index 9fea7d35c7..96563c1a59 100644 --- a/wrap/pybind11/setup.py +++ b/wrap/pybind11/setup.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 # Setup script for PyPI; use CMakeFile.txt to build extension modules +from __future__ import annotations import contextlib import os @@ -9,9 +10,9 @@ import string import subprocess import sys +from collections.abc import Generator from pathlib import Path from tempfile import TemporaryDirectory -from typing import Dict, Iterator, List, Union import setuptools.command.sdist @@ -23,7 +24,7 @@ COMMON_FILE = Path("include/pybind11/detail/common.h") -def build_expected_version_hex(matches: Dict[str, str]) -> str: +def build_expected_version_hex(matches: dict[str, str]) -> str: patch_level_serial = matches["PATCH"] serial = None major = int(matches["MAJOR"]) @@ -64,7 +65,7 @@ def build_expected_version_hex(matches: Dict[str, str]) -> str: # Read the listed version -loc: Dict[str, str] = {} +loc: dict[str, str] = {} code = compile(VERSION_FILE.read_text(encoding="utf-8"), "pybind11/_version.py", "exec") exec(code, loc) version = loc["__version__"] @@ -84,9 +85,7 @@ def build_expected_version_hex(matches: Dict[str, str]) -> str: # TODO: use literals & overload (typing extensions or Python 3.8) -def get_and_replace( - filename: Path, binary: bool = False, **opts: str -) -> Union[bytes, str]: +def get_and_replace(filename: Path, binary: bool = False, **opts: str) -> bytes | str: if binary: contents = filename.read_bytes() return string.Template(contents.decode()).substitute(opts).encode() @@ -97,7 +96,7 @@ def get_and_replace( # Use our input files instead when making the SDist (and anything that depends # on it, like a wheel) class SDist(setuptools.command.sdist.sdist): - def make_release_tree(self, base_dir: str, files: List[str]) -> None: + def make_release_tree(self, base_dir: str, files: list[str]) -> None: super().make_release_tree(base_dir, files) for to, src in to_src: @@ -112,7 +111,7 @@ def make_release_tree(self, base_dir: str, files: List[str]) -> None: # Remove the CMake install directory when done @contextlib.contextmanager -def remove_output(*sources: str) -> Iterator[None]: +def remove_output(*sources: str) -> Generator[None, None, None]: try: yield finally: diff --git a/wrap/pybind11/tests/CMakeLists.txt b/wrap/pybind11/tests/CMakeLists.txt index 80ee9c1f11..f182e24992 100644 --- a/wrap/pybind11/tests/CMakeLists.txt +++ b/wrap/pybind11/tests/CMakeLists.txt @@ -7,13 +7,13 @@ cmake_minimum_required(VERSION 3.5) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) endif() # Filter out items; print an optional message if any items filtered. This ignores extensions. @@ -144,6 +144,7 @@ set(PYBIND11_TEST_FILES test_opaque_types test_operator_overloading test_pickling + test_python_multiple_inheritance test_pytypes test_sequences_and_iterators test_smart_ptr @@ -329,7 +330,7 @@ if(Boost_FOUND) add_library(Boost::headers IMPORTED INTERFACE) if(TARGET Boost::boost) # Classic FindBoost - set_property(TARGET Boost::boost PROPERTY INTERFACE_LINK_LIBRARIES Boost::boost) + set_property(TARGET Boost::headers PROPERTY INTERFACE_LINK_LIBRARIES Boost::boost) else() # Very old FindBoost, or newer Boost than CMake in older CMakes set_property(TARGET Boost::headers PROPERTY INTERFACE_INCLUDE_DIRECTORIES @@ -519,11 +520,15 @@ set(PYBIND11_TEST_PREFIX_COMMAND "" CACHE STRING "Put this before pytest, use for checkers and such") +set(PYBIND11_PYTEST_ARGS + "" + CACHE STRING "Extra arguments for pytest") + # A single command to compile and run the tests add_custom_target( pytest COMMAND ${PYBIND11_TEST_PREFIX_COMMAND} ${PYTHON_EXECUTABLE} -m pytest - ${PYBIND11_ABS_PYTEST_FILES} + ${PYBIND11_ABS_PYTEST_FILES} ${PYBIND11_PYTEST_ARGS} DEPENDS ${test_targets} WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" USES_TERMINAL) diff --git a/wrap/pybind11/tests/conftest.py b/wrap/pybind11/tests/conftest.py index ad5b47b4b3..7de6c2acee 100644 --- a/wrap/pybind11/tests/conftest.py +++ b/wrap/pybind11/tests/conftest.py @@ -4,6 +4,8 @@ Adds docstring and exceptions message sanitizers. """ +from __future__ import annotations + import contextlib import difflib import gc @@ -218,4 +220,5 @@ def pytest_report_header(config): f" {pybind11_tests.cpp_std}" f" {pybind11_tests.PYBIND11_INTERNALS_ID}" f" PYBIND11_SIMPLE_GIL_MANAGEMENT={pybind11_tests.PYBIND11_SIMPLE_GIL_MANAGEMENT}" + f" PYBIND11_NUMPY_1_ONLY={pybind11_tests.PYBIND11_NUMPY_1_ONLY}" ) diff --git a/wrap/pybind11/tests/cross_module_gil_utils.cpp b/wrap/pybind11/tests/cross_module_gil_utils.cpp index 7c20849dd9..39112668a4 100644 --- a/wrap/pybind11/tests/cross_module_gil_utils.cpp +++ b/wrap/pybind11/tests/cross_module_gil_utils.cpp @@ -92,6 +92,9 @@ extern "C" PYBIND11_EXPORT PyObject *PyInit_cross_module_gil_utils() { if (m != nullptr) { static_assert(sizeof(&gil_acquire) == sizeof(void *), "Function pointer must have the same size as void*"); +#ifdef Py_GIL_DISABLED + PyUnstable_Module_SetGIL(m, Py_MOD_GIL_NOT_USED); +#endif ADD_FUNCTION("gil_acquire_funcaddr", gil_acquire) ADD_FUNCTION("gil_multi_acquire_release_funcaddr", gil_multi_acquire_release) ADD_FUNCTION("gil_acquire_inner_custom_funcaddr", diff --git a/wrap/pybind11/tests/cross_module_interleaved_error_already_set.cpp b/wrap/pybind11/tests/cross_module_interleaved_error_already_set.cpp index fdd9939e45..65a4463b8c 100644 --- a/wrap/pybind11/tests/cross_module_interleaved_error_already_set.cpp +++ b/wrap/pybind11/tests/cross_module_interleaved_error_already_set.cpp @@ -16,12 +16,12 @@ namespace { namespace py = pybind11; void interleaved_error_already_set() { - PyErr_SetString(PyExc_RuntimeError, "1st error."); + py::set_error(PyExc_RuntimeError, "1st error."); try { throw py::error_already_set(); } catch (const py::error_already_set &) { // The 2nd error could be conditional in a real application. - PyErr_SetString(PyExc_RuntimeError, "2nd error."); + py::set_error(PyExc_RuntimeError, "2nd error."); } // Here the 1st error is destroyed before the 2nd error is fetched. // The error_already_set dtor triggers a pybind11::detail::get_internals() // call via pybind11::gil_scoped_acquire. @@ -42,6 +42,9 @@ extern "C" PYBIND11_EXPORT PyObject *PyInit_cross_module_interleaved_error_alrea if (m != nullptr) { static_assert(sizeof(&interleaved_error_already_set) == sizeof(void *), "Function pointer must have the same size as void *"); +#ifdef Py_GIL_DISABLED + PyUnstable_Module_SetGIL(m, Py_MOD_GIL_NOT_USED); +#endif PyModule_AddObject( m, "funcaddr", diff --git a/wrap/pybind11/tests/eigen_tensor_avoid_stl_array.cpp b/wrap/pybind11/tests/eigen_tensor_avoid_stl_array.cpp index eacc9e9bd6..5aca66c5ee 100644 --- a/wrap/pybind11/tests/eigen_tensor_avoid_stl_array.cpp +++ b/wrap/pybind11/tests/eigen_tensor_avoid_stl_array.cpp @@ -11,4 +11,6 @@ #include "test_eigen_tensor.inl" -PYBIND11_MODULE(eigen_tensor_avoid_stl_array, m) { eigen_tensor_test::test_module(m); } +PYBIND11_MODULE(eigen_tensor_avoid_stl_array, m, pybind11::mod_gil_not_used()) { + eigen_tensor_test::test_module(m); +} diff --git a/wrap/pybind11/tests/env.py b/wrap/pybind11/tests/env.py index 7eea5a3b3b..9f5347f2e5 100644 --- a/wrap/pybind11/tests/env.py +++ b/wrap/pybind11/tests/env.py @@ -1,5 +1,8 @@ +from __future__ import annotations + import platform import sys +import sysconfig import pytest @@ -9,6 +12,7 @@ CPYTHON = platform.python_implementation() == "CPython" PYPY = platform.python_implementation() == "PyPy" +PY_GIL_DISABLED = bool(sysconfig.get_config_var("Py_GIL_DISABLED")) def deprecated_call(): diff --git a/wrap/pybind11/tests/extra_python_package/test_files.py b/wrap/pybind11/tests/extra_python_package/test_files.py index 57387dd8bc..5a3f779a7d 100644 --- a/wrap/pybind11/tests/extra_python_package/test_files.py +++ b/wrap/pybind11/tests/extra_python_package/test_files.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import contextlib import os import string @@ -35,6 +37,7 @@ "include/pybind11/eval.h", "include/pybind11/functional.h", "include/pybind11/gil.h", + "include/pybind11/gil_safe_call_once.h", "include/pybind11/iostream.h", "include/pybind11/numpy.h", "include/pybind11/operators.h", @@ -44,6 +47,7 @@ "include/pybind11/stl.h", "include/pybind11/stl_bind.h", "include/pybind11/type_caster_pyobject_ptr.h", + "include/pybind11/typing.h", } detail_headers = { @@ -71,6 +75,7 @@ "share/cmake/pybind11/pybind11Common.cmake", "share/cmake/pybind11/pybind11Config.cmake", "share/cmake/pybind11/pybind11ConfigVersion.cmake", + "share/cmake/pybind11/pybind11GuessPythonExtSuffix.cmake", "share/cmake/pybind11/pybind11NewTools.cmake", "share/cmake/pybind11/pybind11Targets.cmake", "share/cmake/pybind11/pybind11Tools.cmake", diff --git a/wrap/pybind11/tests/extra_setuptools/test_setuphelper.py b/wrap/pybind11/tests/extra_setuptools/test_setuphelper.py index d5d3093bf0..2c069adffb 100644 --- a/wrap/pybind11/tests/extra_setuptools/test_setuphelper.py +++ b/wrap/pybind11/tests/extra_setuptools/test_setuphelper.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import os import subprocess import sys diff --git a/wrap/pybind11/tests/pybind11_cross_module_tests.cpp b/wrap/pybind11/tests/pybind11_cross_module_tests.cpp index 9379f3f259..76f40bfa97 100644 --- a/wrap/pybind11/tests/pybind11_cross_module_tests.cpp +++ b/wrap/pybind11/tests/pybind11_cross_module_tests.cpp @@ -16,7 +16,7 @@ #include #include -PYBIND11_MODULE(pybind11_cross_module_tests, m) { +PYBIND11_MODULE(pybind11_cross_module_tests, m, py::mod_gil_not_used()) { m.doc() = "pybind11 cross-module test module"; // test_local_bindings.py tests: @@ -31,11 +31,11 @@ PYBIND11_MODULE(pybind11_cross_module_tests, m) { // test_exceptions.py py::register_local_exception(m, "LocalSimpleException"); m.def("raise_runtime_error", []() { - PyErr_SetString(PyExc_RuntimeError, "My runtime error"); + py::set_error(PyExc_RuntimeError, "My runtime error"); throw py::error_already_set(); }); m.def("raise_value_error", []() { - PyErr_SetString(PyExc_ValueError, "My value error"); + py::set_error(PyExc_ValueError, "My value error"); throw py::error_already_set(); }); m.def("throw_pybind_value_error", []() { throw py::value_error("pybind11 value error"); }); @@ -49,7 +49,7 @@ PYBIND11_MODULE(pybind11_cross_module_tests, m) { std::rethrow_exception(p); } } catch (const shared_exception &e) { - PyErr_SetString(PyExc_KeyError, e.what()); + py::set_error(PyExc_KeyError, e.what()); } }); @@ -60,7 +60,7 @@ PYBIND11_MODULE(pybind11_cross_module_tests, m) { std::rethrow_exception(p); } } catch (const LocalException &e) { - PyErr_SetString(PyExc_KeyError, e.what()); + py::set_error(PyExc_KeyError, e.what()); } }); diff --git a/wrap/pybind11/tests/pybind11_tests.cpp b/wrap/pybind11/tests/pybind11_tests.cpp index 6240346487..3d2d84e77a 100644 --- a/wrap/pybind11/tests/pybind11_tests.cpp +++ b/wrap/pybind11/tests/pybind11_tests.cpp @@ -58,7 +58,7 @@ void bind_ConstructorStats(py::module_ &m) { // registered instances to allow instance cleanup checks (invokes a GC first) .def_static("detail_reg_inst", []() { ConstructorStats::gc(); - return py::detail::get_internals().registered_instances.size(); + return py::detail::num_registered_instances(); }); } @@ -75,26 +75,34 @@ const char *cpp_std() { #endif } -PYBIND11_MODULE(pybind11_tests, m) { +PYBIND11_MODULE(pybind11_tests, m, py::mod_gil_not_used()) { m.doc() = "pybind11 test module"; // Intentionally kept minimal to not create a maintenance chore // ("just enough" to be conclusive). -#if defined(_MSC_FULL_VER) - m.attr("compiler_info") = "MSVC " PYBIND11_TOSTRING(_MSC_FULL_VER); -#elif defined(__VERSION__) +#if defined(__VERSION__) m.attr("compiler_info") = __VERSION__; +#elif defined(_MSC_FULL_VER) + m.attr("compiler_info") = "MSVC " PYBIND11_TOSTRING(_MSC_FULL_VER); #else m.attr("compiler_info") = py::none(); #endif m.attr("cpp_std") = cpp_std(); m.attr("PYBIND11_INTERNALS_ID") = PYBIND11_INTERNALS_ID; + // Free threaded Python uses UINT32_MAX for immortal objects. + m.attr("PYBIND11_REFCNT_IMMORTAL") = UINT32_MAX; m.attr("PYBIND11_SIMPLE_GIL_MANAGEMENT") = #if defined(PYBIND11_SIMPLE_GIL_MANAGEMENT) true; #else false; #endif + m.attr("PYBIND11_NUMPY_1_ONLY") = +#if defined(PYBIND11_NUMPY_1_ONLY) + true; +#else + false; +#endif bind_ConstructorStats(m); diff --git a/wrap/pybind11/tests/pybind11_tests.h b/wrap/pybind11/tests/pybind11_tests.h index a7c00c2f9b..7be58feb6c 100644 --- a/wrap/pybind11/tests/pybind11_tests.h +++ b/wrap/pybind11/tests/pybind11_tests.h @@ -3,6 +3,8 @@ #include #include +#include + namespace py = pybind11; using namespace pybind11::literals; @@ -52,6 +54,17 @@ union IntFloat { float f; }; +class UnusualOpRef { +public: + using NonTrivialType = std::shared_ptr; // Almost any non-trivial type will do. + // Overriding operator& should not break pybind11. + NonTrivialType operator&() { return non_trivial_member; } + NonTrivialType operator&() const { return non_trivial_member; } + +private: + NonTrivialType non_trivial_member; +}; + /// Custom cast-only type that casts to a string "rvalue" or "lvalue" depending on the cast /// context. Used to test recursive casters (e.g. std::tuple, stl containers). struct RValueCaster {}; diff --git a/wrap/pybind11/tests/pytest.ini b/wrap/pybind11/tests/pytest.ini index 792ba361f7..42c3c40c63 100644 --- a/wrap/pybind11/tests/pytest.ini +++ b/wrap/pybind11/tests/pytest.ini @@ -20,3 +20,4 @@ filterwarnings = # bogus numpy ABI warning (see numpy/#432) ignore:.*numpy.dtype size changed.*:RuntimeWarning ignore:.*numpy.ufunc size changed.*:RuntimeWarning + default:The global interpreter lock:RuntimeWarning diff --git a/wrap/pybind11/tests/requirements.txt b/wrap/pybind11/tests/requirements.txt index 4ba1011196..337897bd24 100644 --- a/wrap/pybind11/tests/requirements.txt +++ b/wrap/pybind11/tests/requirements.txt @@ -1,9 +1,13 @@ -build==0.8.0 -numpy==1.21.5; platform_python_implementation=="PyPy" and sys_platform=="linux" and python_version=="3.7" -numpy==1.19.3; platform_python_implementation!="PyPy" and python_version=="3.6" -numpy==1.21.5; platform_python_implementation!="PyPy" and python_version>="3.7" and python_version<"3.10" -numpy==1.22.2; platform_python_implementation!="PyPy" and python_version>="3.10" and python_version<"3.11" -pytest==7.0.0 +--only-binary=:all: +build~=1.0; python_version>="3.7" +numpy~=1.20.0; python_version=="3.7" and platform_python_implementation=="PyPy" +numpy~=1.23.0; python_version=="3.8" and platform_python_implementation=="PyPy" +numpy~=1.25.0; python_version=="3.9" and platform_python_implementation=='PyPy' +numpy~=1.21.5; platform_python_implementation!="PyPy" and python_version>="3.7" and python_version<"3.10" +numpy~=1.22.2; platform_python_implementation!="PyPy" and python_version=="3.10" +numpy~=1.26.0; platform_python_implementation!="PyPy" and python_version>="3.11" and python_version<"3.13" +pytest~=7.0 pytest-timeout -scipy==1.5.4; platform_python_implementation!="PyPy" and python_version<"3.10" -scipy==1.10.0; platform_python_implementation!="PyPy" and python_version=="3.10" +scipy~=1.5.4; platform_python_implementation!="PyPy" and python_version<"3.10" +scipy~=1.8.0; platform_python_implementation!="PyPy" and python_version=="3.10" and sys_platform!='win32' +scipy~=1.11.1; platform_python_implementation!="PyPy" and python_version>="3.11" and python_version<"3.13" and sys_platform!='win32' diff --git a/wrap/pybind11/tests/test_async.py b/wrap/pybind11/tests/test_async.py index 83a4c5036a..4d33ba65f6 100644 --- a/wrap/pybind11/tests/test_async.py +++ b/wrap/pybind11/tests/test_async.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest asyncio = pytest.importorskip("asyncio") diff --git a/wrap/pybind11/tests/test_buffers.py b/wrap/pybind11/tests/test_buffers.py index 63d9d869fd..84a301e250 100644 --- a/wrap/pybind11/tests/test_buffers.py +++ b/wrap/pybind11/tests/test_buffers.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import ctypes import io import struct @@ -219,3 +221,10 @@ def test_ctypes_from_buffer(): assert cinfo.shape == pyinfo.shape assert cinfo.strides == pyinfo.strides assert not cinfo.readonly + + +def test_buffer_docstring(): + assert ( + m.get_buffer_info.__doc__.strip() + == "get_buffer_info(arg0: Buffer) -> pybind11_tests.buffers.buffer_info" + ) diff --git a/wrap/pybind11/tests/test_builtin_casters.cpp b/wrap/pybind11/tests/test_builtin_casters.cpp index 0623b85dc9..292304a63d 100644 --- a/wrap/pybind11/tests/test_builtin_casters.cpp +++ b/wrap/pybind11/tests/test_builtin_casters.cpp @@ -95,7 +95,7 @@ TEST_SUBMODULE(builtin_casters, m) { } // 𝐀, utf16 else { wstr.push_back((wchar_t) mathbfA32); - } // 𝐀, utf32 + } // 𝐀, utf32 wstr.push_back(0x7a); // z m.def("good_utf8_string", []() { @@ -104,10 +104,9 @@ TEST_SUBMODULE(builtin_casters, m) { m.def("good_utf16_string", [=]() { return std::u16string({b16, ib16, cake16_1, cake16_2, mathbfA16_1, mathbfA16_2, z16}); }); // b‽🎂𝐀z - m.def("good_utf32_string", [=]() { - return std::u32string({a32, mathbfA32, cake32, ib32, z32}); - }); // a𝐀🎂‽z - m.def("good_wchar_string", [=]() { return wstr; }); // a‽𝐀z + m.def("good_utf32_string", + [=]() { return std::u32string({a32, mathbfA32, cake32, ib32, z32}); }); // a𝐀🎂‽z + m.def("good_wchar_string", [=]() { return wstr; }); // a‽𝐀z m.def("bad_utf8_string", []() { return std::string("abc\xd0" "def"); @@ -117,9 +116,8 @@ TEST_SUBMODULE(builtin_casters, m) { // UnicodeDecodeError m.def("bad_utf32_string", [=]() { return std::u32string({a32, char32_t(0xd800), z32}); }); if (sizeof(wchar_t) == 2) { - m.def("bad_wchar_string", [=]() { - return std::wstring({wchar_t(0x61), wchar_t(0xd800)}); - }); + m.def("bad_wchar_string", + [=]() { return std::wstring({wchar_t(0x61), wchar_t(0xd800)}); }); } m.def("u8_Z", []() -> char { return 'Z'; }); m.def("u8_eacute", []() -> char { return '\xe9'; }); @@ -236,8 +234,7 @@ TEST_SUBMODULE(builtin_casters, m) { // test_int_convert m.def("int_passthrough", [](int arg) { return arg; }); - m.def( - "int_passthrough_noconvert", [](int arg) { return arg; }, py::arg{}.noconvert()); + m.def("int_passthrough_noconvert", [](int arg) { return arg; }, py::arg{}.noconvert()); // test_tuple m.def( @@ -302,8 +299,7 @@ TEST_SUBMODULE(builtin_casters, m) { // test_bool_caster m.def("bool_passthrough", [](bool arg) { return arg; }); - m.def( - "bool_passthrough_noconvert", [](bool arg) { return arg; }, py::arg{}.noconvert()); + m.def("bool_passthrough_noconvert", [](bool arg) { return arg; }, py::arg{}.noconvert()); // TODO: This should be disabled and fixed in future Intel compilers #if !defined(__INTEL_COMPILER) @@ -311,8 +307,7 @@ TEST_SUBMODULE(builtin_casters, m) { // When compiled with the Intel compiler, this results in segmentation faults when importing // the module. Tested with icc (ICC) 2021.1 Beta 20200827, this should be tested again when // a newer version of icc is available. - m.def( - "bool_passthrough_noconvert2", [](bool arg) { return arg; }, py::arg().noconvert()); + m.def("bool_passthrough_noconvert2", [](bool arg) { return arg; }, py::arg().noconvert()); #endif // test_reference_wrapper diff --git a/wrap/pybind11/tests/test_builtin_casters.py b/wrap/pybind11/tests/test_builtin_casters.py index b1f57bdd98..9aa5926e9c 100644 --- a/wrap/pybind11/tests/test_builtin_casters.py +++ b/wrap/pybind11/tests/test_builtin_casters.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import sys import pytest @@ -352,7 +354,7 @@ def test_tuple(doc): assert ( doc(m.pair_passthrough) == """ - pair_passthrough(arg0: Tuple[bool, str]) -> Tuple[str, bool] + pair_passthrough(arg0: tuple[bool, str]) -> tuple[str, bool] Return a pair in reversed order """ @@ -360,7 +362,7 @@ def test_tuple(doc): assert ( doc(m.tuple_passthrough) == """ - tuple_passthrough(arg0: Tuple[bool, str, int]) -> Tuple[int, str, bool] + tuple_passthrough(arg0: tuple[bool, str, int]) -> tuple[int, str, bool] Return a triple in reversed order """ diff --git a/wrap/pybind11/tests/test_call_policies.cpp b/wrap/pybind11/tests/test_call_policies.cpp index d177008cfe..92924cb452 100644 --- a/wrap/pybind11/tests/test_call_policies.cpp +++ b/wrap/pybind11/tests/test_call_policies.cpp @@ -63,10 +63,8 @@ TEST_SUBMODULE(call_policies, m) { .def("returnNullChildKeepAliveParent", &Parent::returnNullChild, py::keep_alive<0, 1>()) .def_static("staticFunction", &Parent::staticFunction, py::keep_alive<1, 0>()); - m.def( - "free_function", [](Parent *, Child *) {}, py::keep_alive<1, 2>()); - m.def( - "invalid_arg_index", [] {}, py::keep_alive<0, 1>()); + m.def("free_function", [](Parent *, Child *) {}, py::keep_alive<1, 2>()); + m.def("invalid_arg_index", [] {}, py::keep_alive<0, 1>()); #if !defined(PYPY_VERSION) // test_alive_gc @@ -97,7 +95,7 @@ TEST_SUBMODULE(call_policies, m) { }, py::call_guard()); -#if defined(WITH_THREAD) && !defined(PYPY_VERSION) +#if !defined(PYPY_VERSION) // `py::call_guard()` should work in PyPy as well, // but it's unclear how to test it without `PyGILState_GetThisThreadState`. auto report_gil_status = []() { diff --git a/wrap/pybind11/tests/test_call_policies.py b/wrap/pybind11/tests/test_call_policies.py index 6160564123..91670deb37 100644 --- a/wrap/pybind11/tests/test_call_policies.py +++ b/wrap/pybind11/tests/test_call_policies.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest import env # noqa: F401 diff --git a/wrap/pybind11/tests/test_callbacks.py b/wrap/pybind11/tests/test_callbacks.py index 4a652f53e8..ce2a6d2549 100644 --- a/wrap/pybind11/tests/test_callbacks.py +++ b/wrap/pybind11/tests/test_callbacks.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import time from threading import Thread @@ -216,3 +218,10 @@ def test_custom_func(): def test_custom_func2(): assert m.custom_function2(3) == 27 assert m.roundtrip(m.custom_function2)(3) == 27 + + +def test_callback_docstring(): + assert ( + m.test_tuple_unpacking.__doc__.strip() + == "test_tuple_unpacking(arg0: Callable) -> object" + ) diff --git a/wrap/pybind11/tests/test_chrono.py b/wrap/pybind11/tests/test_chrono.py index a29316c38d..ed889fbd6b 100644 --- a/wrap/pybind11/tests/test_chrono.py +++ b/wrap/pybind11/tests/test_chrono.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import datetime import pytest diff --git a/wrap/pybind11/tests/test_class.cpp b/wrap/pybind11/tests/test_class.cpp index 7241bc8818..9001d86b19 100644 --- a/wrap/pybind11/tests/test_class.cpp +++ b/wrap/pybind11/tests/test_class.cpp @@ -403,7 +403,7 @@ TEST_SUBMODULE(class_, m) { // [workaround(intel)] = default does not work here // Removing or defaulting this destructor results in linking errors with the Intel compiler // (in Debug builds only, tested with icpc (ICC) 2021.1 Beta 20200827) - ~PublicistB() override{}; // NOLINT(modernize-use-equals-default) + ~PublicistB() override {}; // NOLINT(modernize-use-equals-default) using ProtectedB::foo; using ProtectedB::get_self; using ProtectedB::void_foo; @@ -461,8 +461,7 @@ TEST_SUBMODULE(class_, m) { py::class_(base, "Nested") .def(py::init<>()) .def("fn", [](Nested &, int, NestBase &, Nested &) {}) - .def( - "fa", [](Nested &, int, NestBase &, Nested &) {}, "a"_a, "b"_a, "c"_a); + .def("fa", [](Nested &, int, NestBase &, Nested &) {}, "a"_a, "b"_a, "c"_a); base.def("g", [](NestBase &, Nested &) {}); base.def("h", []() { return NestBase(); }); diff --git a/wrap/pybind11/tests/test_class.py b/wrap/pybind11/tests/test_class.py index ee7467cf8b..9b2b1d8346 100644 --- a/wrap/pybind11/tests/test_class.py +++ b/wrap/pybind11/tests/test_class.py @@ -1,7 +1,11 @@ +from __future__ import annotations + +from unittest import mock + import pytest import env -from pybind11_tests import ConstructorStats, UserType +from pybind11_tests import PYBIND11_REFCNT_IMMORTAL, ConstructorStats, UserType from pybind11_tests import class_ as m @@ -203,6 +207,18 @@ def __init__(self): assert msg(exc_info.value) == expected +@pytest.mark.parametrize( + "mock_return_value", [None, (1, 2, 3), m.Pet("Polly", "parrot"), m.Dog("Molly")] +) +def test_mock_new(mock_return_value): + with mock.patch.object( + m.Pet, "__new__", return_value=mock_return_value + ) as mock_new: + obj = m.Pet("Noname", "Nospecies") + assert obj is mock_return_value + mock_new.assert_called_once_with(m.Pet, "Noname", "Nospecies") + + def test_automatic_upcasting(): assert type(m.return_class_1()).__name__ == "DerivedClass1" assert type(m.return_class_2()).__name__ == "DerivedClass2" @@ -363,7 +379,9 @@ class PyDog(m.Dog): refcount_3 = getrefcount(cls) assert refcount_1 == refcount_3 - assert refcount_2 > refcount_1 + assert (refcount_2 > refcount_1) or ( + refcount_2 == refcount_1 == PYBIND11_REFCNT_IMMORTAL + ) def test_reentrant_implicit_conversion_failure(msg): diff --git a/wrap/pybind11/tests/test_cmake_build/CMakeLists.txt b/wrap/pybind11/tests/test_cmake_build/CMakeLists.txt index e5aa975cfc..f28bde08e5 100644 --- a/wrap/pybind11/tests/test_cmake_build/CMakeLists.txt +++ b/wrap/pybind11/tests/test_cmake_build/CMakeLists.txt @@ -5,9 +5,8 @@ function(pybind11_add_build_test name) set(build_options "-DCMAKE_CXX_COMPILER=${CMAKE_CXX_COMPILER}") + list(APPEND build_options "-DPYBIND11_FINDPYTHON=${PYBIND11_FINDPYTHON}") if(PYBIND11_FINDPYTHON) - list(APPEND build_options "-DPYBIND11_FINDPYTHON=${PYBIND11_FINDPYTHON}") - if(DEFINED Python_ROOT_DIR) list(APPEND build_options "-DPython_ROOT_DIR=${Python_ROOT_DIR}") endif() diff --git a/wrap/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt b/wrap/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt index d9dcb45e42..2be0aa6596 100644 --- a/wrap/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt +++ b/wrap/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt @@ -1,12 +1,12 @@ cmake_minimum_required(VERSION 3.5) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) endif() project(test_installed_embed CXX) diff --git a/wrap/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt b/wrap/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt index 2f4f642753..fa7795e1e6 100644 --- a/wrap/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt +++ b/wrap/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt @@ -1,13 +1,13 @@ cmake_minimum_required(VERSION 3.5) project(test_installed_module CXX) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) endif() project(test_installed_function CXX) diff --git a/wrap/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt b/wrap/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt index a981e236f5..7e73f42435 100644 --- a/wrap/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt +++ b/wrap/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt @@ -1,12 +1,12 @@ cmake_minimum_required(VERSION 3.5) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) endif() project(test_installed_target CXX) diff --git a/wrap/pybind11/tests/test_cmake_build/main.cpp b/wrap/pybind11/tests/test_cmake_build/main.cpp index e30f2c4b9a..640449c31b 100644 --- a/wrap/pybind11/tests/test_cmake_build/main.cpp +++ b/wrap/pybind11/tests/test_cmake_build/main.cpp @@ -1,6 +1,6 @@ #include namespace py = pybind11; -PYBIND11_MODULE(test_cmake_build, m) { +PYBIND11_MODULE(test_cmake_build, m, py::mod_gil_not_used()) { m.def("add", [](int i, int j) { return i + j; }); } diff --git a/wrap/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt b/wrap/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt index f286746b95..33a366472c 100644 --- a/wrap/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt +++ b/wrap/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt @@ -1,12 +1,12 @@ cmake_minimum_required(VERSION 3.5) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) endif() project(test_subdirectory_embed CXX) @@ -16,6 +16,12 @@ set(PYBIND11_INSTALL CACHE BOOL "") set(PYBIND11_EXPORT_NAME test_export) +# Allow PYTHON_EXECUTABLE if in FINDPYTHON mode and building pybind11's tests +# (makes transition easier while we support both modes). +if(DEFINED PYTHON_EXECUTABLE AND NOT DEFINED Python_EXECUTABLE) + set(Python_EXECUTABLE "${PYTHON_EXECUTABLE}") +endif() + add_subdirectory("${pybind11_SOURCE_DIR}" pybind11) # Test basic target functionality diff --git a/wrap/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt b/wrap/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt index 275a75c0b5..76418a71f3 100644 --- a/wrap/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt +++ b/wrap/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt @@ -1,16 +1,22 @@ cmake_minimum_required(VERSION 3.5) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) endif() project(test_subdirectory_function CXX) +# Allow PYTHON_EXECUTABLE if in FINDPYTHON mode and building pybind11's tests +# (makes transition easier while we support both modes). +if(DEFINED PYTHON_EXECUTABLE AND NOT DEFINED Python_EXECUTABLE) + set(Python_EXECUTABLE "${PYTHON_EXECUTABLE}") +endif() + add_subdirectory("${pybind11_SOURCE_DIR}" pybind11) pybind11_add_module(test_subdirectory_function ../main.cpp) set_target_properties(test_subdirectory_function PROPERTIES OUTPUT_NAME test_cmake_build) diff --git a/wrap/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt b/wrap/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt index 37bb2c56e7..28e9031878 100644 --- a/wrap/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt +++ b/wrap/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt @@ -1,16 +1,22 @@ cmake_minimum_required(VERSION 3.5) -# The `cmake_minimum_required(VERSION 3.5...3.26)` syntax does not work with +# 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.26) +if(${CMAKE_VERSION} VERSION_LESS 3.29) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.26) + cmake_policy(VERSION 3.29) endif() project(test_subdirectory_target CXX) +# Allow PYTHON_EXECUTABLE if in FINDPYTHON mode and building pybind11's tests +# (makes transition easier while we support both modes). +if(DEFINED PYTHON_EXECUTABLE AND NOT DEFINED Python_EXECUTABLE) + set(Python_EXECUTABLE "${PYTHON_EXECUTABLE}") +endif() + add_subdirectory("${pybind11_SOURCE_DIR}" pybind11) add_library(test_subdirectory_target MODULE ../main.cpp) diff --git a/wrap/pybind11/tests/test_cmake_build/test.py b/wrap/pybind11/tests/test_cmake_build/test.py index 807fd43b4a..bb4c20e0cb 100644 --- a/wrap/pybind11/tests/test_cmake_build/test.py +++ b/wrap/pybind11/tests/test_cmake_build/test.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import sys import test_cmake_build diff --git a/wrap/pybind11/tests/test_const_name.py b/wrap/pybind11/tests/test_const_name.py index a145f0bbb5..f520249456 100644 --- a/wrap/pybind11/tests/test_const_name.py +++ b/wrap/pybind11/tests/test_const_name.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import const_name as m diff --git a/wrap/pybind11/tests/test_constants_and_functions.cpp b/wrap/pybind11/tests/test_constants_and_functions.cpp index 312edca9e0..bf42b41551 100644 --- a/wrap/pybind11/tests/test_constants_and_functions.cpp +++ b/wrap/pybind11/tests/test_constants_and_functions.cpp @@ -54,7 +54,11 @@ int f2(int x) noexcept(true) { return x + 2; } int f3(int x) noexcept(false) { return x + 3; } PYBIND11_WARNING_PUSH PYBIND11_WARNING_DISABLE_GCC("-Wdeprecated") +#if defined(__clang_major__) && __clang_major__ >= 5 +PYBIND11_WARNING_DISABLE_CLANG("-Wdeprecated-dynamic-exception-spec") +#else PYBIND11_WARNING_DISABLE_CLANG("-Wdeprecated") +#endif // NOLINTNEXTLINE(modernize-use-noexcept) int f4(int x) throw() { return x + 4; } // Deprecated equivalent to noexcept(true) PYBIND11_WARNING_POP diff --git a/wrap/pybind11/tests/test_constants_and_functions.py b/wrap/pybind11/tests/test_constants_and_functions.py index a1142461c0..63004e1b6c 100644 --- a/wrap/pybind11/tests/test_constants_and_functions.py +++ b/wrap/pybind11/tests/test_constants_and_functions.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest m = pytest.importorskip("pybind11_tests.constants_and_functions") diff --git a/wrap/pybind11/tests/test_copy_move.cpp b/wrap/pybind11/tests/test_copy_move.cpp index f54733550a..ddffbe3a94 100644 --- a/wrap/pybind11/tests/test_copy_move.cpp +++ b/wrap/pybind11/tests/test_copy_move.cpp @@ -157,6 +157,13 @@ struct type_caster { PYBIND11_NAMESPACE_END(detail) PYBIND11_NAMESPACE_END(pybind11) +namespace { + +py::object CastUnusualOpRefConstRef(const UnusualOpRef &cref) { return py::cast(cref); } +py::object CastUnusualOpRefMovable(UnusualOpRef &&mvbl) { return py::cast(std::move(mvbl)); } + +} // namespace + TEST_SUBMODULE(copy_move_policies, m) { // test_lacking_copy_ctor py::class_(m, "lacking_copy_ctor") @@ -289,11 +296,15 @@ TEST_SUBMODULE(copy_move_policies, m) { "get_moveissue1", [](int i) { return std::unique_ptr(new MoveIssue1(i)); }, py::return_value_policy::move); - m.def( - "get_moveissue2", [](int i) { return MoveIssue2(i); }, py::return_value_policy::move); + m.def("get_moveissue2", [](int i) { return MoveIssue2(i); }, py::return_value_policy::move); // Make sure that cast from pytype rvalue to other pytype works m.def("get_pytype_rvalue_castissue", [](double i) { return py::float_(i).cast(); }); + + py::class_(m, "UnusualOpRef"); + m.def("CallCastUnusualOpRefConstRef", + []() { return CastUnusualOpRefConstRef(UnusualOpRef()); }); + m.def("CallCastUnusualOpRefMovable", []() { return CastUnusualOpRefMovable(UnusualOpRef()); }); } /* diff --git a/wrap/pybind11/tests/test_copy_move.py b/wrap/pybind11/tests/test_copy_move.py index 9fef089339..ee046305f5 100644 --- a/wrap/pybind11/tests/test_copy_move.py +++ b/wrap/pybind11/tests/test_copy_move.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import copy_move_policies as m @@ -130,3 +132,9 @@ def test_pytype_rvalue_cast(): value = m.get_pytype_rvalue_castissue(1.0) assert value == 1 + + +def test_unusual_op_ref(): + # Merely to test that this still exists and built successfully. + assert m.CallCastUnusualOpRefConstRef().__class__.__name__ == "UnusualOpRef" + assert m.CallCastUnusualOpRefMovable().__class__.__name__ == "UnusualOpRef" diff --git a/wrap/pybind11/tests/test_custom_type_casters.cpp b/wrap/pybind11/tests/test_custom_type_casters.cpp index b4af02a452..0ca2d25414 100644 --- a/wrap/pybind11/tests/test_custom_type_casters.cpp +++ b/wrap/pybind11/tests/test_custom_type_casters.cpp @@ -134,6 +134,16 @@ struct type_caster : public other_lib::my_caster {}; } // namespace detail } // namespace PYBIND11_NAMESPACE +// This simply is required to compile +namespace ADL_issue { +template +OutStringType concat(Args &&...) { + return OutStringType(); +} + +struct test {}; +} // namespace ADL_issue + TEST_SUBMODULE(custom_type_casters, m) { // test_custom_type_casters @@ -175,14 +185,10 @@ TEST_SUBMODULE(custom_type_casters, m) { py::arg_v(nullptr, ArgInspector1()).noconvert(true), py::arg() = ArgAlwaysConverts()); - m.def( - "floats_preferred", [](double f) { return 0.5 * f; }, "f"_a); - m.def( - "floats_only", [](double f) { return 0.5 * f; }, "f"_a.noconvert()); - m.def( - "ints_preferred", [](int i) { return i / 2; }, "i"_a); - m.def( - "ints_only", [](int i) { return i / 2; }, "i"_a.noconvert()); + m.def("floats_preferred", [](double f) { return 0.5 * f; }, "f"_a); + m.def("floats_only", [](double f) { return 0.5 * f; }, "f"_a.noconvert()); + m.def("ints_preferred", [](int i) { return i / 2; }, "i"_a); + m.def("ints_only", [](int i) { return i / 2; }, "i"_a.noconvert()); // test_custom_caster_destruction // Test that `take_ownership` works on types with a custom type caster when given a pointer @@ -206,4 +212,6 @@ TEST_SUBMODULE(custom_type_casters, m) { py::return_value_policy::reference); m.def("other_lib_type", [](other_lib::MyType x) { return x; }); + + m.def("_adl_issue", [](const ADL_issue::test &) {}); } diff --git a/wrap/pybind11/tests/test_custom_type_casters.py b/wrap/pybind11/tests/test_custom_type_casters.py index 3a00ea964b..689b1e9cb6 100644 --- a/wrap/pybind11/tests/test_custom_type_casters.py +++ b/wrap/pybind11/tests/test_custom_type_casters.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import custom_type_casters as m diff --git a/wrap/pybind11/tests/test_custom_type_setup.py b/wrap/pybind11/tests/test_custom_type_setup.py index e63ff5758e..56922c6dd1 100644 --- a/wrap/pybind11/tests/test_custom_type_setup.py +++ b/wrap/pybind11/tests/test_custom_type_setup.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import gc import weakref diff --git a/wrap/pybind11/tests/test_docstring_options.cpp b/wrap/pybind11/tests/test_docstring_options.cpp index dda1cf6e41..de045a7ca1 100644 --- a/wrap/pybind11/tests/test_docstring_options.cpp +++ b/wrap/pybind11/tests/test_docstring_options.cpp @@ -15,37 +15,26 @@ TEST_SUBMODULE(docstring_options, m) { py::options options; options.disable_function_signatures(); - m.def( - "test_function1", [](int, int) {}, py::arg("a"), py::arg("b")); - m.def( - "test_function2", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); - - m.def( - "test_overloaded1", [](int) {}, py::arg("i"), "Overload docstring"); - m.def( - "test_overloaded1", [](double) {}, py::arg("d")); - - m.def( - "test_overloaded2", [](int) {}, py::arg("i"), "overload docstring 1"); - m.def( - "test_overloaded2", [](double) {}, py::arg("d"), "overload docstring 2"); - - m.def( - "test_overloaded3", [](int) {}, py::arg("i")); - m.def( - "test_overloaded3", [](double) {}, py::arg("d"), "Overload docstr"); + m.def("test_function1", [](int, int) {}, py::arg("a"), py::arg("b")); + m.def("test_function2", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + + m.def("test_overloaded1", [](int) {}, py::arg("i"), "Overload docstring"); + m.def("test_overloaded1", [](double) {}, py::arg("d")); + + m.def("test_overloaded2", [](int) {}, py::arg("i"), "overload docstring 1"); + m.def("test_overloaded2", [](double) {}, py::arg("d"), "overload docstring 2"); + + m.def("test_overloaded3", [](int) {}, py::arg("i")); + m.def("test_overloaded3", [](double) {}, py::arg("d"), "Overload docstr"); options.enable_function_signatures(); - m.def( - "test_function3", [](int, int) {}, py::arg("a"), py::arg("b")); - m.def( - "test_function4", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + m.def("test_function3", [](int, int) {}, py::arg("a"), py::arg("b")); + m.def("test_function4", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); options.disable_function_signatures().disable_user_defined_docstrings(); - m.def( - "test_function5", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + m.def("test_function5", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); { py::options nested_options; @@ -59,8 +48,7 @@ TEST_SUBMODULE(docstring_options, m) { } } - m.def( - "test_function7", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + m.def("test_function7", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); { py::options options; diff --git a/wrap/pybind11/tests/test_docstring_options.py b/wrap/pybind11/tests/test_docstring_options.py index e6f5a9d987..09fc8ac254 100644 --- a/wrap/pybind11/tests/test_docstring_options.py +++ b/wrap/pybind11/tests/test_docstring_options.py @@ -1,3 +1,5 @@ +from __future__ import annotations + from pybind11_tests import docstring_options as m diff --git a/wrap/pybind11/tests/test_eigen_matrix.cpp b/wrap/pybind11/tests/test_eigen_matrix.cpp index 554cc4d7f8..21261bfc2f 100644 --- a/wrap/pybind11/tests/test_eigen_matrix.cpp +++ b/wrap/pybind11/tests/test_eigen_matrix.cpp @@ -330,6 +330,21 @@ TEST_SUBMODULE(eigen_matrix, m) { m.def("dense_c", [mat]() -> DenseMatrixC { return DenseMatrixC(mat); }); m.def("dense_copy_r", [](const DenseMatrixR &m) -> DenseMatrixR { return m; }); m.def("dense_copy_c", [](const DenseMatrixC &m) -> DenseMatrixC { return m; }); + // test_defaults + bool have_numpy = true; + try { + py::module_::import("numpy"); + } catch (const py::error_already_set &) { + have_numpy = false; + } + if (have_numpy) { + py::module_::import("numpy"); + Eigen::Matrix defaultMatrix = Eigen::Matrix3d::Identity(); + m.def("defaults_mat", [](const Eigen::Matrix3d &) {}, py::arg("mat") = defaultMatrix); + + Eigen::VectorXd defaultVector = Eigen::VectorXd::Ones(32); + m.def("defaults_vec", [](const Eigen::VectorXd &) {}, py::arg("vec") = defaultMatrix); + } // test_sparse, test_sparse_signature m.def("sparse_r", [mat]() -> SparseMatrixR { // NOLINTNEXTLINE(clang-analyzer-core.uninitialized.UndefReturn) diff --git a/wrap/pybind11/tests/test_eigen_matrix.py b/wrap/pybind11/tests/test_eigen_matrix.py index b2e76740b1..e1d7433f15 100644 --- a/wrap/pybind11/tests/test_eigen_matrix.py +++ b/wrap/pybind11/tests/test_eigen_matrix.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import ConstructorStats @@ -608,7 +610,9 @@ def test_both_ref_mutators(): def test_nocopy_wrapper(): # get_elem requires a column-contiguous matrix reference, but should be # callable with other types of matrix (via copying): - int_matrix_colmajor = np.array([[1, 2, 3], [4, 5, 6], [7, 8, 9]], order="F") + int_matrix_colmajor = np.array( + [[1, 2, 3], [4, 5, 6], [7, 8, 9]], dtype="l", order="F" + ) dbl_matrix_colmajor = np.array( int_matrix_colmajor, dtype="double", order="F", copy=True ) @@ -716,6 +720,11 @@ def test_dense_signature(doc): ) +def test_defaults(doc): + assert "\n" not in str(doc(m.defaults_mat)) + assert "\n" not in str(doc(m.defaults_vec)) + + def test_named_arguments(): a = np.array([[1.0, 2], [3, 4], [5, 6]]) b = np.ones((2, 1)) diff --git a/wrap/pybind11/tests/test_eigen_tensor.inl b/wrap/pybind11/tests/test_eigen_tensor.inl index d864ce7379..25cf29f15b 100644 --- a/wrap/pybind11/tests/test_eigen_tensor.inl +++ b/wrap/pybind11/tests/test_eigen_tensor.inl @@ -121,8 +121,7 @@ void init_tensor_module(pybind11::module &m) { []() { return &get_fixed_tensor(); }, py::return_value_policy::copy); - m.def( - "copy_tensor", []() { return &get_tensor(); }, py::return_value_policy::copy); + m.def("copy_tensor", []() { return &get_tensor(); }, py::return_value_policy::copy); m.def( "copy_const_tensor", diff --git a/wrap/pybind11/tests/test_eigen_tensor.py b/wrap/pybind11/tests/test_eigen_tensor.py index 3e7ee6b7f2..a2b99d9d7d 100644 --- a/wrap/pybind11/tests/test_eigen_tensor.py +++ b/wrap/pybind11/tests/test_eigen_tensor.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import sys import pytest diff --git a/wrap/pybind11/tests/test_embed/CMakeLists.txt b/wrap/pybind11/tests/test_embed/CMakeLists.txt index 09a3693999..9b539cd42d 100644 --- a/wrap/pybind11/tests/test_embed/CMakeLists.txt +++ b/wrap/pybind11/tests/test_embed/CMakeLists.txt @@ -7,6 +7,13 @@ if("${PYTHON_MODULE_EXTENSION}" MATCHES "pypy" OR "${Python_INTERPRETER_ID}" STR return() endif() +if(TARGET Python::Module AND NOT TARGET Python::Python) + message(STATUS "Skipping embed test since no embed libs found") + add_custom_target(cpptest) # Dummy target since embedding is not supported. + set(_suppress_unused_variable_warning "${DOWNLOAD_CATCH}") + return() +endif() + find_package(Catch 2.13.9) if(CATCH_FOUND) diff --git a/wrap/pybind11/tests/test_embed/external_module.cpp b/wrap/pybind11/tests/test_embed/external_module.cpp index 5c482fe061..6564ecbef5 100644 --- a/wrap/pybind11/tests/test_embed/external_module.cpp +++ b/wrap/pybind11/tests/test_embed/external_module.cpp @@ -6,7 +6,7 @@ namespace py = pybind11; * modules aren't preserved over a finalize/initialize. */ -PYBIND11_MODULE(external_module, m) { +PYBIND11_MODULE(external_module, m, py::mod_gil_not_used()) { class A { public: explicit A(int value) : v{value} {}; diff --git a/wrap/pybind11/tests/test_embed/test_interpreter.py b/wrap/pybind11/tests/test_embed/test_interpreter.py index f279449722..424d36dea2 100644 --- a/wrap/pybind11/tests/test_embed/test_interpreter.py +++ b/wrap/pybind11/tests/test_embed/test_interpreter.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import sys from widget_module import Widget diff --git a/wrap/pybind11/tests/test_embed/test_trampoline.py b/wrap/pybind11/tests/test_embed/test_trampoline.py index 8e14e8ef0b..b8ff3eba28 100644 --- a/wrap/pybind11/tests/test_embed/test_trampoline.py +++ b/wrap/pybind11/tests/test_embed/test_trampoline.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import trampoline_module diff --git a/wrap/pybind11/tests/test_enum.py b/wrap/pybind11/tests/test_enum.py index 4e85d29c31..9914b90013 100644 --- a/wrap/pybind11/tests/test_enum.py +++ b/wrap/pybind11/tests/test_enum.py @@ -1,4 +1,5 @@ # ruff: noqa: SIM201 SIM300 SIM202 +from __future__ import annotations import pytest @@ -60,9 +61,7 @@ def test_unscoped_enum(): ETwo : Docstring for ETwo - EThree : Docstring for EThree""".split( - "\n" - ): + EThree : Docstring for EThree""".split("\n"): assert docstring_line in m.UnscopedEnum.__doc__ # Unscoped enums will accept ==/!= int comparisons @@ -264,3 +263,8 @@ def test_docstring_signatures(): for attr in enum_type.__dict__.values(): # Issue #2623/PR #2637: Add argument names to enum_ methods assert "arg0" not in (attr.__doc__ or "") + + +def test_str_signature(): + for enum_type in [m.ScopedEnum, m.UnscopedEnum]: + assert enum_type.__str__.__doc__.startswith("__str__") diff --git a/wrap/pybind11/tests/test_eval.py b/wrap/pybind11/tests/test_eval.py index 51b6b796b4..45b68ece72 100644 --- a/wrap/pybind11/tests/test_eval.py +++ b/wrap/pybind11/tests/test_eval.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import os import pytest diff --git a/wrap/pybind11/tests/test_eval_call.py b/wrap/pybind11/tests/test_eval_call.py index fd1da2a5cc..a677249d4b 100644 --- a/wrap/pybind11/tests/test_eval_call.py +++ b/wrap/pybind11/tests/test_eval_call.py @@ -1,4 +1,5 @@ # This file is called from 'test_eval.py' +from __future__ import annotations if "call_test2" in locals(): call_test2(y) # noqa: F821 undefined name diff --git a/wrap/pybind11/tests/test_exceptions.cpp b/wrap/pybind11/tests/test_exceptions.cpp index 854c7e6f76..c1d05bb241 100644 --- a/wrap/pybind11/tests/test_exceptions.cpp +++ b/wrap/pybind11/tests/test_exceptions.cpp @@ -6,6 +6,8 @@ All rights reserved. Use of this source code is governed by a BSD-style license that can be found in the LICENSE file. */ +#include + #include "test_exceptions.h" #include "local_bindings.h" @@ -25,6 +27,10 @@ class MyException : public std::exception { std::string message = ""; }; +class MyExceptionUseDeprecatedOperatorCall : public MyException { + using MyException::MyException; +}; + // A type that should be translated to a standard Python exception class MyException2 : public std::exception { public: @@ -109,8 +115,10 @@ TEST_SUBMODULE(exceptions, m) { m.def("throw_std_exception", []() { throw std::runtime_error("This exception was intentionally thrown."); }); - // make a new custom exception and use it as a translation target - static py::exception ex(m, "MyException"); + // PLEASE KEEP IN SYNC with docs/advanced/exceptions.rst + PYBIND11_CONSTINIT static py::gil_safe_call_once_and_store ex_storage; + ex_storage.call_once_and_store_result( + [&]() { return py::exception(m, "MyException"); }); py::register_exception_translator([](std::exception_ptr p) { try { if (p) { @@ -118,7 +126,32 @@ TEST_SUBMODULE(exceptions, m) { } } catch (const MyException &e) { // Set MyException as the active python error - ex(e.what()); + py::set_error(ex_storage.get_stored(), e.what()); + } + }); + + // Same as above, but using the deprecated `py::exception<>::operator()` + // We want to be sure it still works, until it's removed. + static const auto *const exd = new py::exception( + m, "MyExceptionUseDeprecatedOperatorCall"); + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) { + std::rethrow_exception(p); + } + } catch (const MyExceptionUseDeprecatedOperatorCall &e) { +#if defined(__INTEL_COMPILER) || defined(__NVCOMPILER) + // It is not worth the trouble dealing with warning suppressions for these compilers. + // Falling back to the recommended approach to keep the test code simple. + py::set_error(*exd, e.what()); +#else + PYBIND11_WARNING_PUSH + PYBIND11_WARNING_DISABLE_CLANG("-Wdeprecated-declarations") + PYBIND11_WARNING_DISABLE_GCC("-Wdeprecated-declarations") + PYBIND11_WARNING_DISABLE_MSVC(4996) + (*exd)(e.what()); + PYBIND11_WARNING_POP +#endif } }); @@ -132,7 +165,7 @@ TEST_SUBMODULE(exceptions, m) { } } catch (const MyException2 &e) { // Translate this exception to a standard RuntimeError - PyErr_SetString(PyExc_RuntimeError, e.what()); + py::set_error(PyExc_RuntimeError, e.what()); } }); @@ -162,11 +195,16 @@ TEST_SUBMODULE(exceptions, m) { std::rethrow_exception(p); } } catch (const MyException6 &e) { - PyErr_SetString(PyExc_RuntimeError, e.what()); + py::set_error(PyExc_RuntimeError, e.what()); } }); - m.def("throws1", []() { throw MyException("this error should go to a custom type"); }); + m.def("throws1", + []() { throw MyException("this error should go to py::exception"); }); + m.def("throws1d", []() { + throw MyExceptionUseDeprecatedOperatorCall( + "this error should go to py::exception"); + }); m.def("throws2", []() { throw MyException2("this error should go to a standard Python exception"); }); m.def("throws3", []() { throw MyException3("this error cannot be translated"); }); @@ -222,7 +260,7 @@ TEST_SUBMODULE(exceptions, m) { m.def("throw_already_set", [](bool err) { if (err) { - PyErr_SetString(PyExc_ValueError, "foo"); + py::set_error(PyExc_ValueError, "foo"); } try { throw py::error_already_set(); @@ -238,7 +276,7 @@ TEST_SUBMODULE(exceptions, m) { } PyErr_Clear(); if (err) { - PyErr_SetString(PyExc_ValueError, "foo"); + py::set_error(PyExc_ValueError, "foo"); } throw py::error_already_set(); }); @@ -247,7 +285,7 @@ TEST_SUBMODULE(exceptions, m) { bool retval = false; try { PythonCallInDestructor set_dict_in_destructor(d); - PyErr_SetString(PyExc_ValueError, "foo"); + py::set_error(PyExc_ValueError, "foo"); throw py::error_already_set(); } catch (const py::error_already_set &) { retval = true; @@ -282,14 +320,14 @@ TEST_SUBMODULE(exceptions, m) { m.def("throw_should_be_translated_to_key_error", []() { throw shared_exception(); }); m.def("raise_from", []() { - PyErr_SetString(PyExc_ValueError, "inner"); + py::set_error(PyExc_ValueError, "inner"); py::raise_from(PyExc_ValueError, "outer"); throw py::error_already_set(); }); m.def("raise_from_already_set", []() { try { - PyErr_SetString(PyExc_ValueError, "inner"); + py::set_error(PyExc_ValueError, "inner"); throw py::error_already_set(); } catch (py::error_already_set &e) { py::raise_from(e, PyExc_ValueError, "outer"); @@ -306,7 +344,7 @@ TEST_SUBMODULE(exceptions, m) { }); m.def("error_already_set_what", [](const py::object &exc_type, const py::object &exc_value) { - PyErr_SetObject(exc_type.ptr(), exc_value.ptr()); + py::set_error(exc_type, exc_value); std::string what = py::error_already_set().what(); bool py_err_set_after_what = (PyErr_Occurred() != nullptr); PyErr_Clear(); @@ -321,7 +359,7 @@ TEST_SUBMODULE(exceptions, m) { }); m.def("test_error_already_set_double_restore", [](bool dry_run) { - PyErr_SetString(PyExc_ValueError, "Random error."); + py::set_error(PyExc_ValueError, "Random error."); py::error_already_set e; e.restore(); PyErr_Clear(); @@ -344,4 +382,7 @@ TEST_SUBMODULE(exceptions, m) { // function returns None instead of int, should give a useful error message fn().cast(); }); + + // m.def("pass_exception_void", [](const py::exception&) {}); // Does not compile. + m.def("return_exception_void", []() { return py::exception(); }); } diff --git a/wrap/pybind11/tests/test_exceptions.h b/wrap/pybind11/tests/test_exceptions.h index 03684b89fa..2eaa3d3d16 100644 --- a/wrap/pybind11/tests/test_exceptions.h +++ b/wrap/pybind11/tests/test_exceptions.h @@ -9,5 +9,5 @@ class PYBIND11_EXPORT_EXCEPTION shared_exception : public pybind11::builtin_exce public: using builtin_exception::builtin_exception; explicit shared_exception() : shared_exception("") {} - void set_error() const override { PyErr_SetString(PyExc_RuntimeError, what()); } + void set_error() const override { py::set_error(PyExc_RuntimeError, what()); } }; diff --git a/wrap/pybind11/tests/test_exceptions.py b/wrap/pybind11/tests/test_exceptions.py index ccac4536d6..b33997eeea 100644 --- a/wrap/pybind11/tests/test_exceptions.py +++ b/wrap/pybind11/tests/test_exceptions.py @@ -1,10 +1,12 @@ +from __future__ import annotations + import sys import pytest import env import pybind11_cross_module_tests as cm -import pybind11_tests # noqa: F401 +import pybind11_tests from pybind11_tests import exceptions as m @@ -139,7 +141,15 @@ def test_custom(msg): # Can we catch a MyException? with pytest.raises(m.MyException) as excinfo: m.throws1() - assert msg(excinfo.value) == "this error should go to a custom type" + assert msg(excinfo.value) == "this error should go to py::exception" + + # Can we catch a MyExceptionUseDeprecatedOperatorCall? + with pytest.raises(m.MyExceptionUseDeprecatedOperatorCall) as excinfo: + m.throws1d() + assert ( + msg(excinfo.value) + == "this error should go to py::exception" + ) # Can we translate to standard Python exceptions? with pytest.raises(RuntimeError) as excinfo: @@ -240,6 +250,11 @@ def pycatch(exctype, f, *args): # noqa: ARG001 assert str(excinfo.value) == "this is a helper-defined translated exception" +# TODO: Investigate this crash, see pybind/pybind11#5062 for background +@pytest.mark.skipif( + sys.platform.startswith("win32") and "Clang" in pybind11_tests.compiler_info, + reason="Started segfaulting February 2024", +) def test_throw_nested_exception(): with pytest.raises(RuntimeError) as excinfo: m.throw_nested_exception() @@ -411,3 +426,9 @@ def test_fn_cast_int_exception(): assert str(excinfo.value).startswith( "Unable to cast Python instance of type to C++ type" ) + + +def test_return_exception_void(): + with pytest.raises(TypeError) as excinfo: + m.return_exception_void() + assert "Exception" in str(excinfo.value) diff --git a/wrap/pybind11/tests/test_factory_constructors.py b/wrap/pybind11/tests/test_factory_constructors.py index 04df80260d..0ddad5e323 100644 --- a/wrap/pybind11/tests/test_factory_constructors.py +++ b/wrap/pybind11/tests/test_factory_constructors.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import re import pytest @@ -77,7 +79,7 @@ def test_init_factory_signature(msg): 1. m.factory_constructors.TestFactory1(arg0: m.factory_constructors.tag.unique_ptr_tag, arg1: int) 2. m.factory_constructors.TestFactory1(arg0: str) 3. m.factory_constructors.TestFactory1(arg0: m.factory_constructors.tag.pointer_tag) - 4. m.factory_constructors.TestFactory1(arg0: handle, arg1: int, arg2: handle) + 4. m.factory_constructors.TestFactory1(arg0: object, arg1: int, arg2: object) Invoked with: 'invalid', 'constructor', 'arguments' """ @@ -95,7 +97,7 @@ def test_init_factory_signature(msg): 3. __init__(self: m.factory_constructors.TestFactory1, arg0: m.factory_constructors.tag.pointer_tag) -> None - 4. __init__(self: m.factory_constructors.TestFactory1, arg0: handle, arg1: int, arg2: handle) -> None + 4. __init__(self: m.factory_constructors.TestFactory1, arg0: object, arg1: int, arg2: object) -> None """ ) diff --git a/wrap/pybind11/tests/test_gil_scoped.py b/wrap/pybind11/tests/test_gil_scoped.py index fc8af9b77c..a183876845 100644 --- a/wrap/pybind11/tests/test_gil_scoped.py +++ b/wrap/pybind11/tests/test_gil_scoped.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import multiprocessing import sys import threading diff --git a/wrap/pybind11/tests/test_iostream.py b/wrap/pybind11/tests/test_iostream.py index d283eb1520..f7eeff502b 100644 --- a/wrap/pybind11/tests/test_iostream.py +++ b/wrap/pybind11/tests/test_iostream.py @@ -1,3 +1,5 @@ +from __future__ import annotations + from contextlib import redirect_stderr, redirect_stdout from io import StringIO @@ -34,7 +36,7 @@ def test_captured_large_string(capsys): def test_captured_utf8_2byte_offset0(capsys): - msg = "\u07FF" + msg = "\u07ff" msg = "" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -44,7 +46,7 @@ def test_captured_utf8_2byte_offset0(capsys): def test_captured_utf8_2byte_offset1(capsys): - msg = "\u07FF" + msg = "\u07ff" msg = "1" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -54,7 +56,7 @@ def test_captured_utf8_2byte_offset1(capsys): def test_captured_utf8_3byte_offset0(capsys): - msg = "\uFFFF" + msg = "\uffff" msg = "" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -64,7 +66,7 @@ def test_captured_utf8_3byte_offset0(capsys): def test_captured_utf8_3byte_offset1(capsys): - msg = "\uFFFF" + msg = "\uffff" msg = "1" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -74,7 +76,7 @@ def test_captured_utf8_3byte_offset1(capsys): def test_captured_utf8_3byte_offset2(capsys): - msg = "\uFFFF" + msg = "\uffff" msg = "12" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -84,7 +86,7 @@ def test_captured_utf8_3byte_offset2(capsys): def test_captured_utf8_4byte_offset0(capsys): - msg = "\U0010FFFF" + msg = "\U0010ffff" msg = "" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -94,7 +96,7 @@ def test_captured_utf8_4byte_offset0(capsys): def test_captured_utf8_4byte_offset1(capsys): - msg = "\U0010FFFF" + msg = "\U0010ffff" msg = "1" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -104,7 +106,7 @@ def test_captured_utf8_4byte_offset1(capsys): def test_captured_utf8_4byte_offset2(capsys): - msg = "\U0010FFFF" + msg = "\U0010ffff" msg = "12" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) @@ -114,7 +116,7 @@ def test_captured_utf8_4byte_offset2(capsys): def test_captured_utf8_4byte_offset3(capsys): - msg = "\U0010FFFF" + msg = "\U0010ffff" msg = "123" + msg * (1024 // len(msg) + 1) m.captured_output_default(msg) diff --git a/wrap/pybind11/tests/test_kwargs_and_defaults.cpp b/wrap/pybind11/tests/test_kwargs_and_defaults.cpp index 77e72c0c70..bc76ec7c2d 100644 --- a/wrap/pybind11/tests/test_kwargs_and_defaults.cpp +++ b/wrap/pybind11/tests/test_kwargs_and_defaults.cpp @@ -22,8 +22,7 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { m.def("kw_func0", kw_func); m.def("kw_func1", kw_func, py::arg("x"), py::arg("y")); m.def("kw_func2", kw_func, py::arg("x") = 100, py::arg("y") = 200); - m.def( - "kw_func3", [](const char *) {}, py::arg("data") = std::string("Hello world!")); + m.def("kw_func3", [](const char *) {}, py::arg("data") = std::string("Hello world!")); /* A fancier default argument */ std::vector list{{13, 17}}; @@ -42,6 +41,50 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { m.def("kw_func_udl", kw_func, "x"_a, "y"_a = 300); m.def("kw_func_udl_z", kw_func, "x"_a, "y"_a = 0); + // test line breaks in default argument representation + struct CustomRepr { + std::string repr_string; + + explicit CustomRepr(const std::string &repr) : repr_string(repr) {} + + std::string __repr__() const { return repr_string; } + }; + + py::class_(m, "CustomRepr") + .def(py::init()) + .def("__repr__", &CustomRepr::__repr__); + + m.def( + "kw_lb_func0", + [](const CustomRepr &) {}, + py::arg("custom") = CustomRepr(" array([[A, B], [C, D]]) ")); + m.def( + "kw_lb_func1", + [](const CustomRepr &) {}, + py::arg("custom") = CustomRepr(" array([[A, B],\n[C, D]]) ")); + m.def( + "kw_lb_func2", + [](const CustomRepr &) {}, + py::arg("custom") = CustomRepr("\v\n array([[A, B], [C, D]])")); + m.def( + "kw_lb_func3", + [](const CustomRepr &) {}, + py::arg("custom") = CustomRepr("array([[A, B], [C, D]]) \f\n")); + m.def( + "kw_lb_func4", + [](const CustomRepr &) {}, + py::arg("custom") = CustomRepr("array([[A, B],\n\f\n[C, D]])")); + m.def( + "kw_lb_func5", + [](const CustomRepr &) {}, + py::arg("custom") = CustomRepr("array([[A, B],\r [C, D]])")); + m.def("kw_lb_func6", [](const CustomRepr &) {}, py::arg("custom") = CustomRepr(" \v\t ")); + m.def( + "kw_lb_func7", + [](const std::string &) {}, + py::arg("str_arg") = "First line.\n Second line."); + m.def("kw_lb_func8", [](const CustomRepr &) {}, py::arg("custom") = CustomRepr("")); + // test_args_and_kwargs m.def("args_function", [](py::args args) -> py::tuple { PYBIND11_WARNING_PUSH @@ -107,10 +150,13 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { // test_args_refcount // PyPy needs a garbage collection to get the reference count values to match CPython's behaviour +// PyPy uses the top few bits for REFCNT_FROM_PYPY & REFCNT_FROM_PYPY_LIGHT, so truncate #ifdef PYPY_VERSION # define GC_IF_NEEDED ConstructorStats::gc() +# define REFCNT(x) (int) Py_REFCNT(x) #else # define GC_IF_NEEDED +# define REFCNT(x) Py_REFCNT(x) #endif m.def("arg_refcount_h", [](py::handle h) { GC_IF_NEEDED; @@ -129,7 +175,7 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { py::tuple t(a.size()); for (size_t i = 0; i < a.size(); i++) { // Use raw Python API here to avoid an extra, intermediate incref on the tuple item: - t[i] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); + t[i] = REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); } return t; }); @@ -139,7 +185,7 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { t[0] = o.ref_count(); for (size_t i = 0; i < a.size(); i++) { // Use raw Python API here to avoid an extra, intermediate incref on the tuple item: - t[i + 1] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); + t[i + 1] = REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); } return t; }); @@ -233,11 +279,9 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { // These should fail to compile: #ifdef PYBIND11_NEVER_DEFINED_EVER // argument annotations are required when using kw_only - m.def( - "bad_kw_only1", [](int) {}, py::kw_only()); + m.def("bad_kw_only1", [](int) {}, py::kw_only()); // can't specify both `py::kw_only` and a `py::args` argument - m.def( - "bad_kw_only2", [](int i, py::args) {}, py::kw_only(), "i"_a); + m.def("bad_kw_only2", [](int i, py::args) {}, py::kw_only(), "i"_a); #endif // test_function_signatures (along with most of the above) diff --git a/wrap/pybind11/tests/test_kwargs_and_defaults.py b/wrap/pybind11/tests/test_kwargs_and_defaults.py index 7174726fce..b9b1a7ea87 100644 --- a/wrap/pybind11/tests/test_kwargs_and_defaults.py +++ b/wrap/pybind11/tests/test_kwargs_and_defaults.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import kwargs_and_defaults as m @@ -8,7 +10,7 @@ def test_function_signatures(doc): assert doc(m.kw_func1) == "kw_func1(x: int, y: int) -> str" assert doc(m.kw_func2) == "kw_func2(x: int = 100, y: int = 200) -> str" assert doc(m.kw_func3) == "kw_func3(data: str = 'Hello world!') -> None" - assert doc(m.kw_func4) == "kw_func4(myList: List[int] = [13, 17]) -> str" + assert doc(m.kw_func4) == "kw_func4(myList: list[int] = [13, 17]) -> str" assert doc(m.kw_func_udl) == "kw_func_udl(x: int, y: int = 300) -> str" assert doc(m.kw_func_udl_z) == "kw_func_udl_z(x: int, y: int = 0) -> str" assert doc(m.args_function) == "args_function(*args) -> tuple" @@ -23,6 +25,42 @@ def test_function_signatures(doc): doc(m.KWClass.foo1) == "foo1(self: m.kwargs_and_defaults.KWClass, x: int, y: float) -> None" ) + assert ( + doc(m.kw_lb_func0) + == "kw_lb_func0(custom: m.kwargs_and_defaults.CustomRepr = array([[A, B], [C, D]])) -> None" + ) + assert ( + doc(m.kw_lb_func1) + == "kw_lb_func1(custom: m.kwargs_and_defaults.CustomRepr = array([[A, B], [C, D]])) -> None" + ) + assert ( + doc(m.kw_lb_func2) + == "kw_lb_func2(custom: m.kwargs_and_defaults.CustomRepr = array([[A, B], [C, D]])) -> None" + ) + assert ( + doc(m.kw_lb_func3) + == "kw_lb_func3(custom: m.kwargs_and_defaults.CustomRepr = array([[A, B], [C, D]])) -> None" + ) + assert ( + doc(m.kw_lb_func4) + == "kw_lb_func4(custom: m.kwargs_and_defaults.CustomRepr = array([[A, B], [C, D]])) -> None" + ) + assert ( + doc(m.kw_lb_func5) + == "kw_lb_func5(custom: m.kwargs_and_defaults.CustomRepr = array([[A, B], [C, D]])) -> None" + ) + assert ( + doc(m.kw_lb_func6) + == "kw_lb_func6(custom: m.kwargs_and_defaults.CustomRepr = ) -> None" + ) + assert ( + doc(m.kw_lb_func7) + == "kw_lb_func7(str_arg: str = 'First line.\\n Second line.') -> None" + ) + assert ( + doc(m.kw_lb_func8) + == "kw_lb_func8(custom: m.kwargs_and_defaults.CustomRepr = ) -> None" + ) def test_named_arguments(): @@ -345,7 +383,7 @@ def test_args_refcount(): arguments""" refcount = m.arg_refcount_h - myval = 54321 + myval = object() expected = refcount(myval) assert m.arg_refcount_h(myval) == expected assert m.arg_refcount_o(myval) == expected + 1 @@ -384,6 +422,7 @@ def test_args_refcount(): # for the `py::args`; in the previous case, we could simply inc_ref and pass on Python's input # tuple without having to inc_ref the individual elements, but here we can't, hence the extra # refs. - assert m.mixed_args_refcount(myval, myval, myval) == (exp3 + 3, exp3 + 3, exp3 + 3) + exp3_3 = exp3 + 3 + assert m.mixed_args_refcount(myval, myval, myval) == (exp3_3, exp3_3, exp3_3) assert m.class_default_argument() == "" diff --git a/wrap/pybind11/tests/test_local_bindings.py b/wrap/pybind11/tests/test_local_bindings.py index d641877396..1e83164c77 100644 --- a/wrap/pybind11/tests/test_local_bindings.py +++ b/wrap/pybind11/tests/test_local_bindings.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest import env # noqa: F401 diff --git a/wrap/pybind11/tests/test_methods_and_attributes.cpp b/wrap/pybind11/tests/test_methods_and_attributes.cpp index 31d46eb7ed..f433847c76 100644 --- a/wrap/pybind11/tests/test_methods_and_attributes.cpp +++ b/wrap/pybind11/tests/test_methods_and_attributes.cpp @@ -374,8 +374,7 @@ TEST_SUBMODULE(methods_and_attributes, m) { m.def("overload_order", [](const std::string &) { return 1; }); m.def("overload_order", [](const std::string &) { return 2; }); m.def("overload_order", [](int) { return 3; }); - m.def( - "overload_order", [](int) { return 4; }, py::prepend{}); + m.def("overload_order", [](int) { return 4; }, py::prepend{}); #if !defined(PYPY_VERSION) // test_dynamic_attributes diff --git a/wrap/pybind11/tests/test_methods_and_attributes.py b/wrap/pybind11/tests/test_methods_and_attributes.py index 955a85f67c..dfa31f5465 100644 --- a/wrap/pybind11/tests/test_methods_and_attributes.py +++ b/wrap/pybind11/tests/test_methods_and_attributes.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import sys import pytest @@ -232,25 +234,29 @@ def test_no_mixed_overloads(): with pytest.raises(RuntimeError) as excinfo: m.ExampleMandA.add_mixed_overloads1() - assert str( - excinfo.value - ) == "overloading a method with both static and instance methods is not supported; " + ( - "#define PYBIND11_DETAILED_ERROR_MESSAGES or compile in debug mode for more details" - if not detailed_error_messages_enabled - else "error while attempting to bind static method ExampleMandA.overload_mixed1" - "(arg0: float) -> str" + assert ( + str(excinfo.value) + == "overloading a method with both static and instance methods is not supported; " + + ( + "#define PYBIND11_DETAILED_ERROR_MESSAGES or compile in debug mode for more details" + if not detailed_error_messages_enabled + else "error while attempting to bind static method ExampleMandA.overload_mixed1" + "(arg0: float) -> str" + ) ) with pytest.raises(RuntimeError) as excinfo: m.ExampleMandA.add_mixed_overloads2() - assert str( - excinfo.value - ) == "overloading a method with both static and instance methods is not supported; " + ( - "#define PYBIND11_DETAILED_ERROR_MESSAGES or compile in debug mode for more details" - if not detailed_error_messages_enabled - else "error while attempting to bind instance method ExampleMandA.overload_mixed2" - "(self: pybind11_tests.methods_and_attributes.ExampleMandA, arg0: int, arg1: int)" - " -> str" + assert ( + str(excinfo.value) + == "overloading a method with both static and instance methods is not supported; " + + ( + "#define PYBIND11_DETAILED_ERROR_MESSAGES or compile in debug mode for more details" + if not detailed_error_messages_enabled + else "error while attempting to bind instance method ExampleMandA.overload_mixed2" + "(self: pybind11_tests.methods_and_attributes.ExampleMandA, arg0: int, arg1: int)" + " -> str" + ) ) diff --git a/wrap/pybind11/tests/test_modules.py b/wrap/pybind11/tests/test_modules.py index 2f6d825b79..95835e14ea 100644 --- a/wrap/pybind11/tests/test_modules.py +++ b/wrap/pybind11/tests/test_modules.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import builtins import pytest diff --git a/wrap/pybind11/tests/test_multiple_inheritance.py b/wrap/pybind11/tests/test_multiple_inheritance.py index 3a1d88d711..d445824b54 100644 --- a/wrap/pybind11/tests/test_multiple_inheritance.py +++ b/wrap/pybind11/tests/test_multiple_inheritance.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest import env # noqa: F401 diff --git a/wrap/pybind11/tests/test_numpy_array.cpp b/wrap/pybind11/tests/test_numpy_array.cpp index 8c122a8658..c2f754208b 100644 --- a/wrap/pybind11/tests/test_numpy_array.cpp +++ b/wrap/pybind11/tests/test_numpy_array.cpp @@ -287,8 +287,7 @@ TEST_SUBMODULE(numpy_array, sm) { // [workaround(intel)] ICC 20/21 breaks with py::arg().stuff, using py::arg{}.stuff works. // Only accept the exact types: - sm.def( - "overloaded3", [](const py::array_t &) { return "int"; }, py::arg{}.noconvert()); + sm.def("overloaded3", [](const py::array_t &) { return "int"; }, py::arg{}.noconvert()); sm.def( "overloaded3", [](const py::array_t &) { return "double"; }, @@ -444,9 +443,8 @@ TEST_SUBMODULE(numpy_array, sm) { }); // resize to 3D array with each dimension = N - sm.def("array_resize3", [](py::array_t a, size_t N, bool refcheck) { - a.resize({N, N, N}, refcheck); - }); + sm.def("array_resize3", + [](py::array_t a, size_t N, bool refcheck) { a.resize({N, N, N}, refcheck); }); // test_array_create_and_resize // return 2D array with Nrows = Ncols = N @@ -460,9 +458,8 @@ TEST_SUBMODULE(numpy_array, sm) { sm.def("array_view", [](py::array_t a, const std::string &dtype) { return a.view(dtype); }); - sm.def("reshape_initializer_list", [](py::array_t a, size_t N, size_t M, size_t O) { - return a.reshape({N, M, O}); - }); + sm.def("reshape_initializer_list", + [](py::array_t a, size_t N, size_t M, size_t O) { return a.reshape({N, M, O}); }); sm.def("reshape_tuple", [](py::array_t a, const std::vector &new_shape) { return a.reshape(new_shape); }); @@ -471,8 +468,7 @@ TEST_SUBMODULE(numpy_array, sm) { [](const py::array &a) { return a[py::make_tuple(0, py::ellipsis(), 0)]; }); // test_argument_conversions - sm.def( - "accept_double", [](const py::array_t &) {}, py::arg("a")); + sm.def("accept_double", [](const py::array_t &) {}, py::arg("a")); sm.def( "accept_double_forcecast", [](const py::array_t &) {}, @@ -493,8 +489,7 @@ TEST_SUBMODULE(numpy_array, sm) { "accept_double_f_style_forcecast", [](const py::array_t &) {}, py::arg("a")); - sm.def( - "accept_double_noconvert", [](const py::array_t &) {}, "a"_a.noconvert()); + sm.def("accept_double_noconvert", [](const py::array_t &) {}, "a"_a.noconvert()); sm.def( "accept_double_forcecast_noconvert", [](const py::array_t &) {}, diff --git a/wrap/pybind11/tests/test_numpy_array.py b/wrap/pybind11/tests/test_numpy_array.py index 12e7d17d15..4726a8e73c 100644 --- a/wrap/pybind11/tests/test_numpy_array.py +++ b/wrap/pybind11/tests/test_numpy_array.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest import env # noqa: F401 @@ -198,11 +200,7 @@ def assert_references(a, b, base=None): assert a.flags.f_contiguous == b.flags.f_contiguous assert a.flags.writeable == b.flags.writeable assert a.flags.aligned == b.flags.aligned - # 1.13 supported Python 3.6 - if tuple(int(x) for x in np.__version__.split(".")[:2]) >= (1, 14): - assert a.flags.writebackifcopy == b.flags.writebackifcopy - else: - assert a.flags.updateifcopy == b.flags.updateifcopy + assert a.flags.writebackifcopy == b.flags.writebackifcopy assert np.all(a == b) assert not b.flags.owndata assert b.base is base @@ -298,7 +296,7 @@ def test_constructors(): results = m.converting_constructors([1, 2, 3]) for a in results.values(): np.testing.assert_array_equal(a, [1, 2, 3]) - assert results["array"].dtype == np.int_ + assert results["array"].dtype == np.dtype(int) assert results["array_t"].dtype == np.int32 assert results["array_t"].dtype == np.float64 @@ -536,7 +534,12 @@ def test_format_descriptors_for_floating_point_types(test_func): @pytest.mark.parametrize("contiguity", [None, "C", "F"]) @pytest.mark.parametrize("noconvert", [False, True]) @pytest.mark.filterwarnings( - "ignore:Casting complex values to real discards the imaginary part:numpy.ComplexWarning" + "ignore:Casting complex values to real discards the imaginary part:" + + ( + "numpy.exceptions.ComplexWarning" + if hasattr(np, "exceptions") + else "numpy.ComplexWarning" + ) ) def test_argument_conversions(forcecast, contiguity, noconvert): function_name = "accept_double" @@ -583,7 +586,8 @@ def test_argument_conversions(forcecast, contiguity, noconvert): def test_dtype_refcount_leak(): from sys import getrefcount - dtype = np.dtype(np.float_) + # Was np.float_ but that alias for float64 was removed in NumPy 2. + dtype = np.dtype(np.float64) a = np.array([1], dtype=dtype) before = getrefcount(dtype) m.ndim(a) diff --git a/wrap/pybind11/tests/test_numpy_dtypes.cpp b/wrap/pybind11/tests/test_numpy_dtypes.cpp index 6654f9ed8f..ed77ec0246 100644 --- a/wrap/pybind11/tests/test_numpy_dtypes.cpp +++ b/wrap/pybind11/tests/test_numpy_dtypes.cpp @@ -157,7 +157,7 @@ py::array mkarray_via_buffer(size_t n) { do { \ (s).bool_ = (i) % 2 != 0; \ (s).uint_ = (uint32_t) (i); \ - (s).float_ = (float) (i) *1.5f; \ + (s).float_ = (float) (i) * 1.5f; \ (s).ldbl_ = (long double) (i) * -2.5L; \ } while (0) @@ -348,7 +348,7 @@ TEST_SUBMODULE(numpy_dtypes, m) { // is not a POD type struct NotPOD { std::string v; - NotPOD() : v("hi"){}; + NotPOD() : v("hi") {}; }; PYBIND11_NUMPY_DTYPE(NotPOD, v); #endif @@ -405,10 +405,35 @@ TEST_SUBMODULE(numpy_dtypes, m) { }); // test_dtype + // Below we use `L` for unsigned long as unfortunately the only name that + // works reliably on Both NumPy 2.x and old NumPy 1.x. std::vector dtype_names{ - "byte", "short", "intc", "int_", "longlong", "ubyte", "ushort", - "uintc", "uint", "ulonglong", "half", "single", "double", "longdouble", - "csingle", "cdouble", "clongdouble", "bool_", "datetime64", "timedelta64", "object_"}; + "byte", + "short", + "intc", + "long", + "longlong", + "ubyte", + "ushort", + "uintc", + "L", + "ulonglong", + "half", + "single", + "double", + "longdouble", + "csingle", + "cdouble", + "clongdouble", + "bool_", + "datetime64", + "timedelta64", + "object_", + // platform dependent aliases (int_ and uint are also NumPy version dependent on windows) + "int_", + "uint", + "intp", + "uintp"}; m.def("print_dtypes", []() { py::list l; diff --git a/wrap/pybind11/tests/test_numpy_dtypes.py b/wrap/pybind11/tests/test_numpy_dtypes.py index d10457eeb2..8ae239ed86 100644 --- a/wrap/pybind11/tests/test_numpy_dtypes.py +++ b/wrap/pybind11/tests/test_numpy_dtypes.py @@ -1,8 +1,11 @@ +from __future__ import annotations + import re import pytest import env # noqa: F401 +from pybind11_tests import PYBIND11_NUMPY_1_ONLY from pybind11_tests import numpy_dtypes as m np = pytest.importorskip("numpy") @@ -76,9 +79,7 @@ def partial_nested_fmt(): partial_size = partial_ld_off + ld.itemsize partial_end_padding = partial_size % np.dtype("uint64").alignment partial_nested_size = partial_nested_off * 2 + partial_size + partial_end_padding - return "{{'names':['a'],'formats':[{}],'offsets':[{}],'itemsize':{}}}".format( - partial_dtype_fmt(), partial_nested_off, partial_nested_size - ) + return f"{{'names':['a'],'formats':[{partial_dtype_fmt()}],'offsets':[{partial_nested_off}],'itemsize':{partial_nested_size}}}" def assert_equal(actual, expected_data, expected_dtype): @@ -172,13 +173,20 @@ def test_dtype(simple_dtype): np.zeros(1, m.trailing_padding_dtype()) ) - expected_chars = "bhilqBHILQefdgFDG?MmO" - assert m.test_dtype_kind() == list("iiiiiuuuuuffffcccbMmO") + expected_chars = list("bhilqBHILQefdgFDG?MmO") + # Note that int_ and uint size and mapping is NumPy version dependent: + expected_chars += [np.dtype(_).char for _ in ("int_", "uint", "intp", "uintp")] + assert m.test_dtype_kind() == list("iiiiiuuuuuffffcccbMmOiuiu") assert m.test_dtype_char_() == list(expected_chars) assert m.test_dtype_num() == [np.dtype(ch).num for ch in expected_chars] assert m.test_dtype_byteorder() == [np.dtype(ch).byteorder for ch in expected_chars] assert m.test_dtype_alignment() == [np.dtype(ch).alignment for ch in expected_chars] - assert m.test_dtype_flags() == [chr(np.dtype(ch).flags) for ch in expected_chars] + if not PYBIND11_NUMPY_1_ONLY: + assert m.test_dtype_flags() == [np.dtype(ch).flags for ch in expected_chars] + else: + assert m.test_dtype_flags() == [ + chr(np.dtype(ch).flags) for ch in expected_chars + ] def test_recarray(simple_dtype, packed_dtype): diff --git a/wrap/pybind11/tests/test_numpy_vectorize.py b/wrap/pybind11/tests/test_numpy_vectorize.py index f1e8b62540..ce38d72d96 100644 --- a/wrap/pybind11/tests/test_numpy_vectorize.py +++ b/wrap/pybind11/tests/test_numpy_vectorize.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import numpy_vectorize as m diff --git a/wrap/pybind11/tests/test_opaque_types.py b/wrap/pybind11/tests/test_opaque_types.py index 5d4f2a1bf4..3420864367 100644 --- a/wrap/pybind11/tests/test_opaque_types.py +++ b/wrap/pybind11/tests/test_opaque_types.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import ConstructorStats, UserType diff --git a/wrap/pybind11/tests/test_operator_overloading.py b/wrap/pybind11/tests/test_operator_overloading.py index 9fde305a03..b6760902dc 100644 --- a/wrap/pybind11/tests/test_operator_overloading.py +++ b/wrap/pybind11/tests/test_operator_overloading.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pybind11_tests import ConstructorStats diff --git a/wrap/pybind11/tests/test_pickling.py b/wrap/pybind11/tests/test_pickling.py index 12361a661e..ad67a1df98 100644 --- a/wrap/pybind11/tests/test_pickling.py +++ b/wrap/pybind11/tests/test_pickling.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pickle import re diff --git a/wrap/pybind11/tests/test_python_multiple_inheritance.cpp b/wrap/pybind11/tests/test_python_multiple_inheritance.cpp new file mode 100644 index 0000000000..6899171585 --- /dev/null +++ b/wrap/pybind11/tests/test_python_multiple_inheritance.cpp @@ -0,0 +1,45 @@ +#include "pybind11_tests.h" + +namespace test_python_multiple_inheritance { + +// Copied from: +// https://github.com/google/clif/blob/5718e4d0807fd3b6a8187dde140069120b81ecef/clif/testing/python_multiple_inheritance.h + +struct CppBase { + explicit CppBase(int value) : base_value(value) {} + int get_base_value() const { return base_value; } + void reset_base_value(int new_value) { base_value = new_value; } + +private: + int base_value; +}; + +struct CppDrvd : CppBase { + explicit CppDrvd(int value) : CppBase(value), drvd_value(value * 3) {} + int get_drvd_value() const { return drvd_value; } + void reset_drvd_value(int new_value) { drvd_value = new_value; } + + int get_base_value_from_drvd() const { return get_base_value(); } + void reset_base_value_from_drvd(int new_value) { reset_base_value(new_value); } + +private: + int drvd_value; +}; + +} // namespace test_python_multiple_inheritance + +TEST_SUBMODULE(python_multiple_inheritance, m) { + using namespace test_python_multiple_inheritance; + + py::class_(m, "CppBase") + .def(py::init()) + .def("get_base_value", &CppBase::get_base_value) + .def("reset_base_value", &CppBase::reset_base_value); + + py::class_(m, "CppDrvd") + .def(py::init()) + .def("get_drvd_value", &CppDrvd::get_drvd_value) + .def("reset_drvd_value", &CppDrvd::reset_drvd_value) + .def("get_base_value_from_drvd", &CppDrvd::get_base_value_from_drvd) + .def("reset_base_value_from_drvd", &CppDrvd::reset_base_value_from_drvd); +} diff --git a/wrap/pybind11/tests/test_python_multiple_inheritance.py b/wrap/pybind11/tests/test_python_multiple_inheritance.py new file mode 100644 index 0000000000..12216283ab --- /dev/null +++ b/wrap/pybind11/tests/test_python_multiple_inheritance.py @@ -0,0 +1,36 @@ +# Adapted from: +# https://github.com/google/clif/blob/5718e4d0807fd3b6a8187dde140069120b81ecef/clif/testing/python/python_multiple_inheritance_test.py +from __future__ import annotations + +from pybind11_tests import python_multiple_inheritance as m + + +class PC(m.CppBase): + pass + + +class PPCC(PC, m.CppDrvd): + pass + + +def test_PC(): + d = PC(11) + assert d.get_base_value() == 11 + d.reset_base_value(13) + assert d.get_base_value() == 13 + + +def test_PPCC(): + d = PPCC(11) + assert d.get_drvd_value() == 33 + d.reset_drvd_value(55) + assert d.get_drvd_value() == 55 + + assert d.get_base_value() == 11 + assert d.get_base_value_from_drvd() == 11 + d.reset_base_value(20) + assert d.get_base_value() == 20 + assert d.get_base_value_from_drvd() == 20 + d.reset_base_value_from_drvd(30) + assert d.get_base_value() == 30 + assert d.get_base_value_from_drvd() == 30 diff --git a/wrap/pybind11/tests/test_pytypes.cpp b/wrap/pybind11/tests/test_pytypes.cpp index b4ee642891..7c30978cea 100644 --- a/wrap/pybind11/tests/test_pytypes.cpp +++ b/wrap/pybind11/tests/test_pytypes.cpp @@ -7,6 +7,8 @@ BSD-style license that can be found in the LICENSE file. */ +#include + #include "pybind11_tests.h" #include @@ -23,7 +25,7 @@ PyObject *conv(PyObject *o) { ret = PyFloat_FromDouble(v); } } else { - PyErr_SetString(PyExc_TypeError, "Unexpected type"); + py::set_error(PyExc_TypeError, "Unexpected type"); } return ret; } @@ -39,6 +41,15 @@ class float_ : public py::object { }; } // namespace external +namespace pybind11 { +namespace detail { +template <> +struct handle_type_name { + static constexpr auto name = const_name("float"); +}; +} // namespace detail +} // namespace pybind11 + namespace implicit_conversion_from_0_to_handle { // Uncomment to trigger compiler error. Note: Before PR #4008 this used to compile successfully. // void expected_to_trigger_compiler_error() { py::handle(0); } @@ -98,6 +109,26 @@ void m_defs(py::module_ &m) { } // namespace handle_from_move_only_type_with_operator_PyObject +#if defined(__cpp_nontype_template_parameter_class) +namespace literals { +enum Color { RED = 0, BLUE = 1 }; + +typedef py::typing::Literal<"26", + "0x1A", + "\"hello world\"", + "b\"hello world\"", + "u\"hello world\"", + "True", + "Color.RED", + "None"> + LiteralFoo; +} // namespace literals +namespace typevar { +typedef py::typing::TypeVar<"T"> TypeVarT; +typedef py::typing::TypeVar<"V"> TypeVarV; +} // namespace typevar +#endif + TEST_SUBMODULE(pytypes, m) { m.def("obj_class_name", [](py::handle obj) { return py::detail::obj_class_name(obj.ptr()); }); @@ -124,6 +155,7 @@ TEST_SUBMODULE(pytypes, m) { m.def("list_size_t", []() { return py::list{(py::size_t) 0}; }); m.def("list_insert_ssize_t", [](py::list *l) { return l->insert((py::ssize_t) 1, 83); }); m.def("list_insert_size_t", [](py::list *l) { return l->insert((py::size_t) 3, 57); }); + m.def("list_clear", [](py::list *l) { l->clear(); }); m.def("get_list", []() { py::list list; list.append("value"); @@ -660,8 +692,8 @@ TEST_SUBMODULE(pytypes, m) { // This is "most correct" and enforced on these platforms. # define PYBIND11_AUTO_IT auto it #else -// This works on many platforms and is (unfortunately) reflective of existing user code. -// NOLINTNEXTLINE(bugprone-macro-parentheses) + // This works on many platforms and is (unfortunately) reflective of existing user code. + // NOLINTNEXTLINE(bugprone-macro-parentheses) # define PYBIND11_AUTO_IT auto &it #endif @@ -820,4 +852,75 @@ TEST_SUBMODULE(pytypes, m) { a >>= b; return a; }); + + m.def("annotate_tuple_float_str", [](const py::typing::Tuple &) {}); + m.def("annotate_tuple_empty", [](const py::typing::Tuple<> &) {}); + m.def("annotate_tuple_variable_length", + [](const py::typing::Tuple &) {}); + m.def("annotate_dict_str_int", [](const py::typing::Dict &) {}); + m.def("annotate_list_int", [](const py::typing::List &) {}); + m.def("annotate_set_str", [](const py::typing::Set &) {}); + m.def("annotate_iterable_str", [](const py::typing::Iterable &) {}); + m.def("annotate_iterator_int", [](const py::typing::Iterator &) {}); + m.def("annotate_fn", + [](const py::typing::Callable, py::str)> &) {}); + + m.def("annotate_fn_only_return", [](const py::typing::Callable &) {}); + m.def("annotate_type", [](const py::typing::Type &t) -> py::type { return t; }); + + m.def("annotate_union", + [](py::typing::List> l, + py::str a, + py::int_ b, + py::object c) -> py::typing::List> { + l.append(a); + l.append(b); + l.append(c); + return l; + }); + + m.def("union_typing_only", + [](py::typing::List> &l) + -> py::typing::List> { return l; }); + + m.def("annotate_union_to_object", + [](py::typing::Union &o) -> py::object { return o; }); + + m.def("annotate_optional", + [](py::list &list) -> py::typing::List> { + list.append(py::str("hi")); + list.append(py::none()); + return list; + }); + + m.def("annotate_type_guard", [](py::object &o) -> py::typing::TypeGuard { + return py::isinstance(o); + }); + m.def("annotate_type_is", + [](py::object &o) -> py::typing::TypeIs { return py::isinstance(o); }); + + m.def("annotate_no_return", []() -> py::typing::NoReturn { throw 0; }); + m.def("annotate_never", []() -> py::typing::Never { throw 0; }); + + m.def("annotate_optional_to_object", + [](py::typing::Optional &o) -> py::object { return o; }); + +#if defined(__cpp_nontype_template_parameter_class) + py::enum_(m, "Color") + .value("RED", literals::Color::RED) + .value("BLUE", literals::Color::BLUE); + + m.def("annotate_literal", [](literals::LiteralFoo &o) -> py::object { return o; }); + m.def("annotate_generic_containers", + [](const py::typing::List &l) -> py::typing::List { + return l; + }); + + m.def("annotate_listT_to_T", + [](const py::typing::List &l) -> typevar::TypeVarT { return l[0]; }); + m.def("annotate_object_to_T", [](const py::object &o) -> typevar::TypeVarT { return o; }); + m.attr("if_defined__cpp_nontype_template_parameter_class") = true; +#else + m.attr("if_defined__cpp_nontype_template_parameter_class") = false; +#endif } diff --git a/wrap/pybind11/tests/test_pytypes.py b/wrap/pybind11/tests/test_pytypes.py index eda7a20a9d..30931e0b9a 100644 --- a/wrap/pybind11/tests/test_pytypes.py +++ b/wrap/pybind11/tests/test_pytypes.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import contextlib import sys import types @@ -65,6 +67,8 @@ def test_list(capture, doc): assert lins == [1, 83, 2] m.list_insert_size_t(lins) assert lins == [1, 83, 2, 57] + m.list_clear(lins) + assert lins == [] with capture: lst = m.get_list() @@ -121,7 +125,7 @@ def test_set(capture, doc): assert m.anyset_contains({"foo"}, "foo") assert doc(m.get_set) == "get_set() -> set" - assert doc(m.print_anyset) == "print_anyset(arg0: anyset) -> None" + assert doc(m.print_anyset) == "print_anyset(arg0: Union[set, frozenset]) -> None" def test_frozenset(capture, doc): @@ -631,7 +635,8 @@ def test_memoryview(method, args, fmt, expected_view): ], ) def test_memoryview_refcount(method): - buf = b"\x0a\x0b\x0c\x0d" + # Avoiding a literal to avoid an immortal object in free-threaded builds + buf = "\x0a\x0b\x0c\x0d".encode("ascii") ref_before = sys.getrefcount(buf) view = method(buf) ref_after = sys.getrefcount(buf) @@ -896,3 +901,150 @@ def test_inplace_lshift(a, b): def test_inplace_rshift(a, b): expected = a >> b assert m.inplace_rshift(a, b) == expected + + +def test_tuple_nonempty_annotations(doc): + assert ( + doc(m.annotate_tuple_float_str) + == "annotate_tuple_float_str(arg0: tuple[float, str]) -> None" + ) + + +def test_tuple_empty_annotations(doc): + assert ( + doc(m.annotate_tuple_empty) == "annotate_tuple_empty(arg0: tuple[()]) -> None" + ) + + +def test_tuple_variable_length_annotations(doc): + assert ( + doc(m.annotate_tuple_variable_length) + == "annotate_tuple_variable_length(arg0: tuple[float, ...]) -> None" + ) + + +def test_dict_annotations(doc): + assert ( + doc(m.annotate_dict_str_int) + == "annotate_dict_str_int(arg0: dict[str, int]) -> None" + ) + + +def test_list_annotations(doc): + assert doc(m.annotate_list_int) == "annotate_list_int(arg0: list[int]) -> None" + + +def test_set_annotations(doc): + assert doc(m.annotate_set_str) == "annotate_set_str(arg0: set[str]) -> None" + + +def test_iterable_annotations(doc): + assert ( + doc(m.annotate_iterable_str) + == "annotate_iterable_str(arg0: Iterable[str]) -> None" + ) + + +def test_iterator_annotations(doc): + assert ( + doc(m.annotate_iterator_int) + == "annotate_iterator_int(arg0: Iterator[int]) -> None" + ) + + +def test_fn_annotations(doc): + assert ( + doc(m.annotate_fn) + == "annotate_fn(arg0: Callable[[list[str], str], int]) -> None" + ) + + +def test_fn_return_only(doc): + assert ( + doc(m.annotate_fn_only_return) + == "annotate_fn_only_return(arg0: Callable[..., int]) -> None" + ) + + +def test_type_annotation(doc): + assert doc(m.annotate_type) == "annotate_type(arg0: type[int]) -> type" + + +def test_union_annotations(doc): + assert ( + doc(m.annotate_union) + == "annotate_union(arg0: list[Union[str, int, object]], arg1: str, arg2: int, arg3: object) -> list[Union[str, int, object]]" + ) + + +def test_union_typing_only(doc): + assert ( + doc(m.union_typing_only) + == "union_typing_only(arg0: list[Union[str]]) -> list[Union[int]]" + ) + + +def test_union_object_annotations(doc): + assert ( + doc(m.annotate_union_to_object) + == "annotate_union_to_object(arg0: Union[int, str]) -> object" + ) + + +def test_optional_annotations(doc): + assert ( + doc(m.annotate_optional) + == "annotate_optional(arg0: list) -> list[Optional[str]]" + ) + + +def test_type_guard_annotations(doc): + assert ( + doc(m.annotate_type_guard) + == "annotate_type_guard(arg0: object) -> TypeGuard[str]" + ) + + +def test_type_is_annotations(doc): + assert doc(m.annotate_type_is) == "annotate_type_is(arg0: object) -> TypeIs[str]" + + +def test_no_return_annotation(doc): + assert doc(m.annotate_no_return) == "annotate_no_return() -> NoReturn" + + +def test_never_annotation(doc): + assert doc(m.annotate_never) == "annotate_never() -> Never" + + +def test_optional_object_annotations(doc): + assert ( + doc(m.annotate_optional_to_object) + == "annotate_optional_to_object(arg0: Optional[int]) -> object" + ) + + +@pytest.mark.skipif( + not m.if_defined__cpp_nontype_template_parameter_class, + reason="C++20 feature not available.", +) +def test_literal(doc): + assert ( + doc(m.annotate_literal) + == 'annotate_literal(arg0: Literal[26, 0x1A, "hello world", b"hello world", u"hello world", True, Color.RED, None]) -> object' + ) + + +@pytest.mark.skipif( + not m.if_defined__cpp_nontype_template_parameter_class, + reason="C++20 feature not available.", +) +def test_typevar(doc): + assert ( + doc(m.annotate_generic_containers) + == "annotate_generic_containers(arg0: list[T]) -> list[V]" + ) + + assert doc(m.annotate_listT_to_T) == "annotate_listT_to_T(arg0: list[T]) -> T" + + assert doc(m.annotate_object_to_T) == "annotate_object_to_T(arg0: object) -> T" diff --git a/wrap/pybind11/tests/test_sequences_and_iterators.cpp b/wrap/pybind11/tests/test_sequences_and_iterators.cpp index 1de65edbf2..4a1d37f4de 100644 --- a/wrap/pybind11/tests/test_sequences_and_iterators.cpp +++ b/wrap/pybind11/tests/test_sequences_and_iterators.cpp @@ -28,6 +28,13 @@ class NonZeroIterator { public: explicit NonZeroIterator(const T *ptr) : ptr_(ptr) {} + + // Make the iterator non-copyable and movable + NonZeroIterator(const NonZeroIterator &) = delete; + NonZeroIterator(NonZeroIterator &&) noexcept = default; + NonZeroIterator &operator=(const NonZeroIterator &) = delete; + NonZeroIterator &operator=(NonZeroIterator &&) noexcept = default; + const T &operator*() const { return *ptr_; } NonZeroIterator &operator++() { ++ptr_; @@ -78,6 +85,7 @@ class NonCopyableInt { int value_; }; using NonCopyableIntPair = std::pair; + PYBIND11_MAKE_OPAQUE(std::vector); PYBIND11_MAKE_OPAQUE(std::vector); @@ -375,6 +383,17 @@ TEST_SUBMODULE(sequences_and_iterators, m) { private: std::vector> data_; }; + + { + // #4383 : Make sure `py::make_*iterator` functions work with move-only iterators + using iterator_t = NonZeroIterator>; + + static_assert(std::is_move_assignable::value, ""); + static_assert(std::is_move_constructible::value, ""); + static_assert(!std::is_copy_assignable::value, ""); + static_assert(!std::is_copy_constructible::value, ""); + } + py::class_(m, "IntPairs") .def(py::init>>()) .def( diff --git a/wrap/pybind11/tests/test_sequences_and_iterators.py b/wrap/pybind11/tests/test_sequences_and_iterators.py index dc129f2bff..f609f553de 100644 --- a/wrap/pybind11/tests/test_sequences_and_iterators.py +++ b/wrap/pybind11/tests/test_sequences_and_iterators.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest from pytest import approx # noqa: PT013 @@ -58,6 +60,15 @@ def test_generalized_iterators_simple(): assert list(m.IntPairs([(1, 2), (3, 4), (0, 5)]).simple_values()) == [2, 4, 5] +def test_iterator_doc_annotations(): + assert m.IntPairs.nonref.__doc__.endswith("-> Iterator[tuple[int, int]]\n") + assert m.IntPairs.nonref_keys.__doc__.endswith("-> Iterator[int]\n") + assert m.IntPairs.nonref_values.__doc__.endswith("-> Iterator[int]\n") + assert m.IntPairs.simple_iterator.__doc__.endswith("-> Iterator[tuple[int, int]]\n") + assert m.IntPairs.simple_keys.__doc__.endswith("-> Iterator[int]\n") + assert m.IntPairs.simple_values.__doc__.endswith("-> Iterator[int]\n") + + def test_iterator_referencing(): """Test that iterators reference rather than copy their referents.""" vec = m.VectorNonCopyableInt() @@ -171,6 +182,10 @@ def __len__(self): assert m.sequence_length("hello") == 5 +def test_sequence_doc(): + assert m.sequence_length.__doc__.strip() == "sequence_length(arg0: Sequence) -> int" + + def test_map_iterator(): sm = m.StringMap({"hi": "bye", "black": "white"}) assert sm["hi"] == "bye" diff --git a/wrap/pybind11/tests/test_smart_ptr.cpp b/wrap/pybind11/tests/test_smart_ptr.cpp index 6d9efcedce..496073b3c1 100644 --- a/wrap/pybind11/tests/test_smart_ptr.cpp +++ b/wrap/pybind11/tests/test_smart_ptr.cpp @@ -103,21 +103,26 @@ class MyObject3 : public std::enable_shared_from_this { int value; }; +template +std::unordered_set &pointer_set() { + // https://google.github.io/styleguide/cppguide.html#Static_and_Global_Variables + static auto singleton = new std::unordered_set(); + return *singleton; +} + // test_unique_nodelete // Object with a private destructor -class MyObject4; -std::unordered_set myobject4_instances; class MyObject4 { public: explicit MyObject4(int value) : value{value} { print_created(this); - myobject4_instances.insert(this); + pointer_set().insert(this); } int value; static void cleanupAllInstances() { - auto tmp = std::move(myobject4_instances); - myobject4_instances.clear(); + auto tmp = std::move(pointer_set()); + pointer_set().clear(); for (auto *o : tmp) { delete o; } @@ -125,7 +130,7 @@ class MyObject4 { private: ~MyObject4() { - myobject4_instances.erase(this); + pointer_set().erase(this); print_destroyed(this); } }; @@ -133,19 +138,17 @@ class MyObject4 { // test_unique_deleter // Object with std::unique_ptr where D is not matching the base class // Object with a protected destructor -class MyObject4a; -std::unordered_set myobject4a_instances; class MyObject4a { public: explicit MyObject4a(int i) : value{i} { print_created(this); - myobject4a_instances.insert(this); + pointer_set().insert(this); }; int value; static void cleanupAllInstances() { - auto tmp = std::move(myobject4a_instances); - myobject4a_instances.clear(); + auto tmp = std::move(pointer_set()); + pointer_set().clear(); for (auto *o : tmp) { delete o; } @@ -153,7 +156,7 @@ class MyObject4a { protected: virtual ~MyObject4a() { - myobject4a_instances.erase(this); + pointer_set().erase(this); print_destroyed(this); } }; diff --git a/wrap/pybind11/tests/test_smart_ptr.py b/wrap/pybind11/tests/test_smart_ptr.py index 2f204e01b1..bf0ae4aeb1 100644 --- a/wrap/pybind11/tests/test_smart_ptr.py +++ b/wrap/pybind11/tests/test_smart_ptr.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import pytest m = pytest.importorskip("pybind11_tests.smart_ptr") diff --git a/wrap/pybind11/tests/test_stl.cpp b/wrap/pybind11/tests/test_stl.cpp index d45465d681..48c907ff3d 100644 --- a/wrap/pybind11/tests/test_stl.cpp +++ b/wrap/pybind11/tests/test_stl.cpp @@ -78,7 +78,7 @@ struct hash { template