30 #include <gtsam/config.h> 33 # include <tbb/parallel_for.h> 45 template class FactorGraph<NonlinearFactor>;
48 double NonlinearFactorGraph::probPrime(
const Values&
values)
const {
54 cout << str <<
"size: " <<
size() << endl << endl;
55 for (
size_t i = 0;
i < factors_.size();
i++) {
57 ss <<
"Factor " <<
i <<
": ";
58 if (factors_[i] !=
nullptr) factors_[
i]->print(ss.str(), keyFormatter);
64 void NonlinearFactorGraph::printErrors(
const Values&
values,
const std::string&
str,
66 const std::function<
bool(
const Factor* ,
double ,
size_t )>& printCondition)
const 68 cout << str <<
"size: " <<
size() << endl
70 for (
size_t i = 0;
i < factors_.size();
i++) {
72 const double errorValue = (factor !=
nullptr ? factors_[
i]->error(values) : .0);
73 if (!printCondition(factor.get(),errorValue,
i))
77 ss <<
"Factor " <<
i <<
": ";
78 if (factor ==
nullptr) {
79 cout <<
"nullptr" <<
"\n";
81 factor->print(ss.str(), keyFormatter);
82 cout <<
"error = " << errorValue <<
"\n";
90 return Base::equals(other, tol);
94 void NonlinearFactorGraph::saveGraph(std::ostream &stm,
const Values& values,
105 struct { boost::optional<Point2> operator()(
110 t <<
p->value().x(),
p->value().y(), 0;
112 t <<
p->value().x(),
p->value().y(), 0;
114 t =
p->value().translation();
125 case GraphvizFormatting::NEGX: x = -t.x();
break;
126 case GraphvizFormatting::NEGY: x = -t.y();
break;
127 case GraphvizFormatting::NEGZ: x = -t.z();
break;
128 default:
throw std::runtime_error(
"Invalid enum value");
134 case GraphvizFormatting::NEGX: y = -t.x();
break;
135 case GraphvizFormatting::NEGY: y = -t.y();
break;
136 case GraphvizFormatting::NEGZ: y = -t.z();
break;
137 default:
throw std::runtime_error(
"Invalid enum value");
143 double minX = numeric_limits<double>::infinity(), maxX = -numeric_limits<double>::infinity();
144 double minY = numeric_limits<double>::infinity(), maxY = -numeric_limits<double>::infinity();
145 for (
const Key&
key : keys) {
147 boost::optional<Point2>
xy = getXY(values.
at(
key), formatting);
164 stm <<
" var" <<
key <<
"[label=\"" << keyFormatter(
key) <<
"\"";
166 boost::optional<Point2>
xy = getXY(values.
at(
key), formatting);
168 stm <<
", pos=\"" << formatting.
scale*(xy->x() - minX) <<
"," << formatting.
scale*(xy->y() - minY) <<
"!\"";
176 std::set<KeyVector > structure;
180 std::sort(factorKeys.begin(), factorKeys.end());
181 structure.insert(factorKeys);
187 for(
const KeyVector& factorKeys: structure){
189 stm <<
" factor" << i <<
"[label=\"\", shape=point";
193 stm <<
", pos=\"" << formatting.
scale*(pos->second.x() - minX) <<
"," 194 << formatting.
scale*(pos->second.y() - minY) <<
"!\"";
199 for(
Key key: factorKeys) {
200 stm <<
" var" <<
key <<
"--" <<
"factor" << i <<
";\n";
207 for(
size_t i = 0;
i <
size(); ++
i) {
217 stm <<
" var" << keys[0] <<
"--" 218 <<
"var" << keys[1] <<
";\n";
221 stm <<
" factor" <<
i <<
"[label=\"\", shape=point";
223 map<size_t, Point2>::const_iterator
pos =
226 stm <<
", pos=\"" << formatting.
scale * (pos->second.x() - minX)
227 <<
"," << formatting.
scale * (pos->second.y() - minY)
235 stm <<
" var" <<
key <<
"--" 236 <<
"factor" << i <<
";\n";
242 bool firstTime =
true;
249 stm <<
" var" <<
key <<
"--" 250 <<
"var" << k <<
";\n";
261 void NonlinearFactorGraph::saveGraph(
262 const std::string&
file,
const Values& values,
265 std::ofstream of(file);
266 saveGraph(of, values, graphvizFormatting, keyFormatter);
272 gttic(NonlinearFactorGraph_error);
273 double total_error = 0.;
277 total_error += factor->error(values);
283 Ordering NonlinearFactorGraph::orderingCOLAMD()
const 285 return Ordering::Colamd(*
this);
291 return Ordering::ColamdConstrained(*
this, constraints);
299 symbolic->reserve(
size());
315 class _LinearizeOneFactor {
317 const Values& linearizationPoint_;
323 nonlinearGraph_(graph), linearizationPoint_(linearizationPoint), result_(result) {
326 void operator()(
const tbb::blocked_range<size_t>& blocked_range)
const {
327 for (
size_t i = blocked_range.begin();
i != blocked_range.end(); ++
i) {
328 if (nonlinearGraph_[
i])
329 result_[
i] = nonlinearGraph_[
i]->
linearize(linearizationPoint_);
342 gttic(NonlinearFactorGraph_linearize);
349 linearFG->resize(
size());
351 tbb::parallel_for(tbb::blocked_range<size_t>(0,
size()),
352 _LinearizeOneFactor(*
this, linearizationPoint, *linearFG));
356 linearFG->reserve(
size());
361 (*linearFG) += factor->linearize(linearizationPoint);
376 scatter.reserve(values.
size());
379 for (
const auto key_value : values) {
380 scatter.
add(key_value.key, key_value.value.dim());
391 scatter.reserve(values.
size());
394 for (
Key key : ordering) {
409 hessianFactor->info_.setZero();
414 if (nonlinearFactor) {
415 const auto& gaussianFactor = nonlinearFactor->linearize(values);
416 gaussianFactor->updateHessian(hessianFactor->keys_, &hessianFactor->info_);
420 if (dampen) dampen(hessianFactor);
422 return hessianFactor;
428 gttic(NonlinearFactorGraph_linearizeToHessianFactor);
431 return linearizeToHessianFactor(values, scatter, dampen);
437 gttic(NonlinearFactorGraph_linearizeToHessianFactor);
440 return linearizeToHessianFactor(values, scatter, dampen);
445 const Dampen& dampen)
const {
446 gttic(NonlinearFactorGraph_updateCholesky);
447 auto hessianFactor = linearizeToHessianFactor(values, dampen);
455 const Dampen& dampen)
const {
456 gttic(NonlinearFactorGraph_updateCholesky);
457 auto hessianFactor = linearizeToHessianFactor(values, ordering, dampen);
void print(const Matrix &A, const string &s, ostream &stream)
GTSAM_EXPORT void add(Key key, size_t dim)
Add a key/dim pair.
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Values retract(const VectorValues &delta) const
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
const ValueType at(Key j) const
std::function< void(const boost::shared_ptr< HessianFactor > &hessianFactor)> Dampen
typdef for dampen functions used below
boost::shared_ptr< This > shared_ptr
boost::shared_ptr< NonlinearFactor > sharedFactor
Shared pointer to a factor.
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Linear Factor Graph where all factors are Gaussians.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
virtual size_t dim() const =0
Exceptions that may be thrown by linear solver components.
static std::stringstream ss
static Scatter scatterFromValues(const Values &values, const Ordering &ordering)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
A Gaussian factor using the canonical parameters (information form)
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
std::uint64_t Key
Integer nonlinear key type.