20 #include <gtsam/inference/Symbol.h> 40 FastList<Key> createKeyList(
const Vector& I) {
42 for (
int i = 0; i < I.size(); i++)
48 FastList<Key> createKeyList(std::string s,
const Vector& I) {
51 for (
int i = 0; i < I.size(); i++)
52 set.push_back(Symbol(c, I[i]));
57 KeyVector createKeyVector(
const Vector& I) {
59 for (
int i = 0; i < I.size(); i++)
65 KeyVector createKeyVector(std::string s,
const Vector& I) {
68 for (
int i = 0; i < I.size(); i++)
69 set.push_back(Symbol(c, I[i]));
74 KeySet createKeySet(
const Vector& I) {
76 for (
int i = 0; i < I.size(); i++)
82 KeySet createKeySet(std::string s,
const Vector& I) {
85 for (
int i = 0; i < I.size(); i++)
86 set.insert(
symbol(c, I[i]));
91 Matrix extractPoint2(
const Values& values) {
93 Values::ConstFiltered<Point2> points = values.filter<Point2>();
94 Matrix result(points.size(), 2);
95 for(
const auto& key_value: points)
96 result.row(j++) = key_value.value;
101 Matrix extractPoint3(
const Values& values) {
102 Values::ConstFiltered<Point3> points = values.filter<Point3>();
103 Matrix result(points.size(), 3);
105 for(
const auto& key_value: points)
106 result.row(j++) = key_value.value;
111 Matrix extractPose2(
const Values& values) {
112 Values::ConstFiltered<Pose2> poses = values.filter<Pose2>();
113 Matrix result(poses.size(), 3);
115 for(
const auto& key_value: poses)
116 result.row(j++) << key_value.value.x(), key_value.value.y(), key_value.value.theta();
121 Values allPose3s(
const Values& values) {
122 return values.
filter<Pose3>();
126 Matrix extractPose3(
const Values& values) {
127 Values::ConstFiltered<Pose3> poses = values.filter<Pose3>();
128 Matrix result(poses.size(), 12);
130 for(
const auto& key_value: poses) {
131 result.row(j).segment(0, 3) << key_value.value.rotation().matrix().row(0);
132 result.row(j).segment(3, 3) << key_value.value.rotation().matrix().row(1);
133 result.row(j).segment(6, 3) << key_value.value.rotation().matrix().row(2);
134 result.row(j).tail(3) = key_value.value.translation();
141 void perturbPoint2(Values& values,
double sigma, int32_t seed = 42u) {
144 Sampler sampler(model, seed);
145 for(
const auto& key_value: values.filter<Point2>()) {
146 values.update<Point2>(key_value.key, key_value.value + Point2(sampler.sample()));
151 void perturbPose2(Values& values,
double sigmaT,
double sigmaR, int32_t seed =
154 Vector3(sigmaT, sigmaT, sigmaR));
155 Sampler sampler(model, seed);
156 for(
const auto& key_value: values.filter<Pose2>()) {
157 values.update<Pose2>(key_value.key, key_value.value.retract(sampler.sample()));
162 void perturbPoint3(Values& values,
double sigma, int32_t seed = 42u) {
165 Sampler sampler(model, seed);
166 for(
const auto& key_value: values.filter<Point3>()) {
167 values.update<Point3>(key_value.key, key_value.value + Point3(sampler.sample()));
172 void insertBackprojections(Values& values,
const SimpleCamera& camera,
173 const Vector& J,
const Matrix& Z,
double depth) {
175 throw std::invalid_argument(
"insertBackProjections: Z must be 2*K");
176 if (Z.cols() != J.size())
177 throw std::invalid_argument(
178 "insertBackProjections: J and Z must have same number of entries");
179 for (
int k = 0; k < Z.cols(); k++) {
180 Point2 p(Z(0, k), Z(1, k));
181 Point3 P = camera.backproject(p, depth);
182 values.insert(J(k), P);
187 void insertProjectionFactors(NonlinearFactorGraph& graph,
Key i,
191 throw std::invalid_argument(
"addMeasurements: Z must be 2*K");
192 if (Z.cols() != J.size())
193 throw std::invalid_argument(
194 "addMeasurements: J and Z must have same number of entries");
195 for (
int k = 0; k < Z.cols(); k++) {
197 boost::make_shared<GenericProjectionFactor<Pose3, Point3> >(
198 Point2(Z(0, k), Z(1, k)), model, i,
Key(J(k)), K, body_P_sensor));
203 Matrix reprojectionErrors(
const NonlinearFactorGraph& graph,
204 const Values& values) {
207 for(
const NonlinearFactor::shared_ptr& f: graph)
208 if (boost::dynamic_pointer_cast<
const GenericProjectionFactor<Pose3, Point3> >(
213 for(
const NonlinearFactor::shared_ptr& f: graph) {
214 boost::shared_ptr<const GenericProjectionFactor<Pose3, Point3> > p =
215 boost::dynamic_pointer_cast<
const GenericProjectionFactor<Pose3, Point3> >(
218 errors.col(k++) = p->unwhitenedError(values);
224 Values localToWorld(
const Values& local,
const Pose2& base,
238 Pose2 pose = local.at<Pose2>(key);
239 world.insert(key, base.compose(pose));
240 }
catch (std::exception e1) {
243 Point2 point = local.at<Point2>(key);
244 world.insert(key, base.transformFrom(point));
245 }
catch (std::exception e2) {
263 RedirectCout() : ssBuffer_(), coutBuffer_(std::cout.rdbuf(ssBuffer_.rdbuf())) {}
267 return ssBuffer_.str();
272 std::cout.rdbuf(coutBuffer_);
276 std::stringstream ssBuffer_;
277 std::streambuf* coutBuffer_;
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)
Return a filtered view of this Values class, without copying any data.
Definition: Values-inl.h:237
~RedirectCout()
destructor – redirect stdout buffer to its original buffer
Definition: utilities.h:271
The most common 5DOF 3D->2D calibration.
A simple camera class with a Cal3_S2 calibration.
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:264
For Python str().
Definition: utilities.h:261
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
sampling that can be parameterized using a NoiseModel to generate samples fromthe given distribution
boost::shared_ptr< Cal3_S2 > shared_ptr
shared pointer to calibration object
Definition: Cal3_S2.h:39
Factor Graph Constsiting of non-linear factors.
std::string str() const
return the string
Definition: utilities.h:266
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
Basic bearing factor from 2D measurement.
Non-linear factor base classes.
A non-templated config holding any types of Manifold-group elements.
RedirectCout()
constructor – redirect stdout buffer to a stringstream buffer
Definition: utilities.h:263
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
Key symbol(unsigned char c, std::uint64_t j)
Create a symbol key from a character and index, i.e.
Definition: Symbol.h:127
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:561