Pose3Upright.cpp
Go to the documentation of this file.
1 
8 #include <iostream>
9 #include <cassert>
11 #include <gtsam/base/Vector.h>
12 
14 
15 using namespace std;
16 
17 namespace gtsam {
18 
19 /* ************************************************************************* */
20 Pose3Upright::Pose3Upright(const Rot2& bearing, const Point3& t)
21 : T_(bearing, Point2(t.x(), t.y())), z_(t.z())
22 {
23 }
24 
25 /* ************************************************************************* */
26 Pose3Upright::Pose3Upright(double x, double y, double z, double theta)
27 : T_(x, y, theta), z_(z)
28 {
29 }
30 
31 /* ************************************************************************* */
33 : T_(pose), z_(z)
34 {
35 }
36 
37 /* ************************************************************************* */
39 : T_(x.x(), x.y(), x.rotation().yaw()), z_(x.z())
40 {
41 }
42 
43 /* ************************************************************************* */
44 void Pose3Upright::print(const std::string& s) const {
45  cout << s << "(" << T_.x() << ", " << T_.y() << ", " << z_ << ", " << T_.theta() << ")" << endl;
46 }
47 
48 /* ************************************************************************* */
49 bool Pose3Upright::equals(const Pose3Upright& x, double tol) const {
50  return T_.equals(x.T_, tol) && std::abs(z_ - x.z_) < tol;
51 }
52 
53 /* ************************************************************************* */
55  return Point3(x(), y(), z());
56 }
57 
58 /* ************************************************************************* */
60  return T_.t();
61 }
62 
63 /* ************************************************************************* */
65  return T_.r();
66 }
67 
68 /* ************************************************************************* */
70  return Rot3::Yaw(theta());
71 }
72 
73 /* ************************************************************************* */
75  return T_;
76 }
77 
78 /* ************************************************************************* */
80  return Pose3(rotation(), translation());
81 }
82 
83 /* ************************************************************************* */
85  if (!H1) {
86  return Pose3Upright(T_.inverse(), -z_);
87  }
89  // TODO(kartikarcot): Could not use reference to a view into H1 and reuse memory
90  // Eigen::Ref<Eigen::Matrix<double, 3, 3>> H3x3 = H1->topLeftCorner(3,3);
91  Pose3Upright result(T_.inverse(H3x3), -z_);
92  Matrix H1_ = -I_4x4;
93  H1_.topLeftCorner(2, 2) = H3x3.topLeftCorner(2, 2);
94  H1_.topRightCorner(2, 1) = H3x3.topRightCorner(2, 1);
95  *H1 = H1_;
96  return result;
97 }
98 
99 /* ************************************************************************* */
102  if (!H1 && !H2)
103  return Pose3Upright(T_.compose(p2.T_), z_ + p2.z_);
104 
105  // TODO(kartikarcot): Could not use reference to a view into H1 and reuse memory
107  Pose3Upright result(T_.compose(p2.T_, H3x3), z_ + p2.z_);
108  if (H1) {
109  Matrix H1_ = I_4x4;
110  H1_.topLeftCorner(2,2) = H3x3.topLeftCorner(2,2);
111  H1_.topRightCorner(2, 1) = H3x3.topRightCorner(2, 1);
112  *H1 = H1_;
113  }
114  if (H2) *H2 = I_4x4;
115  return result;
116 }
117 
118 /* ************************************************************************* */
121  if (!H1 && !H2)
122  return Pose3Upright(T_.between(p2.T_), p2.z_ - z_);
123 
124  // TODO(kartikarcot): Could not use reference to a view into H1 and H2 to reuse memory
125  OptionalJacobian<3, 3>::Jacobian H3x3_1, H3x3_2;
126  Pose3Upright result(T_.between(p2.T_, H3x3_1, H3x3_2), p2.z_ - z_);
127  if (H1) {
128  Matrix H1_ = -I_4x4;
129  H1_.topLeftCorner(2,2) = H3x3_1.topLeftCorner(2,2);
130  H1_.topRightCorner(2, 1) = H3x3_1.topRightCorner(2, 1);
131  *H1 = H1_;
132  }
133  if (H2) *H2 = I_4x4;
134  return result;
135 }
136 
137 /* ************************************************************************* */
139  assert(v.size() == 4);
140  Vector v1(3); v1 << v(0), v(1), v(3);
141  return Pose3Upright(T_.retract(v1), z_ + v(2));
142 }
143 
144 /* ************************************************************************* */
146  Vector pose2 = T_.localCoordinates(p2.pose2());
147  Vector result(4);
148  result << pose2(0), pose2(1), p2.z() - z_, pose2(2);
149  return result;
150 }
151 
152 /* ************************************************************************* */
154  assert(xi.size() == 4);
155  Vector v1(3); v1 << xi(0), xi(1), xi(3);
156  return Pose3Upright(Pose2::Expmap(v1), xi(2));
157 }
158 
159 /* ************************************************************************* */
161  Vector pose2 = Pose2::Logmap(p.pose2());
162  Vector result(4);
163  result << pose2(0), pose2(1), p.z(), pose2(2);
164  return result;
165 }
166 /* ************************************************************************* */
167 
168 } // \namespace gtsam
169 
170 
171 
gtsam::Pose2::inverse
Pose2 inverse() const
inverse
Definition: Pose2.cpp:202
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
gtsam::Pose3Upright::pose2
Pose2 pose2() const
Definition: Pose3Upright.cpp:74
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Vector.h
typedef and functions to augment Eigen's VectorXd
gtsam::Pose3Upright::z
double z() const
Definition: Pose3Upright.h:66
s
RealScalar s
Definition: level1_cplx_impl.h:126
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
gtsam::Pose2::equals
bool equals(const Pose2 &pose, double tol=1e-9) const
Definition: Pose2.cpp:62
gtsam::Pose3Upright::compose
Pose3Upright compose(const Pose3Upright &p2, OptionalJacobian< 4, 4 > H1={}, OptionalJacobian< 4, 4 > H2={}) const
compose this transformation onto another (first *this and then p2)
Definition: Pose3Upright.cpp:100
gtsam::Pose2::t
const Point2 & t() const
translation
Definition: Pose2.h:259
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::Rot3::Yaw
static Rot3 Yaw(double t)
Positive yaw is to right (as in aircraft heading). See ypr.
Definition: Rot3.h:178
gtsam::Pose3Upright::between
Pose3Upright between(const Pose3Upright &p2, OptionalJacobian< 4, 4 > H1={}, OptionalJacobian< 4, 4 > H2={}) const
Definition: Pose3Upright.cpp:119
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Pose3Upright::theta
double theta() const
Definition: Pose3Upright.h:67
gtsam::Pose2::Expmap
static Pose2 Expmap(const Vector3 &xi, ChartJacobian H={})
Exponential map at identity - create a rotation from canonical coordinates .
Definition: Pose2.cpp:67
gtsam::Pose3Upright::Expmap
static Pose3Upright Expmap(const Vector &xi)
Exponential map at identity - create a rotation from canonical coordinates.
Definition: Pose3Upright.cpp:153
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::Pose3Upright::T_
Pose2 T_
Definition: Pose3Upright.h:31
gtsam::Pose3Upright::pose
Pose3 pose() const
Definition: Pose3Upright.cpp:79
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
gtsam::Pose2::Logmap
static Vector3 Logmap(const Pose2 &p, ChartJacobian H={})
Log map at identity - return the canonical coordinates of this rotation.
Definition: Pose2.cpp:83
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Pose3Upright::Logmap
static Vector Logmap(const Pose3Upright &p)
Log map at identity - return the canonical coordinates of this rotation.
Definition: Pose3Upright.cpp:160
gtsam::Pose2::r
const Rot2 & r() const
rotation
Definition: Pose2.h:262
Pose3Upright.h
Variation of a Pose3 in which the rotation is constained to purely yaw This state is essentially a Po...
OptionalJacobian.h
Special class for optional Jacobian arguments.
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::LieGroup::localCoordinates
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:136
gtsam::Pose3Upright::rotation
Rot3 rotation() const
Definition: Pose3Upright.cpp:69
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::Pose2::theta
double theta() const
get theta
Definition: Pose2.h:256
gtsam::Pose3Upright::translation2
Point2 translation2() const
Definition: Pose3Upright.cpp:59
gtsam::Rot2
Definition: Rot2.h:35
gtsam::Pose3Upright::rotation2
Rot2 rotation2() const
Definition: Pose3Upright.cpp:64
gtsam
traits
Definition: SFMdata.h:40
gtsam::rotation
Rot3_ rotation(const Pose3_ &pose)
Definition: slam/expressions.h:89
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Pose3Upright::translation
Point3 translation() const
Definition: Pose3Upright.cpp:54
gtsam::Pose2::x
double x() const
get x
Definition: Pose2.h:250
gtsam::Pose3Upright::y
double y() const
Definition: Pose3Upright.h:65
std
Definition: BFloat16.h:88
gtsam::Pose3Upright::equals
bool equals(const Pose3Upright &pose, double tol=1e-9) const
Definition: Pose3Upright.cpp:49
gtsam::Pose3Upright::print
void print(const std::string &s="") const
Definition: Pose3Upright.cpp:44
p
float * p
Definition: Tutorial_Map_using.cpp:9
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Pose3Upright::x
double x() const
Definition: Pose3Upright.h:64
gtsam::LieGroup::retract
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::Pose3Upright::retract
Pose3Upright retract(const Vector &v) const
Definition: Pose3Upright.cpp:138
abs
#define abs(x)
Definition: datatypes.h:17
gtsam::Pose3Upright
Definition: Pose3Upright.h:25
gtsam::Pose3Upright::Pose3Upright
Pose3Upright()
Default constructor initializes at origin.
Definition: Pose3Upright.h:39
gtsam::Pose3Upright::localCoordinates
Vector localCoordinates(const Pose3Upright &p2) const
Local 3D coordinates of Pose3Upright manifold neighborhood around current pose.
Definition: Pose3Upright.cpp:145
gtsam::Pose3Upright::z_
double z_
Definition: Pose3Upright.h:32
align_3::t
Point2 t(10, 10)
gtsam::Pose2::y
double y() const
get y
Definition: Pose2.h:253
gtsam::Pose3Upright::inverse
Pose3Upright inverse(OptionalJacobian< 4, 4 > H1={}) const
inverse transformation with derivatives
Definition: Pose3Upright.cpp:84
v1
Vector v1
Definition: testSerializationBase.cpp:38
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:45