24 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 25 #include <boost/serialization/nvp.hpp> 34 template <
typename A1,
typename A2>
40 template <
typename A1,
typename A2>
49 template <
typename A1,
typename A2,
80 const A1&
a1,
const A2&
a2,
91 if (H1) *H1 << HB1, HR1;
92 if (H2) *H2 << HB2, HR2;
151 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 152 template <
class ARCHIVE>
154 void serialize(ARCHIVE& ar,
const unsigned int ) {
155 ar& boost::serialization::make_nvp(
"bearing", bearing_);
156 ar& boost::serialization::make_nvp(
"range", range_);
159 friend class boost::serialization::access;
173 template <
typename A1,
typename A2>
182 template <
class A1,
typename A2,
class RT>
186 const A1&
a1,
const A2&
a2,
189 return a1.bearing(a2, H1, H2);
196 template <
class A1,
typename A2,
class RT>
200 const A1&
a1,
const A2&
a2,
203 return a1.range(a2, H1, H2);
static B MeasureBearing(const A1 &a1, const A2 &a2)
Predict bearing.
Concept check for values that can be used in unit tests.
RT operator()(const A1 &a1, const A2 &a2, OptionalJacobian< traits< RT >::dimension, traits< A1 >::dimension > H1={}, OptionalJacobian< traits< RT >::dimension, traits< A2 >::dimension > H2={})
std::string serialize(const T &input)
serializes to a string
Rot2 R(Rot2::fromAngle(0.1))
void print(const std::string &str="") const
OptionalJacobian< dimension, dimension > ChartJacobian
static BearingRange Measure(const A1 &a1, const A2 &a2, OptionalJacobian< dimension, traits< A1 >::dimension > H1={}, OptionalJacobian< dimension, traits< A2 >::dimension > H2={})
Prediction function that stacks measurements.
Eigen::Matrix< double, dimension, 1 > TangentVector
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
TangentVector localCoordinates(const BearingRange &other) const
Compute the coordinates in the tangent space.
Base class and basic functions for Manifold types.
Array< int, Dynamic, 1 > v
RT operator()(const A1 &a1, const A2 &a2, OptionalJacobian< traits< RT >::dimension, traits< A1 >::dimension > H1={}, OptionalJacobian< traits< RT >::dimension, traits< A2 >::dimension > H2={})
Array< double, 1, 3 > e(1./3., 0.5, 2.)
BearingRange retract(const TangentVector &xi) const
Retract delta to manifold.
bool equals(const BearingRange< A1, A2 > &m2, double tol=1e-8) const
BearingRange(const B &b, const R &r)
const R & range() const
Return range measurement.
Special class for optional Jacobian arguments.
The matrix class, also used for vectors and row-vectors.
static R MeasureRange(const A1 &a1, const A2 &a2)
Predict range.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
const B & bearing() const
Return bearing measurement.