Go to the documentation of this file.
24 #include <gtsam/config.h>
36 Unit3::Unit3(
const Vector3&
p) : p_(
p.normalized()) {}
50 *
H << direction.
basis().transpose() * D_p_point;
58 std::uniform_real_distribution<double>
uniform(-1.0, 1.0);
64 sqsum =
x *
x +
y *
y;
66 const double mult = 2 *
sqrt(1 - sqsum);
67 return Unit3(
x * mult,
y * mult, 2 * sqsum - 1);
74 if ((mx <= my) && (mx <= mz)) {
75 return Point3(1.0, 0.0, 0.0);
76 }
else if ((my <= mx) && (my <= mz)) {
77 return Point3(0.0, 1.0, 0.0);
89 std::unique_lock<std::mutex> lock(B_mutex_);
92 const bool cachedBasis =
static_cast<bool>(
B_);
93 const bool cachedJacobian =
static_cast<bool>(
H_B_);
96 if (!cachedJacobian) {
100 Matrix33 H_B1_n, H_b1_B1, H_b2_n, H_b2_b1;
114 const Matrix32& H_n_p =
B;
115 jacobian.block<3, 2>(0, 0) = H_b1_B1 * H_B1_n * H_n_p;
116 auto H_b1_p = jacobian.block<3, 2>(0, 0);
117 jacobian.block<3, 2>(3, 0) = H_b2_n * H_n_p + H_b2_b1 * H_b1_p;
159 os << pair.
p_ << endl;
165 cout <<
s <<
":" <<
p_ << endl;
181 const Point3 qn =
q.point3(H_q ? &H_qn_q :
nullptr);
184 Matrix13 H_dot_pn, H_dot_qn;
185 double d =
gtsam::dot(pn, qn, H_p ? &H_dot_pn :
nullptr, H_q ? &H_dot_qn :
nullptr);
188 (*H_p) << H_dot_pn * H_pn_p;
192 (*H_q) = H_dot_qn * H_qn_q;
203 *H_q =
basis().transpose() *
q.basis();
213 const Point3 qn =
q.point3(H_q ? &H_qn_q :
nullptr);
217 Matrix23 Bt =
basis(H_p ? &H_B_p :
nullptr).transpose();
222 const Matrix32& H_b1_p = H_B_p.block<3, 2>(0, 0);
223 const Matrix32& H_b2_p = H_B_p.block<3, 2>(3, 0);
226 const Matrix13 H_xi1_b1 = qn.transpose();
227 const Matrix13 H_xi2_b2 = qn.transpose();
230 const Matrix12 H_xi1_p = H_xi1_b1 * H_b1_p;
231 const Matrix12 H_xi2_p = H_xi2_b2 * H_b2_p;
232 *H_p << H_xi1_p, H_xi2_p;
237 const Matrix23 H_xi_qu = Bt;
238 *H_q = H_xi_qu * H_qn_q;
248 const double theta =
xi.norm();
250 *
H = (
xi.transpose() / theta) * H_xi_q;
258 const double theta = xi_hat.norm();
262 Matrix23 H_from_point;
265 H? &H_from_point :
nullptr);
268 (-
p_ * xi_hat.transpose() + Matrix33::Identity()) *
basis();
273 const double st =
std::sin(theta) / theta;
275 H? &H_from_point :
nullptr);
278 (
p_ * -st * xi_hat.transpose() + st * Matrix33::Identity() +
279 xi_hat * ((
c - st) /
std::pow(theta, 2)) * xi_hat.transpose()) *
basis();
290 const double x2 =
x *
x;
291 const double z = 1 -
x2;
295 y = 1.0 - (
x - 1.0) / 3.0;
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, opt_B > B
static const double d[K][N]
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Jet< T, N > sin(const Jet< T, N > &f)
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
Point3 point3(OptionalJacobian< 3, 2 > H={}) const
Return unit-norm Point3.
static std::uniform_real_distribution uniform(0.0, 1.0)
std::optional< Matrix62 > H_B_
Cached basis derivative.
std::optional< Matrix32 > B_
Cached basis.
Vector2 error(const Unit3 &q, OptionalJacobian< 2, 2 > H_q={}) const
ofstream os("timeSchurFactors.csv")
Matrix3 skewSymmetric(double wx, double wy, double wz)
Jet< T, N > acos(const Jet< T, N > &f)
Jet< T, N > cos(const Jet< T, N > &f)
Unit3()
Default constructor.
double dot(const Unit3 &q, OptionalJacobian< 1, 2 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
Return dot product with q.
static void normalize(Signature::Row &row)
Point3 cross(const Point3 &p, const Point3 &q, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2)
cross product
double distance(const Unit3 &q, OptionalJacobian< 1, 2 > H={}) const
Distance between two directions.
EIGEN_DEVICE_FUNC const Scalar & q
double dot(const V1 &a, const V2 &b)
Jet< T, N > pow(const Jet< T, N > &f, double g)
Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H={}) const
The retract function.
static Point3 CalculateBestAxis(const Point3 &n)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Vector2 errorVector(const Unit3 &q, OptionalJacobian< 2, 2 > H_p={}, OptionalJacobian< 2, 2 > H_q={}) const
Matrix3 skew() const
Return skew-symmetric associated with 3D point on unit sphere.
Array< int, Dynamic, 1 > v
static Unit3 Random(std::mt19937 &rng)
const Matrix32 & basis(OptionalJacobian< 6, 2 > H={}) const
Represents a 3D point on a unit sphere.
Vector3 unitVector(OptionalJacobian< 3, 2 > H={}) const
Return unit-norm Vector.
static Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H={})
Named constructor from Point3 with optional Jacobian.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Jet< T, N > sqrt(const Jet< T, N > &f)
void print(const std::string &s=std::string()) const
The print fuction.
Vector2 localCoordinates(const Unit3 &s) const
The local coordinates function.
Vector3 p_
The location of the point on the unit sphere.
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:18:21