gtsam 4.1.1
gtsam
utilities.h
Go to the documentation of this file.
1/* ----------------------------------------------------------------------------
2
3 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4 * Atlanta, Georgia 30332-0415
5 * All Rights Reserved
6 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7
8 * See LICENSE for the license information
9
10 * -------------------------------------------------------------------------- */
11
18#pragma once
19
32
33#include <exception>
34
35namespace gtsam {
36
37namespace utilities {
38
39// Create a KeyList from indices
40FastList<Key> createKeyList(const Vector& I) {
41 FastList<Key> set;
42 for (int i = 0; i < I.size(); i++)
43 set.push_back(I[i]);
44 return set;
45}
46
47// Create a KeyList from indices using symbol
48FastList<Key> createKeyList(std::string s, const Vector& I) {
49 FastList<Key> set;
50 char c = s[0];
51 for (int i = 0; i < I.size(); i++)
52 set.push_back(Symbol(c, I[i]));
53 return set;
54}
55
56// Create a KeyVector from indices
57KeyVector createKeyVector(const Vector& I) {
58 KeyVector set;
59 for (int i = 0; i < I.size(); i++)
60 set.push_back(I[i]);
61 return set;
62}
63
64// Create a KeyVector from indices using symbol
65KeyVector createKeyVector(std::string s, const Vector& I) {
66 KeyVector set;
67 char c = s[0];
68 for (int i = 0; i < I.size(); i++)
69 set.push_back(Symbol(c, I[i]));
70 return set;
71}
72
73// Create a KeySet from indices
74KeySet createKeySet(const Vector& I) {
75 KeySet set;
76 for (int i = 0; i < I.size(); i++)
77 set.insert(I[i]);
78 return set;
79}
80
81// Create a KeySet from indices using symbol
82KeySet createKeySet(std::string s, const Vector& I) {
83 KeySet set;
84 char c = s[0];
85 for (int i = 0; i < I.size(); i++)
86 set.insert(symbol(c, I[i]));
87 return set;
88}
89
91Matrix extractPoint2(const Values& values) {
93 // Point2 is aliased as a gtsam::Vector in the wrapper
94 Values::ConstFiltered<gtsam::Vector> points2 = values.filter<gtsam::Vector>();
95
96 Matrix result(points.size() + points2.size(), 2);
97
98 size_t j = 0;
99 for (const auto& key_value : points) {
100 result.row(j++) = key_value.value;
101 }
102 for (const auto& key_value : points2) {
103 if (key_value.value.rows() == 2) {
104 result.row(j++) = key_value.value;
105 }
106 }
107 return result;
108}
109
111Matrix extractPoint3(const Values& values) {
113 // Point3 is aliased as a gtsam::Vector in the wrapper
114 Values::ConstFiltered<gtsam::Vector> points2 = values.filter<gtsam::Vector>();
115
116 Matrix result(points.size() + points2.size(), 3);
117
118 size_t j = 0;
119 for (const auto& key_value : points) {
120 result.row(j++) = key_value.value;
121 }
122 for (const auto& key_value : points2) {
123 if (key_value.value.rows() == 3) {
124 result.row(j++) = key_value.value;
125 }
126 }
127 return result;
128}
129
131Values allPose2s(const Values& values) {
132 return values.filter<Pose2>();
133}
134
136Matrix extractPose2(const Values& values) {
137 Values::ConstFiltered<Pose2> poses = values.filter<Pose2>();
138 Matrix result(poses.size(), 3);
139 size_t j = 0;
140 for(const auto& key_value: poses)
141 result.row(j++) << key_value.value.x(), key_value.value.y(), key_value.value.theta();
142 return result;
143}
144
146Values allPose3s(const Values& values) {
147 return values.filter<Pose3>();
148}
149
151Matrix extractPose3(const Values& values) {
152 Values::ConstFiltered<Pose3> poses = values.filter<Pose3>();
153 Matrix result(poses.size(), 12);
154 size_t j = 0;
155 for(const auto& key_value: poses) {
156 result.row(j).segment(0, 3) << key_value.value.rotation().matrix().row(0);
157 result.row(j).segment(3, 3) << key_value.value.rotation().matrix().row(1);
158 result.row(j).segment(6, 3) << key_value.value.rotation().matrix().row(2);
159 result.row(j).tail(3) = key_value.value.translation();
160 j++;
161 }
162 return result;
163}
164
166void perturbPoint2(Values& values, double sigma, int32_t seed = 42u) {
167 noiseModel::Isotropic::shared_ptr model =
169 Sampler sampler(model, seed);
170 for (const auto& key_value : values.filter<Point2>()) {
171 values.update<Point2>(key_value.key,
172 key_value.value + Point2(sampler.sample()));
173 }
174 for (const auto& key_value : values.filter<gtsam::Vector>()) {
175 if (key_value.value.rows() == 2) {
176 values.update<gtsam::Vector>(key_value.key,
177 key_value.value + Point2(sampler.sample()));
178 }
179 }
180}
181
183void perturbPose2(Values& values, double sigmaT, double sigmaR, int32_t seed =
184 42u) {
185 noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(
186 Vector3(sigmaT, sigmaT, sigmaR));
187 Sampler sampler(model, seed);
188 for(const auto& key_value: values.filter<Pose2>()) {
189 values.update<Pose2>(key_value.key, key_value.value.retract(sampler.sample()));
190 }
191}
192
194void perturbPoint3(Values& values, double sigma, int32_t seed = 42u) {
195 noiseModel::Isotropic::shared_ptr model =
197 Sampler sampler(model, seed);
198 for (const auto& key_value : values.filter<Point3>()) {
199 values.update<Point3>(key_value.key,
200 key_value.value + Point3(sampler.sample()));
201 }
202 for (const auto& key_value : values.filter<gtsam::Vector>()) {
203 if (key_value.value.rows() == 3) {
204 values.update<gtsam::Vector>(key_value.key,
205 key_value.value + Point3(sampler.sample()));
206 }
207 }
208}
209
220 const Vector& J, const Matrix& Z, double depth) {
221 if (Z.rows() != 2)
222 throw std::invalid_argument("insertBackProjections: Z must be 2*J");
223 if (Z.cols() != J.size())
224 throw std::invalid_argument(
225 "insertBackProjections: J and Z must have same number of entries");
226 for (int k = 0; k < Z.cols(); k++) {
227 Point2 p(Z(0, k), Z(1, k));
228 Point3 P = camera.backproject(p, depth);
229 values.insert(J(k), P);
230 }
231}
232
245 const Vector& J, const Matrix& Z, const SharedNoiseModel& model,
246 const Cal3_S2::shared_ptr K, const Pose3& body_P_sensor = Pose3()) {
247 if (Z.rows() != 2)
248 throw std::invalid_argument("addMeasurements: Z must be 2*K");
249 if (Z.cols() != J.size())
250 throw std::invalid_argument(
251 "addMeasurements: J and Z must have same number of entries");
252 for (int k = 0; k < Z.cols(); k++) {
253 graph.push_back(
255 Point2(Z(0, k), Z(1, k)), model, i, Key(J(k)), K, body_P_sensor));
256 }
257}
258
261 const Values& values) {
262 // first count
263 size_t K = 0, k = 0;
264 for(const NonlinearFactor::shared_ptr& f: graph)
265 if (boost::dynamic_pointer_cast<const GenericProjectionFactor<Pose3, Point3> >(
266 f))
267 ++K;
268 // now fill
269 Matrix errors(2, K);
270 for(const NonlinearFactor::shared_ptr& f: graph) {
271 boost::shared_ptr<const GenericProjectionFactor<Pose3, Point3> > p =
272 boost::dynamic_pointer_cast<const GenericProjectionFactor<Pose3, Point3> >(
273 f);
274 if (p)
275 errors.col(k++) = p->unwhitenedError(values);
276 }
277 return errors;
278}
279
281Values localToWorld(const Values& local, const Pose2& base,
282 const KeyVector user_keys = KeyVector()) {
283
284 Values world;
285
286 // if no keys given, get all keys from local values
287 KeyVector keys(user_keys);
288 if (keys.size()==0)
289 keys = local.keys();
290
291 // Loop over all keys
292 for(Key key: keys) {
293 try {
294 // if value is a Pose2, compose it with base pose
295 Pose2 pose = local.at<Pose2>(key);
296 world.insert(key, base.compose(pose));
297 } catch (const std::exception& e1) {
298 try {
299 // if value is a Point2, transform it from base pose
300 Point2 point = local.at<Point2>(key);
301 world.insert(key, base.transformFrom(point));
302 } catch (const std::exception& e2) {
303 // if not Pose2 or Point2, do nothing
304 #ifndef NDEBUG
305 std::cerr << "Values[key] is neither Pose2 nor Point2, so skip" << std::endl;
306 #endif
307 }
308 }
309 }
310 return world;
311}
312
313} // namespace utilities
314
315}
316
The most common 5DOF 3D->2D calibration.
3D Point
Base class for all pinhole cameras.
3D Pose
2D Point
2D Pose
sampling from a NoiseModel
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
Non-linear factor base classes.
Reprojection of a LANDMARK to a 2D point.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Key symbol(unsigned char c, std::uint64_t j)
Create a symbol key from a character and index, i.e.
Definition: Symbol.h:135
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition: Point2.h:27
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, boost::shared_ptr< T > > make_shared(Args &&... args)
Add our own make_shared as a layer of wrapping on boost::make_shared This solves the problem with the...
Definition: make_shared.h:57
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
Definition: PinholeCamera.h:33
Point3 backproject(const Point2 &p, double depth, OptionalJacobian< 3, 6 > Dresult_dpose=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none, OptionalJacobian< 3, DimK > Dresult_dcal=boost::none) const
backproject a 2-dimensional point to a 3-dimensional point at given depth
Definition: PinholePose.h:132
Definition: Pose2.h:36
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
Return point coordinates in global frame.
Definition: Pose2.cpp:218
Definition: Pose3.h:37
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
A diagonal noise model created by specifying a Vector of sigmas, i.e.
Definition: NoiseModel.cpp:270
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:567
Sampling structure that keeps internal random number generators for diagonal distributions specified ...
Definition: Sampler.h:31
Vector sample() const
sample from distribution
Definition: Sampler.cpp:51
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:78
A filtered view of a const Values, returned from Values::filter.
Definition: Values-inl.h:169
size_t size() const
Returns the number of values in this view.
Definition: Values-inl.h:189
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:63
const ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:346
KeyVector keys() const
Returns a set of keys in the config Note: by construction, the list is ordered.
Definition: Values.cpp:183
void insert(Key j, const Value &val)
Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present.
Definition: Values.cpp:132
void update(Key j, const Value &val)
single element change of existing element
Definition: Values.cpp:153
Filtered< Value > filter(const std::function< bool(Key)> &filterFcn)
Return a filtered view of this Values class, without copying any data.
Definition: Values-inl.h:239
Definition: ProjectionFactor.h:40
Matrix extractPoint2(const Values &values)
Extract all Point2 values into a single matrix [x y].
Definition: utilities.h:91
Values localToWorld(const Values &local, const Pose2 &base, const KeyVector user_keys=KeyVector())
Convert from local to world coordinates.
Definition: utilities.h:281
Matrix extractPoint3(const Values &values)
Extract all Point3 values into a single matrix [x y z].
Definition: utilities.h:111
Matrix reprojectionErrors(const NonlinearFactorGraph &graph, const Values &values)
Calculate the errors of all projection factors in a graph.
Definition: utilities.h:260
void perturbPoint2(Values &values, double sigma, int32_t seed=42u)
Perturb all Point2 values using normally distributed noise.
Definition: utilities.h:166
void perturbPose2(Values &values, double sigmaT, double sigmaR, int32_t seed=42u)
Perturb all Pose2 values using normally distributed noise.
Definition: utilities.h:183
Values allPose2s(const Values &values)
Extract all Pose3 values.
Definition: utilities.h:131
void insertProjectionFactors(NonlinearFactorGraph &graph, Key i, const Vector &J, const Matrix &Z, const SharedNoiseModel &model, const Cal3_S2::shared_ptr K, const Pose3 &body_P_sensor=Pose3())
Insert multiple projection factors for a single pose key.
Definition: utilities.h:244
Values allPose3s(const Values &values)
Extract all Pose3 values.
Definition: utilities.h:146
void insertBackprojections(Values &values, const PinholeCamera< Cal3_S2 > &camera, const Vector &J, const Matrix &Z, double depth)
Insert a number of initial point values by backprojecting.
Definition: utilities.h:219
Matrix extractPose3(const Values &values)
Extract all Pose3 values into a single matrix [r11 r12 r13 r21 r22 r23 r31 r32 r33 x y z].
Definition: utilities.h:151
Matrix extractPose2(const Values &values)
Extract all Pose2 values into a single matrix [x y theta].
Definition: utilities.h:136
void perturbPoint3(Values &values, double sigma, int32_t seed=42u)
Perturb all Point3 values using normally distributed noise.
Definition: utilities.h:194