Skip to content

Commit f77af12

Browse files
authored
Merge pull request #774 from borglab/fix/nonlinearequality
2 parents b582b5b + a55e474 commit f77af12

File tree

1 file changed

+30
-23
lines changed

1 file changed

+30
-23
lines changed

gtsam/nonlinear/NonlinearEquality.h

Lines changed: 30 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -59,10 +59,10 @@ class NonlinearEquality: public NoiseModelFactor1<VALUE> {
5959
double error_gain_;
6060

6161
// typedef to this class
62-
typedef NonlinearEquality<VALUE> This;
62+
using This = NonlinearEquality<VALUE>;
6363

6464
// typedef to base class
65-
typedef NoiseModelFactor1<VALUE> Base;
65+
using Base = NoiseModelFactor1<VALUE>;
6666

6767
public:
6868

@@ -73,7 +73,7 @@ class NonlinearEquality: public NoiseModelFactor1<VALUE> {
7373
CompareFunction compare_;
7474
// bool (*compare_)(const T& a, const T& b);
7575

76-
/** default constructor - only for serialization */
76+
/// Default constructor - only for serialization
7777
NonlinearEquality() {
7878
}
7979

@@ -109,9 +109,11 @@ class NonlinearEquality: public NoiseModelFactor1<VALUE> {
109109

110110
void print(const std::string& s = "",
111111
const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
112-
std::cout << s << "Constraint: on [" << keyFormatter(this->key()) << "]\n";
112+
std::cout << (s.empty() ? s : s + " ") << "Constraint: on ["
113+
<< keyFormatter(this->key()) << "]\n";
113114
traits<VALUE>::Print(feasible_, "Feasible Point:\n");
114-
std::cout << "Variable Dimension: " << traits<T>::GetDimension(feasible_) << std::endl;
115+
std::cout << "Variable Dimension: " << traits<T>::GetDimension(feasible_)
116+
<< std::endl;
115117
}
116118

117119
/** Check if two factors are equal */
@@ -125,7 +127,7 @@ class NonlinearEquality: public NoiseModelFactor1<VALUE> {
125127
/// @name Standard Interface
126128
/// @{
127129

128-
/** actual error function calculation */
130+
/// Actual error function calculation
129131
double error(const Values& c) const override {
130132
const T& xj = c.at<T>(this->key());
131133
Vector e = this->unwhitenedError(c);
@@ -136,7 +138,7 @@ class NonlinearEquality: public NoiseModelFactor1<VALUE> {
136138
}
137139
}
138140

139-
/** error function */
141+
/// Error function
140142
Vector evaluateError(const T& xj,
141143
boost::optional<Matrix&> H = boost::none) const override {
142144
const size_t nj = traits<T>::GetDimension(feasible_);
@@ -157,7 +159,7 @@ class NonlinearEquality: public NoiseModelFactor1<VALUE> {
157159
}
158160
}
159161

160-
// Linearize is over-written, because base linearization tries to whiten
162+
/// Linearize is over-written, because base linearization tries to whiten
161163
GaussianFactor::shared_ptr linearize(const Values& x) const override {
162164
const T& xj = x.at<T>(this->key());
163165
Matrix A;
@@ -179,7 +181,7 @@ class NonlinearEquality: public NoiseModelFactor1<VALUE> {
179181

180182
private:
181183

182-
/** Serialization function */
184+
/// Serialization function
183185
friend class boost::serialization::access;
184186
template<class ARCHIVE>
185187
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
@@ -212,7 +214,7 @@ class NonlinearEquality1: public NoiseModelFactor1<VALUE> {
212214
typedef NoiseModelFactor1<VALUE> Base;
213215
typedef NonlinearEquality1<VALUE> This;
214216

215-
/** default constructor to allow for serialization */
217+
/// Default constructor to allow for serialization
216218
NonlinearEquality1() {
217219
}
218220

@@ -231,12 +233,12 @@ class NonlinearEquality1: public NoiseModelFactor1<VALUE> {
231233
* @param value feasible value that values(key) shouild be equal to
232234
* @param key the key for the unknown variable to be constrained
233235
* @param mu a parameter which really turns this into a strong prior
234-
*
235236
*/
236-
NonlinearEquality1(const X& value, Key key, double mu = 1000.0) :
237-
Base( noiseModel::Constrained::All(traits<X>::GetDimension(value),
238-
std::abs(mu)), key), value_(value) {
239-
}
237+
NonlinearEquality1(const X& value, Key key, double mu = 1000.0)
238+
: Base(noiseModel::Constrained::All(traits<X>::GetDimension(value),
239+
std::abs(mu)),
240+
key),
241+
value_(value) {}
240242

241243
~NonlinearEquality1() override {
242244
}
@@ -247,7 +249,7 @@ class NonlinearEquality1: public NoiseModelFactor1<VALUE> {
247249
gtsam::NonlinearFactor::shared_ptr(new This(*this)));
248250
}
249251

250-
/** g(x) with optional derivative */
252+
/// g(x) with optional derivative
251253
Vector evaluateError(const X& x1,
252254
boost::optional<Matrix&> H = boost::none) const override {
253255
if (H)
@@ -256,7 +258,7 @@ class NonlinearEquality1: public NoiseModelFactor1<VALUE> {
256258
return traits<X>::Local(value_,x1);
257259
}
258260

259-
/** Print */
261+
/// Print
260262
void print(const std::string& s = "",
261263
const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
262264
std::cout << s << ": NonlinearEquality1(" << keyFormatter(this->key())
@@ -269,7 +271,7 @@ class NonlinearEquality1: public NoiseModelFactor1<VALUE> {
269271

270272
private:
271273

272-
/** Serialization function */
274+
/// Serialization function
273275
friend class boost::serialization::access;
274276
template<class ARCHIVE>
275277
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
@@ -287,7 +289,7 @@ struct traits<NonlinearEquality1<VALUE> > : Testable<NonlinearEquality1<VALUE> >
287289

288290
/* ************************************************************************* */
289291
/**
290-
* Simple binary equality constraint - this constraint forces two factors to
292+
* Simple binary equality constraint - this constraint forces two variables to
291293
* be the same.
292294
*/
293295
template<class VALUE>
@@ -301,15 +303,20 @@ class NonlinearEquality2: public NoiseModelFactor2<VALUE, VALUE> {
301303

302304
GTSAM_CONCEPT_MANIFOLD_TYPE(X)
303305

304-
/** default constructor to allow for serialization */
306+
/// Default constructor to allow for serialization
305307
NonlinearEquality2() {
306308
}
307309

308310
public:
309311

310312
typedef boost::shared_ptr<NonlinearEquality2<VALUE> > shared_ptr;
311313

312-
///TODO: comment
314+
/**
315+
* Constructor
316+
* @param key1 the key for the first unknown variable to be constrained
317+
* @param key2 the key for the second unknown variable to be constrained
318+
* @param mu a parameter which really turns this into a strong prior
319+
*/
313320
NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) :
314321
Base(noiseModel::Constrained::All(traits<X>::dimension, std::abs(mu)), key1, key2) {
315322
}
@@ -322,7 +329,7 @@ class NonlinearEquality2: public NoiseModelFactor2<VALUE, VALUE> {
322329
gtsam::NonlinearFactor::shared_ptr(new This(*this)));
323330
}
324331

325-
/** g(x) with optional derivative2 */
332+
/// g(x) with optional derivative2
326333
Vector evaluateError(const X& x1, const X& x2, boost::optional<Matrix&> H1 =
327334
boost::none, boost::optional<Matrix&> H2 = boost::none) const override {
328335
static const size_t p = traits<X>::dimension;
@@ -335,7 +342,7 @@ class NonlinearEquality2: public NoiseModelFactor2<VALUE, VALUE> {
335342

336343
private:
337344

338-
/** Serialization function */
345+
/// Serialization function
339346
friend class boost::serialization::access;
340347
template<class ARCHIVE>
341348
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {

0 commit comments

Comments
 (0)