@@ -31,7 +31,7 @@ namespace detail {
3131/* * Convenience base class to add aliases `X1`, `X2`, ..., `X6` -> ValueType<N>.
3232 * Usage example:
3333 * ```
34- * class MyFactor : public NoiseModelFactorN <Pose3, Point3>,
34+ * class MyFactor : public NoiseModelFactorT <Pose3, Point3>,
3535 * public NoiseModelFactorAliases<Pose3, Point3> {
3636 * // class implementation ...
3737 * };
@@ -94,9 +94,9 @@ struct NoiseModelFactorAliases<T1, T2, T3, T4, T5, T6, TExtra...> {
9494 * between a Pose3 and Point3 could be implemented like so:
9595 *
9696 * ~~~~~~~~~~~~~~~~~~~~{.cpp}
97- * class MyFactor : public NoiseModelFactorN< Pose3, Point3> {
97+ * class MyFactor : public NoiseModelFactorT<Vector, Pose3, Point3> {
9898 * public:
99- * using Base = NoiseModelFactorN <Pose3, Point3>;
99+ * using Base = NoiseModelFactorT <Pose3, Point3>;
100100 *
101101 * MyFactor(Key pose_key, Key point_key, const SharedNoiseModel& noiseModel)
102102 * : Base(noiseModel, pose_key, point_key) {}
@@ -121,7 +121,7 @@ struct NoiseModelFactorAliases<T1, T2, T3, T4, T5, T6, TExtra...> {
121121 * return Vector1(error);
122122 * }
123123 * };
124- *
124+ *
125125 * // Unit Test
126126 * TEST(NonlinearFactor, MyFactor) {
127127 * MyFactor f(X(1), X(2), noiseModel::Unit::Create(1));
@@ -138,8 +138,8 @@ struct NoiseModelFactorAliases<T1, T2, T3, T4, T5, T6, TExtra...> {
138138 * are typically more general than just vectors, e.g., Rot3 or Pose3, which are
139139 * objects in non-linear manifolds (Lie groups).
140140 */
141- template <class ... ValueTypes>
142- class NoiseModelFactorN
141+ template <class OutputVec , class ... ValueTypes>
142+ class NoiseModelFactorT
143143 : public NoiseModelFactor,
144144 public detail::NoiseModelFactorAliases<ValueTypes...> {
145145 public:
@@ -150,7 +150,7 @@ class NoiseModelFactorN
150150
151151protected:
152152 using Base = NoiseModelFactor;
153- using This = NoiseModelFactorN< ValueTypes...>;
153+ using This = NoiseModelFactorT<OutputVec, ValueTypes...>;
154154
155155 // / @name SFINAE aliases
156156 // / @{
@@ -212,88 +212,88 @@ class NoiseModelFactorN
212212 using MatrixTypeT = Matrix;
213213
214214 public:
215- /* *
216- * The type of the I'th template param can be obtained as ValueType<I>.
217- * I is 1-indexed for backwards compatibility/consistency! So for example,
218- * ```
219- * using Factor = NoiseModelFactorN< Pose3, Point3>;
220- * Factor::ValueType<1> // Pose3
221- * Factor::ValueType<2> // Point3
222- * // Factor::ValueType<0> // ERROR! Will not compile.
223- * // Factor::ValueType<3> // ERROR! Will not compile.
224- * ```
225- *
226- * You can also use the shortcuts `X1`, ..., `X6` which are the same as
227- * `ValueType<1>`, ..., `ValueType<6>` respectively (see
228- * detail::NoiseModelFactorAliases).
229- *
230- * Note that, if your class is templated AND you want to use `ValueType<1>`
231- * inside your class, due to dependent types you need the `template` keyword:
232- * `typename MyFactor<T>::template ValueType<1>`.
233- */
234- template <int I, typename = IndexIsValid<I>>
235- using ValueType =
236- typename std::tuple_element<I - 1 , std::tuple<ValueTypes...>>::type;
215+ /* *
216+ * The type of the I'th template param can be obtained as ValueType<I>.
217+ * I is 1-indexed for backwards compatibility/consistency! So for example,
218+ * ```
219+ * using Factor = NoiseModelFactorT<Vector, Pose3, Point3>;
220+ * Factor::ValueType<1> // Pose3
221+ * Factor::ValueType<2> // Point3
222+ * // Factor::ValueType<0> // ERROR! Will not compile.
223+ * // Factor::ValueType<3> // ERROR! Will not compile.
224+ * ```
225+ *
226+ * You can also use the shortcuts `X1`, ..., `X6` which are the same as
227+ * `ValueType<1>`, ..., `ValueType<6>` respectively (see
228+ * detail::NoiseModelFactorAliases).
229+ *
230+ * Note that, if your class is templated AND you want to use `ValueType<1>`
231+ * inside your class, due to dependent types you need the `template` keyword:
232+ * `typename MyFactor<T>::template ValueType<1>`.
233+ */
234+ template <int I, typename = IndexIsValid<I>>
235+ using ValueType =
236+ typename std::tuple_element<I - 1 , std::tuple<ValueTypes...>>::type;
237237
238- public:
239-
240- // / @name Constructors
241- // / @{
242-
243- // / Default Constructor for I/O
244- NoiseModelFactorN () {}
245-
246- /* *
247- * Constructor.
248- * Example usage: NoiseModelFactorN(noise, key1, key2, ..., keyN)
249- * @param noiseModel Shared pointer to noise model.
250- * @param keys Keys for the variables in this factor, passed in as separate
251- * arguments.
252- */
253- NoiseModelFactorN ( const SharedNoiseModel& noiseModel,
254- KeyType<ValueTypes> ... keys)
255- : Base(noiseModel, std::array<Key, N>{keys...}) {}
256-
257- /* *
258- * Constructor.
259- * Example usage: `NoiseModelFactorN (noise, {key1, key2, ..., keyN})`
260- * Example usage: `NoiseModelFactorN(noise, keys)` where keys is a vector<Key>
261- * @param noiseModel Shared pointer to noise model.
262- * @param keys A container of keys for the variables in this factor.
263- */
264- template <typename CONTAINER = std::initializer_list<Key>,
265- typename = IsContainerOfKeys<CONTAINER>>
266- NoiseModelFactorN (const SharedNoiseModel& noiseModel, CONTAINER keys)
267- : Base(noiseModel, keys) {
268- if (keys.size () != N) {
269- throw std::invalid_argument (
270- " NoiseModelFactorN : wrong number of keys given" );
271- }
272- }
238+ public:
239+ // / @name Constructors
240+ // / @{
241+
242+ // / Default Constructor for I/O
243+ NoiseModelFactorT () {}
244+
245+ /* *
246+ * Constructor.
247+ * Example usage: NoiseModelFactorT(noise, key1, key2, ..., keyN)
248+ * @param noiseModel Shared pointer to noise model.
249+ * @param keys Keys for the variables in this factor, passed in as separate
250+ * arguments.
251+ */
252+ NoiseModelFactorT ( const SharedNoiseModel& noiseModel,
253+ KeyType<ValueTypes>... keys)
254+ : Base(noiseModel, std::array<Key, N>{keys ...}) {}
255+
256+ /* *
257+ * Constructor.
258+ * Example usage: `NoiseModelFactorT(noise, {key1, key2, ..., keyN})`
259+ * Example usage: `NoiseModelFactorT (noise, keys)` where keys is a
260+ * vector<Key>
261+ * @param noiseModel Shared pointer to noise model.
262+ * @param keys A container of keys for the variables in this factor.
263+ */
264+ template <typename CONTAINER = std::initializer_list<Key>,
265+ typename = IsContainerOfKeys<CONTAINER>>
266+ NoiseModelFactorT (const SharedNoiseModel& noiseModel, CONTAINER keys)
267+ : Base(noiseModel, keys) {
268+ if (keys.size () != N) {
269+ throw std::invalid_argument (
270+ " NoiseModelFactorT : wrong number of keys given" );
271+ }
272+ }
273273
274274 // / @}
275275
276- ~NoiseModelFactorN () override {}
277-
278- /* * Returns a key. Usage: `key<I>()` returns the I'th key.
279- * I is 1-indexed for backwards compatibility/consistency! So for example,
280- * ```
281- * NoiseModelFactorN< Pose3, Point3> factor(noise, key1, key2);
282- * key<1>() // = key1
283- * key<2>() // = key2
284- * // key<0>() // ERROR! Will not compile
285- * // key<3>() // ERROR! Will not compile
286- * ```
287- *
288- * Note that, if your class is templated AND you are trying to call `key<1>`
289- * inside your class, due to dependent types you need the `template` keyword:
290- * `this->key1()`.
291- */
292- template <int I = 1 >
293- inline Key key () const {
294- static_assert (I <= N, " Index out of bounds" );
295- return keys_[I - 1 ];
296- }
276+ ~NoiseModelFactorT () override {}
277+
278+ /* * Returns a key. Usage: `key<I>()` returns the I'th key.
279+ * I is 1-indexed for backwards compatibility/consistency! So for example,
280+ * ```
281+ * NoiseModelFactorT<Vector, Pose3, Point3> factor(noise, key1, key2);
282+ * key<1>() // = key1
283+ * key<2>() // = key2
284+ * // key<0>() // ERROR! Will not compile
285+ * // key<3>() // ERROR! Will not compile
286+ * ```
287+ *
288+ * Note that, if your class is templated AND you are trying to call `key<1>`
289+ * inside your class, due to dependent types you need the `template` keyword:
290+ * `this->key1()`.
291+ */
292+ template <int I = 1 >
293+ inline Key key () const {
294+ static_assert (I <= N, " Index out of bounds" );
295+ return keys_[I - 1 ];
296+ }
297297
298298 // / @name NoiseModelFactor methods
299299 // / @{
@@ -347,15 +347,15 @@ class NoiseModelFactorN
347347 * as separate arguments.
348348 * @param[out] H The Jacobian with respect to each variable (optional).
349349 */
350- virtual Vector evaluateError (const ValueTypes&... x,
350+ virtual OutputVec evaluateError (const ValueTypes&... x,
351351 OptionalMatrixTypeT<ValueTypes>... H) const = 0;
352352
353353 /* * If all the optional arguments are matrices then redirect the call to
354354 * the one which takes pointers.
355355 * To get access to this version of the function from derived classes
356356 * one will need to use the "using" keyword and specify that like this:
357357 * public:
358- * using NoiseModelFactorN <list the value types here>::evaluateError;
358+ * using NoiseModelFactorT <list the value types here>::evaluateError;
359359 */
360360 Vector evaluateError (const ValueTypes&... x,
361361 MatrixTypeT<ValueTypes>&... H) const {
@@ -406,7 +406,7 @@ class NoiseModelFactorN
406406 /* * Pack expansion with index_sequence template pattern, used to index into
407407 * `keys_` and `H`.
408408 *
409- * Example: For `NoiseModelFactorN <Pose3, Point3>`, the call would look like:
409+ * Example: For `NoiseModelFactorT <Pose3, Point3>`, the call would look like:
410410 * `const Vector error = unwhitenedError(0, 1, values, H);`
411411 */
412412 template <std::size_t ... Indices>
@@ -471,7 +471,10 @@ class NoiseModelFactorN
471471
472472 // / @}
473473
474- }; // \class NoiseModelFactorN
474+ }; // \class NoiseModelFactorT
475+
476+ template <class ... ValueTypes>
477+ using NoiseModelFactorN = NoiseModelFactorT<Vector, ValueTypes...>;
475478
476479#define NoiseModelFactor1 NoiseModelFactorN
477480#define NoiseModelFactor2 NoiseModelFactorN
0 commit comments