test_GraphvizFormatting.py
Go to the documentation of this file.
1 """
2 See LICENSE for the license information
3 
4 Unit tests for Graphviz formatting of NonlinearFactorGraph.
5 Author: senselessDev (contact by mentioning on GitHub, e.g. in PR#1059)
6 """
7 
8 # pylint: disable=no-member, invalid-name
9 
10 import unittest
11 import textwrap
12 
13 import numpy as np
14 
15 import gtsam
16 from gtsam.utils.test_case import GtsamTestCase
17 
18 
20  """Tests for saving NonlinearFactorGraph to GraphViz format."""
21 
22  def setUp(self):
24 
25  odometry = gtsam.Pose2(2.0, 0.0, 0.0)
26  odometryNoise = gtsam.noiseModel.Diagonal.Sigmas(
27  np.array([0.2, 0.2, 0.1]))
28  self.graph.add(gtsam.BetweenFactorPose2(0, 1, odometry, odometryNoise))
29  self.graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise))
30 
32  self.values.insert_pose2(0, gtsam.Pose2(0., 0., 0.))
33  self.values.insert_pose2(1, gtsam.Pose2(2., 0., 0.))
34  self.values.insert_pose2(2, gtsam.Pose2(4., 0., 0.))
35 
36  def test_default(self):
37  """Test with default GraphvizFormatting"""
38  expected_result = """\
39  graph {
40  size="5,5";
41 
42  var0[label="0", pos="0,0!"];
43  var1[label="1", pos="0,2!"];
44  var2[label="2", pos="0,4!"];
45 
46  factor0[label="", shape=point];
47  var0--factor0;
48  var1--factor0;
49  factor1[label="", shape=point];
50  var1--factor1;
51  var2--factor1;
52  }
53  """
54 
55  self.assertEqual(self.graph.dot(self.values),
56  textwrap.dedent(expected_result))
57 
58  def test_swapped_axes(self):
59  """Test with user-defined GraphvizFormatting swapping x and y"""
60  expected_result = """\
61  graph {
62  size="5,5";
63 
64  var0[label="0", pos="0,0!"];
65  var1[label="1", pos="2,0!"];
66  var2[label="2", pos="4,0!"];
67 
68  factor0[label="", shape=point];
69  var0--factor0;
70  var1--factor0;
71  factor1[label="", shape=point];
72  var1--factor1;
73  var2--factor1;
74  }
75  """
76 
77  graphviz_formatting = gtsam.GraphvizFormatting()
78  graphviz_formatting.paperHorizontalAxis = gtsam.GraphvizFormatting.Axis.X
79  graphviz_formatting.paperVerticalAxis = gtsam.GraphvizFormatting.Axis.Y
80  self.assertEqual(self.graph.dot(self.values,
81  writer=graphviz_formatting),
82  textwrap.dedent(expected_result))
83 
84  def test_factor_points(self):
85  """Test with user-defined GraphvizFormatting without factor points"""
86  expected_result = """\
87  graph {
88  size="5,5";
89 
90  var0[label="0", pos="0,0!"];
91  var1[label="1", pos="0,2!"];
92  var2[label="2", pos="0,4!"];
93 
94  var0--var1;
95  var1--var2;
96  }
97  """
98 
99  graphviz_formatting = gtsam.GraphvizFormatting()
100  graphviz_formatting.plotFactorPoints = False
101 
102  self.assertEqual(self.graph.dot(self.values,
103  writer=graphviz_formatting),
104  textwrap.dedent(expected_result))
105 
106  def test_width_height(self):
107  """Test with user-defined GraphvizFormatting for width and height"""
108  expected_result = """\
109  graph {
110  size="20,10";
111 
112  var0[label="0", pos="0,0!"];
113  var1[label="1", pos="0,2!"];
114  var2[label="2", pos="0,4!"];
115 
116  factor0[label="", shape=point];
117  var0--factor0;
118  var1--factor0;
119  factor1[label="", shape=point];
120  var1--factor1;
121  var2--factor1;
122  }
123  """
124 
125  graphviz_formatting = gtsam.GraphvizFormatting()
126  graphviz_formatting.figureWidthInches = 20
127  graphviz_formatting.figureHeightInches = 10
128 
129  self.assertEqual(self.graph.dot(self.values,
130  writer=graphviz_formatting),
131  textwrap.dedent(expected_result))
132 
133 
134 if __name__ == "__main__":
135  unittest.main()
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:37:45