@@ -184,4 +184,98 @@ template <typename A1, typename A2, typename T>
184184struct traits <RangeFactorWithTransform<A1, A2, T> >
185185 : public Testable<RangeFactorWithTransform<A1, A2, T> > {};
186186
187+
188+ /* *
189+ * Binary factor for a range measurement, with a transform applied
190+ * @ingroup sam
191+ */
192+ template <typename A1, typename A2 = A1,
193+ typename T = typename Range<A1, A2>::result_type>
194+ class RangeFactorWithTransformBias : public ExpressionFactorN <T, A1, A2, T> {
195+ private:
196+ typedef RangeFactorWithTransformBias<A1, A2> This;
197+ typedef ExpressionFactorN<T, A1, A2, T> Base;
198+
199+ A1 body_T_sensor_; // /< The pose of the sensor in the body frame
200+
201+ public:
202+ // // Default constructor
203+ RangeFactorWithTransformBias () {}
204+
205+ RangeFactorWithTransformBias (Key key1, Key key2, Key key3, T measured,
206+ const SharedNoiseModel& model,
207+ const A1& body_T_sensor)
208+ : Base({key1, key2, key3}, model, measured), body_T_sensor_(body_T_sensor) {
209+ this ->initialize (expression ({key1, key2, key3}));
210+ }
211+
212+ ~RangeFactorWithTransformBias () override {}
213+
214+ // / @return a deep copy of this factor
215+ gtsam::NonlinearFactor::shared_ptr clone () const override {
216+ return std::static_pointer_cast<gtsam::NonlinearFactor>(
217+ gtsam::NonlinearFactor::shared_ptr (new This (*this )));
218+ }
219+
220+ // Return measurement expression
221+ Expression<T> expression (const typename Base::ArrayNKeys& keys) const override {
222+ Expression<A1> body_T_sensor__ (body_T_sensor_);
223+ Expression<A1> nav_T_body_ (keys[0 ]);
224+ Expression<A1> nav_T_sensor_ (traits<A1>::Compose, nav_T_body_,
225+ body_T_sensor__);
226+ Expression<A2> a2_ (keys[1 ]);
227+ Expression<T> bias_ (keys[2 ]);
228+ Expression<T> range_ (Range<A1, A2>(), nav_T_sensor_, a2_);
229+ return range_ + bias_;
230+ }
231+
232+ Vector evaluateError (const A1& a1, const A2& a2, const T& bias,
233+ OptionalMatrixType H1 = OptionalNone, OptionalMatrixType H2 = OptionalNone, OptionalMatrixType H3 = OptionalNone) const {
234+ std::vector<Matrix> Hs (3 );
235+ const auto &keys = Factor::keys ();
236+ Vector error = Base::unwhitenedError (
237+ {{keys[0 ], genericValue (a1)}, {keys[1 ], genericValue (a2)},
238+ {keys[2 ], genericValue (bias)}},
239+ Hs);
240+ if (H1) *H1 = Hs[0 ];
241+ if (H2) *H2 = Hs[1 ];
242+ if (H3) *H3 = Hs[2 ];
243+ return error;
244+ }
245+
246+ // An evaluateError overload to accept matrices (Matrix&) and pass it to the
247+ // OptionalMatrixType evaluateError overload
248+ Vector evaluateError (const A1& a1, const A2& a2, const T& bias, Matrix& H1, Matrix& H2, Matrix& H3) const {
249+ return evaluateError (a1, a2, bias, &H1, &H2, &H3);
250+ }
251+
252+ /* * print contents */
253+ void print (const std::string& s = " " ,
254+ const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
255+ std::cout << s << " RangeFactorWithTransformBias" << std::endl;
256+ this ->body_T_sensor_ .print (" sensor pose in body frame: " );
257+ Base::print (s, keyFormatter);
258+ }
259+
260+ private:
261+ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
262+ friend class boost ::serialization::access;
263+ /* * Serialization function */
264+ template <typename ARCHIVE>
265+ void serialize (ARCHIVE& ar, const unsigned int /* version*/ ) {
266+ // **IMPORTANT** We need to (de)serialize parameters before the base class,
267+ // since it calls expression() and we need all parameters ready at that
268+ // point.
269+ ar& BOOST_SERIALIZATION_NVP (body_T_sensor_);
270+ ar& boost::serialization::make_nvp (
271+ " Base" , boost::serialization::base_object<Base>(*this ));
272+ }
273+ #endif
274+ }; // \ RangeFactorWithTransform
275+
276+ // / traits
277+ template <typename A1, typename A2, typename T>
278+ struct traits <RangeFactorWithTransformBias<A1, A2, T> >
279+ : public Testable<RangeFactorWithTransform<A1, A2, T> > {};
280+
187281} // \ namespace gtsam
0 commit comments