18 #define BOOST_SPIRIT_USE_PHOENIX_V3 1 27 #include <boost/fusion/include/vector.hpp> 28 #include <boost/fusion/sequence.hpp> 29 #include <boost/lambda/lambda.hpp> 30 #include <boost/phoenix/bind.hpp> 31 #include <boost/spirit/include/classic.hpp> 32 #include <boost/spirit/include/qi.hpp> 38 #include <unordered_map> 41 using boost::fusion::at_c;
44 namespace bf = boost::fusion;
45 namespace qi = boost::spirit::qi;
47 using Chars = std::vector<char>;
50 template <
size_t I,
class FusionVector>
52 const Chars &chars = at_c<I>(vars);
53 return string(chars.begin(), chars.end());
66 typedef std::unordered_map<std::string, coefficient_v>
constraint_v;
68 std::unordered_map<std::string, constraint_v *>
74 std::unordered_map<std::string, double>
77 std::unordered_map<std::string, double>
79 std::unordered_map<Key, Vector1>
g;
80 std::unordered_map<std::string, Key>
82 std::unordered_map<Key, std::unordered_map<Key, Matrix11>>
87 std::unordered_map<Key, double>
89 std::unordered_map<Key, double>
91 std::unordered_map<Key, double>
100 void setName(boost::fusion::vector<Chars, Chars, Chars>
const &
name) {
101 name_ = fromChars<1>(
name);
103 cout <<
"Parsing file: " << name_ << endl;
108 double,
Chars>
const &vars) {
109 string var_ = fromChars<1>(vars);
110 string row_ = fromChars<3>(vars);
111 Matrix11 coefficient = at_c<5>(vars) * I_1x1;
113 cout <<
"Added Column for Var: " << var_ <<
" Row: " << row_
114 <<
" Coefficient: " << coefficient << endl;
116 if (!varname_to_key.count(var_))
117 varname_to_key[var_] =
Symbol(
'X', numVariables++);
118 if (row_ == obj_name) {
119 g[varname_to_key[var_]] = coefficient;
122 (*row_to_constraint_v[row_])[row_][varname_to_key[var_]] = coefficient;
127 Chars,
double>
const &vars) {
128 string var_ = fromChars<0>(vars);
129 string row1_ = fromChars<2>(vars);
130 string row2_ = fromChars<6>(vars);
131 Matrix11 coefficient1 = at_c<4>(vars) * I_1x1;
132 Matrix11 coefficient2 = at_c<8>(vars) * I_1x1;
133 if (!varname_to_key.count(var_))
134 varname_to_key.insert({var_, Symbol(
'X', numVariables++)});
135 if (row1_ == obj_name)
136 g[varname_to_key[var_]] = coefficient1;
138 (*row_to_constraint_v[row1_])[row1_][varname_to_key[var_]] = coefficient1;
139 if (row2_ == obj_name)
140 g[varname_to_key[var_]] = coefficient2;
142 (*row_to_constraint_v[row2_])[row2_][varname_to_key[var_]] = coefficient2;
146 double,
Chars>
const &vars) {
147 string var_ = fromChars<1>(vars);
148 string row_ = fromChars<3>(vars);
149 double range = at_c<5>(vars);
150 ranges[row_] = range;
152 cout <<
"SINGLE RANGE ADDED" << endl;
153 cout <<
"VAR:" << var_ <<
" ROW: " << row_ <<
" RANGE: " << range << endl;
159 string var_ = fromChars<1>(vars);
160 string row1_ = fromChars<3>(vars);
161 string row2_ = fromChars<7>(vars);
162 double range1 = at_c<5>(vars);
163 double range2 = at_c<9>(vars);
167 cout <<
"DOUBLE RANGE ADDED" << endl;
168 cout <<
"VAR: " << var_ <<
" ROW1: " << row1_ <<
" RANGE1: " << range1
169 <<
" ROW2: " << row2_ <<
" RANGE2: " << range2 << endl;
174 Chars>
const &vars) {
175 string var_ = fromChars<1>(vars);
176 string row_ = fromChars<3>(vars);
177 double coefficient = at_c<5>(vars);
178 if (row_ == obj_name) {
181 b[row_] = coefficient;
185 cout <<
"Added RHS for Var: " << var_ <<
" Row: " << row_
186 <<
" Coefficient: " << coefficient << endl;
193 string var_ = fromChars<1>(vars);
194 string row1_ = fromChars<3>(vars);
195 string row2_ = fromChars<7>(vars);
196 double coefficient1 = at_c<5>(vars);
197 double coefficient2 = at_c<9>(vars);
198 if (row1_ == obj_name) {
201 b[row1_] = coefficient1;
204 if (row2_ == obj_name) {
207 b[row2_] = coefficient2;
211 cout <<
"Added RHS for Var: " << var_ <<
" Row: " << row1_
212 <<
" Coefficient: " << coefficient1 << endl;
214 <<
"Row: " << row2_ <<
" Coefficient: " << coefficient2 << endl;
219 boost::fusion::vector<Chars, char, Chars, Chars, Chars>
const &vars) {
220 string name_ = fromChars<3>(vars);
221 char type = at_c<1>(vars);
227 row_to_constraint_v[name_] = &IL;
230 row_to_constraint_v[name_] = &IG;
233 row_to_constraint_v[name_] = &
E;
236 cout <<
"invalid type: " << type << endl;
240 cout <<
"Added Row Type: " << type <<
" Name: " << name_ << endl;
245 Chars,
double>
const &vars) {
246 string type_ = fromChars<1>(vars);
247 string var_ = fromChars<5>(vars);
248 double number = at_c<7>(vars);
249 if (type_.compare(
string(
"UP")) == 0)
250 up[varname_to_key[var_]] = number;
251 else if (type_.compare(
string(
"LO")) == 0)
252 lo[varname_to_key[var_]] = number;
253 else if (type_.compare(
string(
"FX")) == 0)
254 fx[varname_to_key[var_]] = number;
256 cout <<
"Invalid Bound Type: " << type_ << endl;
259 cout <<
"Added Bound Type: " << type_ <<
" Var: " << var_
260 <<
" Amount: " << number << endl;
266 string type_ = fromChars<1>(vars);
267 string var_ = fromChars<5>(vars);
268 free.push_back(varname_to_key[var_]);
270 cout <<
"Added Free Bound Type: " << type_ <<
" Var: " << var_
271 <<
" Amount: " << endl;
276 double,
Chars>
const &vars) {
277 string var1_ = fromChars<1>(vars);
278 string var2_ = fromChars<3>(vars);
279 Matrix11 coefficient = at_c<5>(vars) * I_1x1;
281 H[varname_to_key[var1_]][varname_to_key[var2_]] = coefficient;
282 H[varname_to_key[var2_]][varname_to_key[var1_]] = coefficient;
284 cout <<
"Added QuadTerm for Var: " << var1_ <<
" Row: " << var2_
285 <<
" Coefficient: " << coefficient << endl;
292 for (
auto kv : varname_to_key) {
293 keys.push_back(kv.second);
299 sort(keys.begin(), keys.end());
300 for (
size_t i = 0;
i < keys.size(); ++
i) {
301 for (
size_t j =
i;
j < keys.size(); ++
j) {
302 if (
H.count(keys[
i]) > 0 &&
H[keys[
i]].count(keys[
j]) > 0) {
303 Gs.emplace_back(
H[keys[i]][keys[j]]);
305 Gs.emplace_back(Z_1x1);
310 if (g.count(
key1) > 0) {
311 gs.emplace_back(-g[
key1]);
313 gs.emplace_back(Z_1x1);
323 size_t dual_key_num = keys.size() + 1;
325 map<Key, Matrix11> keyMatrixMapPos;
326 map<Key, Matrix11> keyMatrixMapNeg;
327 if (ranges.count(kv.first) == 1) {
328 for (
auto km : kv.second) {
329 keyMatrixMapPos.insert(km);
330 km.second = -km.second;
331 keyMatrixMapNeg.insert(km);
333 if (ranges[kv.first] > 0) {
337 keyMatrixMapPos,
b[kv.first] + ranges[kv.first], dual_key_num++));
338 }
else if (ranges[kv.first] < 0) {
342 keyMatrixMapNeg, ranges[kv.first] -
b[kv.first], dual_key_num++));
344 cerr <<
"ERROR: CANNOT ADD A RANGE OF ZERO" << endl;
349 map<Key, Matrix11> keyMatrixMap;
350 for (
auto km : kv.second) {
351 keyMatrixMap.insert(km);
358 map<Key, Matrix11> keyMatrixMapNeg;
359 map<Key, Matrix11> keyMatrixMapPos;
360 for (
auto km : kv.second) {
361 keyMatrixMapPos.insert(km);
362 km.second = -km.second;
363 keyMatrixMapNeg.insert(km);
367 if (ranges.count(kv.first) == 1) {
369 keyMatrixMapPos,
b[kv.first] + ranges[kv.first], dual_key_num++));
374 map<Key, Matrix11> keyMatrixMapPos;
375 map<Key, Matrix11> keyMatrixMapNeg;
376 for (
auto km : kv.second) {
377 keyMatrixMapPos.insert(km);
378 km.second = -km.second;
379 keyMatrixMapNeg.insert(km);
383 if (ranges.count(kv.first) == 1) {
385 keyMatrixMapNeg, ranges[kv.first] -
b[kv.first], dual_key_num++));
390 if (find(free.begin(), free.end(), k) != free.end())
continue;
391 if (
fx.count(k) == 1)
394 if (up.count(k) == 1)
397 if (lo.count(k) == 1)
408 typedef qi::grammar<boost::spirit::basic_istream_iterator<char>>
base_grammar;
413 boost::function<void(bf::vector<Chars, Chars, Chars>
const &)> setName;
414 boost::function<void(bf::vector<Chars, char, Chars, Chars, Chars>
const &)>
416 boost::function<void(
417 bf::vector<Chars, Chars, Chars, Chars, Chars, double, Chars>
const &)>
419 boost::function<void(bf::vector<Chars, Chars, Chars, Chars, Chars,
double,
420 Chars, Chars, Chars,
double>)>
422 boost::function<void(
423 bf::vector<Chars, Chars, Chars, Chars, Chars, double, Chars>
const &)>
425 boost::function<void(bf::vector<Chars, Chars, Chars, Chars, Chars,
double,
426 Chars, Chars, Chars,
double>)>
428 boost::function<void(
429 bf::vector<Chars, Chars, Chars, Chars, Chars, double, Chars>)>
431 boost::function<void(bf::vector<Chars, Chars, Chars, Chars,
double, Chars,
432 Chars, Chars,
double>
const &)>
434 boost::function<void(
435 bf::vector<Chars, Chars, Chars, Chars, Chars, double, Chars>
const &)>
437 boost::function<void(bf::vector<Chars, Chars, Chars, Chars, Chars, Chars,
438 Chars,
double>
const &)>
440 boost::function<void(
441 bf::vector<Chars, Chars, Chars, Chars, Chars, Chars, Chars>
const &)>
444 : base_grammar(start),
457 using namespace boost::spirit;
458 using namespace boost::spirit::qi;
459 character = lexeme[alnum |
'_' |
'-' |
'.'];
460 title = lexeme[character >> *(blank | character)];
461 word = lexeme[+character];
462 name = lexeme[lit(
"NAME") >> *blank >> title >> +space][setName];
463 row = lexeme[*blank >> character >> +blank >> word >> *blank][addRow];
464 rhs_single = lexeme[*blank >> word >> +blank >> word >> +blank >> double_ >>
467 lexeme[(*blank >> word >> +blank >> word >> +blank >> double_ >>
468 +blank >> word >> +blank >> double_)[rhsDouble] >>
470 range_single = lexeme[*blank >> word >> +blank >> word >> +blank >>
471 double_ >> *blank][rangeSingle];
473 lexeme[(*blank >> word >> +blank >> word >> +blank >> double_ >>
474 +blank >> word >> +blank >> double_)[rangeDouble] >>
476 col_single = lexeme[*blank >> word >> +blank >> word >> +blank >> double_ >>
479 lexeme[*blank >> (word >> +blank >> word >> +blank >> double_ >>
480 +blank >> word >> +blank >> double_)[colDouble] >>
482 quad_l = lexeme[*blank >> word >> +blank >> word >> +blank >> double_ >>
483 *blank][addQuadTerm];
484 bound = lexeme[(*blank >> word >> +blank >> word >> +blank >> word >>
485 +blank >> double_)[addBound] >>
487 bound_fr = lexeme[*blank >> word >> +blank >> word >> +blank >> word >>
488 *blank][addFreeBound];
489 rows = lexeme[lit(
"ROWS") >> *blank >> eol >> +(
row >> eol)];
490 rhs = lexeme[lit(
"RHS") >> *blank >> eol >>
491 +((rhs_double | rhs_single) >> eol)];
492 cols = lexeme[lit(
"COLUMNS") >> *blank >> eol >>
493 +((col_double | col_single) >> eol)];
494 quad = lexeme[lit(
"QUADOBJ") >> *blank >> eol >> +(quad_l >> eol)];
495 bounds = lexeme[lit(
"BOUNDS") >> +space >> *((
bound | bound_fr) >> eol)];
496 ranges = lexeme[lit(
"RANGES") >> +space >>
497 *((range_double | range_single) >> eol)];
498 end = lexeme[lit(
"ENDATA") >> *space];
500 lexeme[
name >>
rows >>
cols >> rhs >> -ranges >> bounds >> quad >>
end];
503 qi::rule<boost::spirit::basic_istream_iterator<char>, char()>
character;
504 qi::rule<boost::spirit::basic_istream_iterator<char>,
Chars()>
word, title;
505 qi::rule<boost::spirit::basic_istream_iterator<char>>
row,
end, col_single,
506 col_double, rhs_single, rhs_double, range_single, range_double, ranges,
510 QP QPSParser::Parse() {
512 std::fstream
stream(fileName_.c_str());
513 stream.unsetf(std::ios::skipws);
514 boost::spirit::basic_istream_iterator<char> begin(
stream);
515 boost::spirit::basic_istream_iterator<char>
last;
qi::rule< boost::spirit::basic_istream_iterator< char > > start
constexpr int last(int, int result)
void addFreeBound(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, Chars, Chars > const &vars)
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, double, Chars > const &)> addQuadTerm
void addRow(boost::fusion::vector< Chars, char, Chars, Chars, Chars > const &vars)
qi::grammar< boost::spirit::basic_istream_iterator< char > > base_grammar
void addBound(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, Chars, Chars, double > const &vars)
std::unordered_map< Key, Matrix11 > coefficient_v
static double range2(const Camera &camera, const Camera2 &camera2)
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, double, Chars > const &)> rhsSingle
double bound(double a, double min, double max)
void addQuadTerm(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, double, Chars > const &vars)
void addRangeDouble(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, double, Chars, Chars, Chars, double > const &vars)
Exception thrown if there is an error parsing a QPS file.
GaussianFactorGraph cost
Quadratic cost factors.
const Symbol key1('v', 1)
unsigned int numVariables
MPSGrammar(QPSVisitor *rqp)
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, Chars, Chars, double > const &)> addBound
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, double, Chars, Chars, Chars, double > const &)> colDouble
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, double, Chars >)> colSingle
static string fromChars(const FusionVector &vars)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
void addRHSDouble(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, double, Chars, Chars, Chars, double > const &vars)
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, double, Chars, Chars, Chars, double >)> rhsDouble
std::unordered_map< std::string, double > b
std::unordered_map< std::string, double > ranges
std::unordered_map< Key, double > fx
Factor graphs of a Quadratic Programming problem.
void addRHS(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, double, Chars > const &vars)
InequalityFactorGraph inequalities
linear inequality constraints: cI(x) <= 0
qi::rule< boost::spirit::basic_istream_iterator< char >, Chars()> word
void addColumnDouble(boost::fusion::vector< Chars, Chars, Chars, Chars, double, Chars, Chars, Chars, double > const &vars)
std::unordered_map< std::string, Key > varname_to_key
EqualityFactorGraph equalities
linear equality constraints: cE(x) = 0
static double range1(const Camera &camera, const Pose3 &pose)
void addRangeSingle(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, double, Chars > const &vars)
std::vector< char > Chars
std::unordered_map< Key, std::unordered_map< Key, Matrix11 > > H
A Gaussian factor using the canonical parameters (information form)
qi::rule< boost::spirit::basic_istream_iterator< char >, char()> character
Annotation for function names.
std::unordered_map< Key, double > lo
std::unordered_map< std::string, coefficient_v > constraint_v
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, Chars, Chars > const &)> addFreeBound
void addColumn(boost::fusion::vector< Chars, Chars, Chars, Chars, Chars, double, Chars > const &vars)
def parse(input_path, output_path, quiet=False, generate_xml_flag=True)
std::unordered_map< Key, double > up
std::uint64_t Key
Integer nonlinear key type.
std::unordered_map< Key, Vector1 > g
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, double, Chars, Chars, Chars, double >)> rangeDouble
std::unordered_map< std::string, constraint_v * > row_to_constraint_v
std::vector< char > Chars
void setName(boost::fusion::vector< Chars, Chars, Chars > const &name)
boost::function< void(bf::vector< Chars, Chars, Chars, Chars, Chars, double, Chars > const &)> rangeSingle