Skip to content

Commit e2a0747

Browse files
committed
Rename Python reserved keywords in wrapper interface files
The generated .pyi stub files use `lambda` and `global` as argument and method names, which are Python reserved keywords. This causes mypy to report syntax errors on the stubs. Rename `lambda` to `lambda_` and `global` to `global_` in the .i wrapper files. The wrapper tool already handles method name mapping (generating `self->lambda()` calls under a `lambda_` Python name), so no C++ changes are needed. Fixes #2322
1 parent 7e2e3f2 commit e2a0747

File tree

4 files changed

+13
-14
lines changed

4 files changed

+13
-14
lines changed

gtsam/nonlinear/nonlinear.i

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -406,7 +406,7 @@ virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer {
406406
const gtsam::LevenbergMarquardtParams& params =
407407
gtsam::LevenbergMarquardtParams());
408408

409-
double lambda() const;
409+
double lambda_() const;
410410
void print(string str = "") const;
411411
};
412412

gtsam/slam/slam.i

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -223,24 +223,24 @@ virtual class SmartProjectionFactor : gtsam::SmartFactorBase<CAMERA> {
223223
bool triangulateForLinearize(const gtsam::CameraSet<CAMERA>& cameras) const;
224224

225225
gtsam::HessianFactor* createHessianFactor(
226-
const gtsam::CameraSet<CAMERA>& cameras, const double lambda = 0.0,
226+
const gtsam::CameraSet<CAMERA>& cameras, const double lambda_ = 0.0,
227227
bool diagonalDamping = false) const;
228228
gtsam::JacobianFactor* createJacobianQFactor(
229-
const gtsam::CameraSet<CAMERA>& cameras, double lambda) const;
229+
const gtsam::CameraSet<CAMERA>& cameras, double lambda_) const;
230230
gtsam::JacobianFactor* createJacobianQFactor(
231-
const gtsam::Values& values, double lambda) const;
231+
const gtsam::Values& values, double lambda_) const;
232232
gtsam::JacobianFactor* createJacobianSVDFactor(
233-
const gtsam::CameraSet<CAMERA>& cameras, double lambda) const;
233+
const gtsam::CameraSet<CAMERA>& cameras, double lambda_) const;
234234
gtsam::HessianFactor* linearizeToHessian(
235-
const gtsam::Values& values, double lambda = 0.0) const;
235+
const gtsam::Values& values, double lambda_ = 0.0) const;
236236
gtsam::JacobianFactor* linearizeToJacobian(
237-
const gtsam::Values& values, double lambda = 0.0) const;
237+
const gtsam::Values& values, double lambda_ = 0.0) const;
238238

239239
gtsam::GaussianFactor* linearizeDamped(const gtsam::CameraSet<CAMERA>& cameras,
240-
const double lambda = 0.0) const;
240+
const double lambda_ = 0.0) const;
241241

242242
gtsam::GaussianFactor* linearizeDamped(const gtsam::Values& values,
243-
const double lambda = 0.0) const;
243+
const double lambda_ = 0.0) const;
244244

245245
gtsam::GaussianFactor* linearize(
246246
const gtsam::Values& values) const;
@@ -355,7 +355,7 @@ class ReferenceFrameFactor : gtsam::NoiseModelFactor {
355355
ReferenceFrameFactor(gtsam::Key globalKey, gtsam::Key transKey,
356356
gtsam::Key localKey, const gtsam::noiseModel::Base* model);
357357

358-
gtsam::Vector evaluateError(const LANDMARK& global, const POSE& trans, const LANDMARK& local);
358+
gtsam::Vector evaluateError(const LANDMARK& global_, const POSE& trans, const LANDMARK& local);
359359

360360
void print(const std::string& s="",
361361
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter);

gtsam_unstable/gtsam_unstable.i

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -760,9 +760,9 @@ virtual class SmartStereoProjectionFactor : gtsam::NonlinearFactor {
760760
bool isFarPoint() const;
761761

762762
gtsam::GaussianFactor linearizeDamped(const gtsam::CameraSet<gtsam::StereoCamera>& cameras,
763-
const double lambda) const;
763+
const double lambda_) const;
764764
gtsam::GaussianFactor linearizeDamped(const gtsam::Values& values,
765-
const double lambda) const;
765+
const double lambda_) const;
766766
};
767767

768768
#include <gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h>

wrap/tests/fixtures/class.i

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -82,8 +82,7 @@ class Test {
8282

8383
// This should be callable as .print() in python
8484
void print() const;
85-
// Since this is a reserved keyword, it should be updated to `lambda_`
86-
void lambda() const;
85+
void lambda_() const;
8786

8887
void set_container(std::vector<testing::Test> container);
8988
void set_container(std::vector<testing::Test*> container);

0 commit comments

Comments
 (0)