Skip to content

Commit cb5ae6c

Browse files
authored
Merge pull request #2471 from jashshah999/fix/python-reserved-keywords
Rename Python reserved keywords in wrapper interface files
2 parents 1ce550a + 655b101 commit cb5ae6c

File tree

6 files changed

+44
-45
lines changed

6 files changed

+44
-45
lines changed

gtsam/slam/ReferenceFrameFactor.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -97,10 +97,10 @@ class ReferenceFrameFactor : public NoiseModelFactorN<POINT, TRANSFORM, POINT> {
9797
NonlinearFactor::shared_ptr(new This(*this))); }
9898

9999
/** Combined cost and derivative function using boost::optional */
100-
Vector evaluateError(const Point& global, const Transform& trans, const Point& local,
100+
Vector evaluateError(const Point& _global, const Transform& trans, const Point& local,
101101
OptionalMatrixType Dforeign, OptionalMatrixType Dtrans,
102102
OptionalMatrixType Dlocal) const override {
103-
Point newlocal = transform_point<Transform,Point>(trans, global, Dtrans, Dforeign);
103+
Point newlocal = transform_point<Transform,Point>(trans, _global, Dtrans, Dforeign);
104104
if (Dlocal) {
105105
*Dlocal = -1* Matrix::Identity(traits<Point>::dimension, traits<Point>::dimension);
106106
}

gtsam/slam/SmartProjectionFactor.h

Lines changed: 23 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -196,7 +196,7 @@ class SmartProjectionFactor: public SmartFactorBase<CAMERA> {
196196

197197
/// Create a Hessianfactor that is an approximation of error(p).
198198
std::shared_ptr<RegularHessianFactor<Base::Dim> > createHessianFactor(
199-
const Cameras& cameras, const double lambda = 0.0,
199+
const Cameras& cameras, const double _lambda = 0.0,
200200
bool diagonalDamping = false) const {
201201
size_t numKeys = this->keys_.size();
202202
// Create structures for Hessian Factors
@@ -230,64 +230,64 @@ class SmartProjectionFactor: public SmartFactorBase<CAMERA> {
230230

231231
// build augmented hessian
232232
SymmetricBlockMatrix augmentedHessian = //
233-
Cameras::SchurComplement(Fs, E, b, lambda, diagonalDamping);
233+
Cameras::SchurComplement(Fs, E, b, _lambda, diagonalDamping);
234234

235235
return std::make_shared<RegularHessianFactor<Base::Dim> >(
236236
this->keys_, augmentedHessian);
237237
}
238238

239239
// Create RegularImplicitSchurFactor factor.
240240
std::shared_ptr<RegularImplicitSchurFactor<CAMERA> > createRegularImplicitSchurFactor(
241-
const Cameras& cameras, double lambda) const {
241+
const Cameras& cameras, double _lambda) const {
242242
if (triangulateForLinearize(cameras))
243-
return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda);
243+
return Base::createRegularImplicitSchurFactor(cameras, *result_, _lambda);
244244
else
245245
// failed: return empty
246246
return std::shared_ptr<RegularImplicitSchurFactor<CAMERA> >();
247247
}
248248

249249
/// Create JacobianFactorQ factor.
250250
std::shared_ptr<JacobianFactorQ<Base::Dim, 2> > createJacobianQFactor(
251-
const Cameras& cameras, double lambda) const {
251+
const Cameras& cameras, double _lambda) const {
252252
if (triangulateForLinearize(cameras))
253-
return Base::createJacobianQFactor(cameras, *result_, lambda);
253+
return Base::createJacobianQFactor(cameras, *result_, _lambda);
254254
else
255255
// failed: return empty
256256
return std::make_shared<JacobianFactorQ<Base::Dim, 2> >(this->keys_);
257257
}
258258

259259
/// Create JacobianFactorQ factor, takes values.
260260
std::shared_ptr<JacobianFactorQ<Base::Dim, 2> > createJacobianQFactor(
261-
const Values& values, double lambda) const {
262-
return createJacobianQFactor(this->cameras(values), lambda);
261+
const Values& values, double _lambda) const {
262+
return createJacobianQFactor(this->cameras(values), _lambda);
263263
}
264264

265265
/// Different (faster) way to compute a JacobianFactorSVD factor.
266266
std::shared_ptr<JacobianFactor> createJacobianSVDFactor(
267-
const Cameras& cameras, double lambda) const {
267+
const Cameras& cameras, double _lambda) const {
268268
if (triangulateForLinearize(cameras))
269-
return Base::createJacobianSVDFactor(cameras, *result_, lambda);
269+
return Base::createJacobianSVDFactor(cameras, *result_, _lambda);
270270
else
271271
// failed: return empty
272272
return std::make_shared<JacobianFactorSVD<Base::Dim, 2> >(this->keys_);
273273
}
274274

275275
/// Linearize to a Hessianfactor.
276276
virtual std::shared_ptr<RegularHessianFactor<Base::Dim> > linearizeToHessian(
277-
const Values& values, double lambda = 0.0) const {
278-
return createHessianFactor(this->cameras(values), lambda);
277+
const Values& values, double _lambda = 0.0) const {
278+
return createHessianFactor(this->cameras(values), _lambda);
279279
}
280280

281281
/// Linearize to an Implicit Schur factor.
282282
virtual std::shared_ptr<RegularImplicitSchurFactor<CAMERA> > linearizeToImplicit(
283-
const Values& values, double lambda = 0.0) const {
284-
return createRegularImplicitSchurFactor(this->cameras(values), lambda);
283+
const Values& values, double _lambda = 0.0) const {
284+
return createRegularImplicitSchurFactor(this->cameras(values), _lambda);
285285
}
286286

287287
/// Linearize to a JacobianfactorQ.
288288
virtual std::shared_ptr<JacobianFactorQ<Base::Dim, 2> > linearizeToJacobian(
289-
const Values& values, double lambda = 0.0) const {
290-
return createJacobianQFactor(this->cameras(values), lambda);
289+
const Values& values, double _lambda = 0.0) const {
290+
return createJacobianQFactor(this->cameras(values), _lambda);
291291
}
292292

293293
/**
@@ -296,17 +296,17 @@ class SmartProjectionFactor: public SmartFactorBase<CAMERA> {
296296
* @return a Gaussian factor
297297
*/
298298
std::shared_ptr<GaussianFactor> linearizeDamped(const Cameras& cameras,
299-
const double lambda = 0.0) const {
299+
const double _lambda = 0.0) const {
300300
// depending on flag set on construction we may linearize to different linear factors
301301
switch (params_.linearizationMode) {
302302
case HESSIAN:
303-
return createHessianFactor(cameras, lambda);
303+
return createHessianFactor(cameras, _lambda);
304304
case IMPLICIT_SCHUR:
305-
return createRegularImplicitSchurFactor(cameras, lambda);
305+
return createRegularImplicitSchurFactor(cameras, _lambda);
306306
case JACOBIAN_SVD:
307-
return createJacobianSVDFactor(cameras, lambda);
307+
return createJacobianSVDFactor(cameras, _lambda);
308308
case JACOBIAN_Q:
309-
return createJacobianQFactor(cameras, lambda);
309+
return createJacobianQFactor(cameras, _lambda);
310310
default:
311311
throw std::runtime_error("SmartFactorlinearize: unknown mode");
312312
}
@@ -318,10 +318,10 @@ class SmartProjectionFactor: public SmartFactorBase<CAMERA> {
318318
* @return a Gaussian factor
319319
*/
320320
std::shared_ptr<GaussianFactor> linearizeDamped(const Values& values,
321-
const double lambda = 0.0) const {
321+
const double _lambda = 0.0) const {
322322
// depending on flag set on construction we may linearize to different linear factors
323323
Cameras cameras = this->cameras(values);
324-
return linearizeDamped(cameras, lambda);
324+
return linearizeDamped(cameras, _lambda);
325325
}
326326

327327
/// linearize

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>

gtsam_unstable/slam/SmartStereoProjectionFactor.h

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -271,9 +271,9 @@ class SmartStereoProjectionFactor
271271

272272
/// different (faster) way to compute Jacobian factor
273273
std::shared_ptr<JacobianFactor> createJacobianSVDFactor(
274-
const Cameras& cameras, double lambda) const {
274+
const Cameras& cameras, double _lambda) const {
275275
if (triangulateForLinearize(cameras))
276-
return Base::createJacobianSVDFactor(cameras, *result_, lambda);
276+
return Base::createJacobianSVDFactor(cameras, *result_, _lambda);
277277
else
278278
return std::make_shared<JacobianFactorSVD<Base::Dim, ZDim> >(this->keys_);
279279
}
@@ -302,15 +302,15 @@ class SmartStereoProjectionFactor
302302
* @return a Gaussian factor
303303
*/
304304
std::shared_ptr<GaussianFactor> linearizeDamped(const Cameras& cameras,
305-
const double lambda = 0.0) const {
305+
const double _lambda = 0.0) const {
306306
// depending on flag set on construction we may linearize to different linear factors
307307
switch (params_.linearizationMode) {
308308
case HESSIAN:
309-
return createHessianFactor(cameras, lambda);
309+
return createHessianFactor(cameras, _lambda);
310310
// case IMPLICIT_SCHUR:
311-
// return createRegularImplicitSchurFactor(cameras, lambda);
311+
// return createRegularImplicitSchurFactor(cameras, _lambda);
312312
case JACOBIAN_SVD:
313-
return createJacobianSVDFactor(cameras, lambda);
313+
return createJacobianSVDFactor(cameras, _lambda);
314314
// case JACOBIAN_Q:
315315
// return createJacobianQFactor(cameras, lambda);
316316
default:
@@ -324,10 +324,10 @@ class SmartStereoProjectionFactor
324324
* @return a Gaussian factor
325325
*/
326326
std::shared_ptr<GaussianFactor> linearizeDamped(const Values& values,
327-
const double lambda = 0.0) const {
327+
const double _lambda = 0.0) const {
328328
// depending on flag set on construction we may linearize to different linear factors
329329
Cameras cameras = this->cameras(values);
330-
return linearizeDamped(cameras, lambda);
330+
return linearizeDamped(cameras, _lambda);
331331
}
332332

333333
/// linearize

wrap/tests/fixtures/class.i

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,6 @@ 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_`
8685
void lambda() const;
8786

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

0 commit comments

Comments
 (0)