24 #include <gtsam/config.h> 40 direction.
p_ =
normalize(point, H ? &D_p_point : 0);
42 *H << direction.
basis().transpose() * D_p_point;
50 std::uniform_real_distribution<double>
uniform(-1.0, 1.0);
56 sqsum = x * x + y *
y;
58 const double mult = 2 *
sqrt(1 - sqsum);
59 return Unit3(x * mult, y * mult, 2 * sqsum - 1);
66 if ((mx <= my) && (mx <= mz)) {
67 return Point3(1.0, 0.0, 0.0);
68 }
else if ((my <= mx) && (my <= mz)) {
69 return Point3(0.0, 1.0, 0.0);
81 std::unique_lock<std::mutex> lock(B_mutex_);
84 const bool cachedBasis =
static_cast<bool>(B_);
85 const bool cachedJacobian =
static_cast<bool>(H_B_);
88 if (!cachedJacobian) {
92 Matrix33 H_B1_n, H_b1_B1, H_b2_n, H_b2_b1;
106 const Matrix32& H_n_p = B;
107 jacobian.block<3, 2>(0, 0) = H_b1_B1 * H_B1_n * H_n_p;
108 auto H_b1_p = jacobian.block<3, 2>(0, 0);
109 jacobian.block<3, 2>(3, 0) = H_b2_n * H_n_p + H_b2_b1 * H_b1_p;
112 H_B_.reset(jacobian);
151 os << pair.
p_ << endl;
157 cout << s <<
":" << p_ << endl;
161 Matrix3 Unit3::skew()
const {
176 Matrix13 H_dot_pn, H_dot_qn;
177 double d =
gtsam::dot(pn, qn, H_p ? &H_dot_pn :
nullptr, H_q ? &H_dot_qn :
nullptr);
180 (*H_p) << H_dot_pn * H_pn_p;
184 (*H_q) = H_dot_qn * H_qn_q;
195 *H_q = basis().transpose() * q.
basis();
209 Matrix23 Bt = basis(H_p ? &H_B_p :
nullptr).transpose();
214 const Matrix32& H_b1_p = H_B_p.block<3, 2>(0, 0);
215 const Matrix32& H_b2_p = H_B_p.block<3, 2>(3, 0);
218 const Matrix13 H_xi1_b1 = qn.transpose();
219 const Matrix13 H_xi2_b2 = qn.transpose();
222 const Matrix12 H_xi1_p = H_xi1_b1 * H_b1_p;
223 const Matrix12 H_xi2_p = H_xi2_b2 * H_b2_p;
224 *H_p << H_xi1_p, H_xi2_p;
229 const Matrix23 H_xi_qu = Bt;
230 *H_q = H_xi_qu * H_qn_q;
240 const double theta = xi.norm();
242 *H = (xi.transpose() /
theta) * H_xi_q;
250 const double theta = xi_hat.norm();
254 Matrix23 H_from_point;
256 const Unit3 exp_p_xi_hat = Unit3::FromPoint3(c * p_ + xi_hat,
257 H? &H_from_point :
nullptr);
260 (-p_ * xi_hat.transpose() + Matrix33::Identity()) * basis();
266 const Unit3 exp_p_xi_hat = Unit3::FromPoint3(c * p_ + xi_hat * st,
267 H? &H_from_point :
nullptr);
270 (p_ * -st * xi_hat.transpose() + st * Matrix33::Identity() +
271 xi_hat * ((c - st) /
std::pow(theta, 2)) * xi_hat.transpose()) * basis();
278 const double x = p_.dot(other.
p_);
282 const double x2 = x *
x;
283 const double z = 1 -
x2;
287 y = 1.0 - (x - 1.0) / 3.0;
294 return basis().transpose() * y * (other.
p_ - x * p_);
void print(const Matrix &A, const string &s, ostream &stream)
static Point3 CalculateBestAxis(const Point3 &n)
Vector3 p_
The location of the point on the unit sphere.
GTSAM_EXPORT const Matrix32 & basis(OptionalJacobian< 6, 2 > H=boost::none) const
double dot(const V1 &a, const V2 &b)
static std::uniform_real_distribution uniform(0.0, 1.0)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
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
Matrix< SCALARB, Dynamic, Dynamic > B
std::ostream & operator<<(std::ostream &os, const Unit3 &pair)
static void normalize(Signature::Row &row)
Represents a 3D point on a unit sphere.
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Point3 cross(const Point3 &p, const Point3 &q, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2)
cross product
static const Point3 point3(0.08, 0.08, 0.0)
EIGEN_DEVICE_FUNC const Scalar & q
GTSAM_EXPORT Point3 point3(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Point3.
EIGEN_DEVICE_FUNC const AcosReturnType acos() const
Matrix3 skewSymmetric(double wx, double wy, double wz)
ofstream os("timeSchurFactors.csv")
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Jet< T, N > pow(const Jet< T, N > &f, double g)
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 x