diff --git a/python/gtsam/examples/SimpleRotation.py b/python/gtsam/examples/SimpleRotation.py index 0fef261f8..3d5fd9e45 100644 --- a/python/gtsam/examples/SimpleRotation.py +++ b/python/gtsam/examples/SimpleRotation.py @@ -31,7 +31,7 @@ def main(): - A measurement model with the correct dimensionality for the factor """ prior = gtsam.Rot2.fromAngle(np.deg2rad(30)) - prior.print_('goal angle') + prior.print('goal angle') model = gtsam.noiseModel.Isotropic.Sigma(dim=1, sigma=np.deg2rad(1)) key = X(1) factor = gtsam.PriorFactorRot2(key, prior, model) @@ -48,7 +48,7 @@ def main(): """ graph = gtsam.NonlinearFactorGraph() graph.push_back(factor) - graph.print_('full graph') + graph.print('full graph') """ Step 3: Create an initial estimate @@ -65,7 +65,7 @@ def main(): """ initial = gtsam.Values() initial.insert(key, gtsam.Rot2.fromAngle(np.deg2rad(20))) - initial.print_('initial estimate') + initial.print('initial estimate') """ Step 4: Optimize @@ -77,7 +77,7 @@ def main(): with the final state of the optimization. """ result = gtsam.LevenbergMarquardtOptimizer(graph, initial).optimize() - result.print_('final result') + result.print('final result') if __name__ == '__main__': diff --git a/python/gtsam/examples/VisualISAMExample.py b/python/gtsam/examples/VisualISAMExample.py index f99d3f3e6..9691b3c46 100644 --- a/python/gtsam/examples/VisualISAMExample.py +++ b/python/gtsam/examples/VisualISAMExample.py @@ -10,8 +10,6 @@ A visualSLAM example for the structure-from-motion problem on a simulated datase This version uses iSAM to solve the problem incrementally """ -from __future__ import print_function - import numpy as np import gtsam from gtsam.examples import SFMdata @@ -94,7 +92,7 @@ def main(): current_estimate = isam.estimate() print('*' * 50) print('Frame {}:'.format(i)) - current_estimate.print_('Current estimate: ') + current_estimate.print('Current estimate: ') # Clear the factor graph and values for the next iteration graph.resize(0) diff --git a/python/gtsam/utils/visual_data_generator.py b/python/gtsam/utils/visual_data_generator.py index 51852760a..b2a7e2d29 100644 --- a/python/gtsam/utils/visual_data_generator.py +++ b/python/gtsam/utils/visual_data_generator.py @@ -36,7 +36,7 @@ class GroundTruth: self.cameras = [Pose3()] * nrCameras self.points = [Point3(0, 0, 0)] * nrPoints - def print_(self, s="") -> None: + def print(self, s="") -> None: print(s) print("K = ", self.K) print("Cameras: ", len(self.cameras))