Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update wrap and allow numpy 2.0.0 #1773

Merged
merged 16 commits into from
Jul 2, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions .github/workflows/build-macos.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 4 additions & 4 deletions .github/workflows/build-python.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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,
]

Expand All @@ -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
Expand Down
4 changes: 2 additions & 2 deletions gtsam/base/base.i
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ class IndexPairSetMap {

#include <gtsam/base/Matrix.h>
#include <gtsam/base/MatrixSerialization.h>
bool linear_independent(Matrix A, Matrix B, double tol);
bool linear_independent(gtsam::Matrix A, gtsam::Matrix B, double tol);

#include <gtsam/base/Value.h>
virtual class Value {
Expand All @@ -100,7 +100,7 @@ virtual class Value {
};

#include <gtsam/base/GenericValue.h>
template <T = {Vector, Matrix, gtsam::Point2, gtsam::Point3, gtsam::Rot2,
template <T = {gtsam::Vector, gtsam::Matrix, gtsam::Point2, gtsam::Point3, gtsam::Rot2,
gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::StereoPoint2,
gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler,
gtsam::Cal3Fisheye, gtsam::Cal3Unified, gtsam::EssentialMatrix,
Expand Down
40 changes: 20 additions & 20 deletions gtsam/basis/basis.i
Original file line number Diff line number Diff line change
Expand Up @@ -10,40 +10,40 @@ namespace gtsam {
#include <gtsam/basis/Fourier.h>

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 <gtsam/basis/Chebyshev.h>

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 <gtsam/basis/Chebyshev2.h>
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 <gtsam/basis/BasisFactors.h>
Expand All @@ -64,10 +64,10 @@ template <BASIS = {gtsam::FourierBasis, gtsam::Chebyshev1Basis,
gtsam::Chebyshev2Basis, gtsam::Chebyshev2}>
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);
};
Expand Down Expand Up @@ -116,10 +116,10 @@ template <BASIS = {gtsam::FourierBasis, gtsam::Chebyshev1Basis,
gtsam::Chebyshev2Basis, gtsam::Chebyshev2}>
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);
};
Expand Down
Loading
Loading