eigen_mav_msgs.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Helen Oleynikova, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13 
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  */
20 
21 #ifndef MAV_MSGS_EIGEN_MAV_MSGS_H
22 #define MAV_MSGS_EIGEN_MAV_MSGS_H
23 
24 #include <Eigen/Eigen>
25 #include <deque>
26 #include <iostream>
27 
28 #include "mav_msgs/common.h"
29 
30 namespace mav_msgs {
31 
34  : attitude(Eigen::Quaterniond::Identity()),
35  thrust(Eigen::Vector3d::Zero()) {}
36  EigenAttitudeThrust(const Eigen::Quaterniond& _attitude,
37  const Eigen::Vector3d& _thrust) {
38  attitude = _attitude;
39  thrust = _thrust;
40  }
41 
42  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43  Eigen::Quaterniond attitude;
44  Eigen::Vector3d thrust;
45 };
46 
48  // TODO(ffurrer): Find a proper way of initializing :)
49 
50  EigenActuators(const Eigen::VectorXd& _angular_velocities) {
51  angular_velocities = _angular_velocities;
52  }
53 
54  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55  Eigen::VectorXd angles; // In rad.
56  Eigen::VectorXd angular_velocities; // In rad/s.
57  Eigen::VectorXd normalized; // Everything else, normalized [-1 to 1].
58 };
59 
62  : angular_rates(Eigen::Vector3d::Zero()),
63  thrust(Eigen::Vector3d::Zero()) {}
64 
65  EigenRateThrust(const Eigen::Vector3d& _angular_rates,
66  const Eigen::Vector3d _thrust)
67  : angular_rates(_angular_rates), thrust(_thrust) {}
68 
69  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
70  Eigen::Vector3d angular_rates;
71  Eigen::Vector3d thrust;
72 };
73 
76  : torque(Eigen::Vector3d::Zero()), thrust(Eigen::Vector3d::Zero()) {}
77 
78  EigenTorqueThrust(const Eigen::Vector3d& _torque,
79  const Eigen::Vector3d _thrust)
80  : torque(_torque), thrust(_thrust) {}
81 
82  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
83  Eigen::Vector3d torque;
84  Eigen::Vector3d thrust;
85 };
86 
89  : roll(0.0), pitch(0.0), yaw_rate(0.0), thrust(Eigen::Vector3d::Zero()) {}
90 
91  EigenRollPitchYawrateThrust(double _roll, double _pitch, double _yaw_rate,
92  const Eigen::Vector3d& _thrust)
93  : roll(_roll), pitch(_pitch), yaw_rate(_yaw_rate), thrust(_thrust) {}
94 
95  double roll;
96  double pitch;
97  double yaw_rate;
98  Eigen::Vector3d thrust;
99 };
100 
109  public:
110  typedef std::vector<EigenMavState,
111  Eigen::aligned_allocator<EigenMavState>> Vector;
112  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
113 
116  : position_W(Eigen::Vector3d::Zero()),
117  velocity_W(Eigen::Vector3d::Zero()),
118  acceleration_B(Eigen::Vector3d::Zero()),
119  orientation_W_B(Eigen::Quaterniond::Identity()),
120  angular_velocity_B(Eigen::Vector3d::Zero()),
121  angular_acceleration_B(Eigen::Vector3d::Zero()) {}
122 
123  EigenMavState(const Eigen::Vector3d& position_W,
124  const Eigen::Vector3d& velocity_W,
125  const Eigen::Vector3d& acceleration_B,
126  const Eigen::Quaterniond& orientation_W_B,
127  const Eigen::Vector3d& angular_velocity_B,
128  const Eigen::Vector3d& angular_acceleration_B)
129  : position_W(position_W),
130  velocity_W(velocity_W),
131  acceleration_B(acceleration_B),
132  orientation_W_B(orientation_W_B),
133  angular_velocity_B(angular_velocity_B),
134  angular_acceleration_B(angular_acceleration_B) {}
135 
136  std::string toString() const {
137  std::stringstream ss;
138  ss << "position: " << position_W.transpose() << std::endl
139  << "velocity: " << velocity_W.transpose() << std::endl
140  << "acceleration_body: " << acceleration_B.transpose() << std::endl
141  << "orientation (w-x-y-z): " << orientation_W_B.w() << " "
142  << orientation_W_B.x() << " " << orientation_W_B.y() << " "
143  << orientation_W_B.z() << " " << std::endl
144  << "angular_velocity_body: " << angular_velocity_B.transpose()
145  << std::endl
146  << "angular_acceleration_body: " << angular_acceleration_B.transpose()
147  << std::endl;
148 
149  return ss.str();
150  }
151 
152  Eigen::Vector3d position_W;
153  Eigen::Vector3d velocity_W;
154  Eigen::Vector3d acceleration_B;
155  Eigen::Quaterniond orientation_W_B;
156  Eigen::Vector3d angular_velocity_B;
157  Eigen::Vector3d angular_acceleration_B;
158 };
159 
161  typedef std::vector<EigenTrajectoryPoint,
162  Eigen::aligned_allocator<EigenTrajectoryPoint>> Vector;
164  : timestamp_ns(-1),
165  time_from_start_ns(0),
166  position_W(Eigen::Vector3d::Zero()),
167  velocity_W(Eigen::Vector3d::Zero()),
168  acceleration_W(Eigen::Vector3d::Zero()),
169  jerk_W(Eigen::Vector3d::Zero()),
170  snap_W(Eigen::Vector3d::Zero()),
171  orientation_W_B(Eigen::Quaterniond::Identity()),
172  angular_velocity_W(Eigen::Vector3d::Zero()),
173  angular_acceleration_W(Eigen::Vector3d::Zero()) {}
174 
175  EigenTrajectoryPoint(int64_t _time_from_start_ns,
176  const Eigen::Vector3d& _position,
177  const Eigen::Vector3d& _velocity,
178  const Eigen::Vector3d& _acceleration,
179  const Eigen::Vector3d& _jerk,
180  const Eigen::Vector3d& _snap,
181  const Eigen::Quaterniond& _orientation,
182  const Eigen::Vector3d& _angular_velocity,
183  const Eigen::Vector3d& _angular_acceleration)
184  : time_from_start_ns(_time_from_start_ns),
185  position_W(_position),
186  velocity_W(_velocity),
187  acceleration_W(_acceleration),
188  jerk_W(_jerk),
189  snap_W(_snap),
190  orientation_W_B(_orientation),
191  angular_velocity_W(_angular_velocity),
192  angular_acceleration_W(_angular_acceleration) {}
193 
194  EigenTrajectoryPoint(int64_t _time_from_start_ns,
195  const Eigen::Vector3d& _position,
196  const Eigen::Vector3d& _velocity,
197  const Eigen::Vector3d& _acceleration,
198  const Eigen::Vector3d& _jerk,
199  const Eigen::Vector3d& _snap,
200  const Eigen::Quaterniond& _orientation,
201  const Eigen::Vector3d& _angular_velocity)
202  : EigenTrajectoryPoint(_time_from_start_ns, _position, _velocity,
203  _acceleration, _jerk, _snap, _orientation,
204  _angular_velocity, Eigen::Vector3d::Zero()) {}
205 
206  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
207  int64_t timestamp_ns; // Time since epoch, negative value = invalid timestamp.
209  Eigen::Vector3d position_W;
210  Eigen::Vector3d velocity_W;
211  Eigen::Vector3d acceleration_W;
212  Eigen::Vector3d jerk_W;
213  Eigen::Vector3d snap_W;
214 
215  Eigen::Quaterniond orientation_W_B;
216  Eigen::Vector3d angular_velocity_W;
217  Eigen::Vector3d angular_acceleration_W;
218 
219  // Accessors for making dealing with orientation/angular velocity easier.
220  inline double getYaw() const { return yawFromQuaternion(orientation_W_B); }
221  inline double getYawRate() const { return angular_velocity_W.z(); }
222  inline double getYawAcc() const { return angular_acceleration_W.z(); }
223  // WARNING: sets roll and pitch to 0.
224  inline void setFromYaw(double yaw) {
225  orientation_W_B = quaternionFromYaw(yaw);
226  }
227  inline void setFromYawRate(double yaw_rate) {
228  angular_velocity_W.x() = 0.0;
229  angular_velocity_W.y() = 0.0;
230  angular_velocity_W.z() = yaw_rate;
231  }
232  inline void setFromYawAcc(double yaw_acc) {
233  angular_acceleration_W.x() = 0.0;
234  angular_acceleration_W.y() = 0.0;
235  angular_acceleration_W.z() = yaw_acc;
236  }
237 
238  std::string toString() const {
239  std::stringstream ss;
240  ss << "position: " << position_W.transpose() << std::endl
241  << "velocity: " << velocity_W.transpose() << std::endl
242  << "acceleration: " << acceleration_W.transpose() << std::endl
243  << "jerk: " << jerk_W.transpose() << std::endl
244  << "snap: " << snap_W.transpose() << std::endl
245  << "yaw: " << getYaw() << std::endl
246  << "yaw_rate: " << getYawRate() << std::endl
247  << "yaw_acc: " << getYawAcc() << std::endl;
248 
249  return ss.str();
250  }
251 };
252 
253 // Operator overload to transform Trajectory Points according to the Eigen
254 // interfaces (uses operator* for this).
255 // Has to be outside of class.
256 // Example:
257 // Eigen::Affine3d transform; EigenTrajectoryPoint point;
258 // EigenTrajectoryPoint transformed = transform * point;
259 inline EigenTrajectoryPoint operator*(const Eigen::Affine3d& lhs,
260  const EigenTrajectoryPoint& rhs) {
261  EigenTrajectoryPoint transformed(rhs);
262  transformed.position_W = lhs * rhs.position_W;
263  transformed.velocity_W = lhs.rotation() * rhs.velocity_W;
264  transformed.acceleration_W = lhs.rotation() * rhs.acceleration_W;
265  transformed.jerk_W = lhs.rotation() * rhs.jerk_W;
266  transformed.snap_W = lhs.rotation() * rhs.snap_W;
267  transformed.orientation_W_B = lhs.rotation() * rhs.orientation_W_B;
268  transformed.angular_velocity_W = lhs.rotation() * rhs.angular_velocity_W;
269  transformed.angular_acceleration_W =
270  lhs.rotation() * rhs.angular_acceleration_W;
271  return transformed;
272 }
273 
276  : timestamp_ns(-1),
277  position_W(Eigen::Vector3d::Zero()),
278  orientation_W_B(Eigen::Quaterniond::Identity()),
279  velocity_B(Eigen::Vector3d::Zero()),
280  angular_velocity_B(Eigen::Vector3d::Zero()) {}
281 
282  EigenOdometry(const Eigen::Vector3d& _position,
283  const Eigen::Quaterniond& _orientation,
284  const Eigen::Vector3d& _velocity_body,
285  const Eigen::Vector3d& _angular_velocity)
286  : position_W(_position),
287  orientation_W_B(_orientation),
288  velocity_B(_velocity_body),
289  angular_velocity_B(_angular_velocity) {}
290 
291  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
292  int64_t timestamp_ns; // Time since epoch, negative value = invalid timestamp.
293  Eigen::Vector3d position_W;
294  Eigen::Quaterniond orientation_W_B;
295  Eigen::Vector3d velocity_B; // Velocity in expressed in the Body frame!
296  Eigen::Vector3d angular_velocity_B;
297  Eigen::Matrix<double, 6, 6> pose_covariance_;
298  Eigen::Matrix<double, 6, 6> twist_covariance_;
299 
300  // Accessors for making dealing with orientation/angular velocity easier.
301  inline double getYaw() const { return yawFromQuaternion(orientation_W_B); }
302  inline void getEulerAngles(Eigen::Vector3d* euler_angles) const {
303  getEulerAnglesFromQuaternion(orientation_W_B, euler_angles);
304  }
305  inline double getYawRate() const { return angular_velocity_B.z(); }
306  // WARNING: sets roll and pitch to 0.
307  inline void setFromYaw(double yaw) {
308  orientation_W_B = quaternionFromYaw(yaw);
309  }
310  inline void setFromYawRate(double yaw_rate) {
311  angular_velocity_B.x() = 0.0;
312  angular_velocity_B.y() = 0.0;
313  angular_velocity_B.z() = yaw_rate;
314  }
315 
316  inline Eigen::Vector3d getVelocityWorld() const {
317  return orientation_W_B * velocity_B;
318  }
319  inline void setVelocityWorld(const Eigen::Vector3d& velocity_world) {
320  velocity_B = orientation_W_B.inverse() * velocity_world;
321  }
322 };
323 
324 // TODO(helenol): replaced with aligned allocator headers from Simon.
325 #define MAV_MSGS_CONCATENATE(x, y) x##y
326 #define MAV_MSGS_CONCATENATE2(x, y) MAV_MSGS_CONCATENATE(x, y)
327 #define MAV_MSGS_MAKE_ALIGNED_CONTAINERS(EIGEN_TYPE) \
328  typedef std::vector<EIGEN_TYPE, Eigen::aligned_allocator<EIGEN_TYPE>> \
329  MAV_MSGS_CONCATENATE2(EIGEN_TYPE, Vector); \
330  typedef std::deque<EIGEN_TYPE, Eigen::aligned_allocator<EIGEN_TYPE>> \
331  MAV_MSGS_CONCATENATE2(EIGEN_TYPE, Deque);
332 
334 MAV_MSGS_MAKE_ALIGNED_CONTAINERS(EigenActuators)
335 MAV_MSGS_MAKE_ALIGNED_CONTAINERS(EigenRateThrust)
336 MAV_MSGS_MAKE_ALIGNED_CONTAINERS(EigenTrajectoryPoint)
337 MAV_MSGS_MAKE_ALIGNED_CONTAINERS(EigenRollPitchYawrateThrust)
339 }
340 
341 #endif // MAV_MSGS_EIGEN_MAV_MSGS_H
#define MAV_MSGS_MAKE_ALIGNED_CONTAINERS(EIGEN_TYPE)
Eigen::VectorXd normalized
Eigen::Vector3d getVelocityWorld() const
Eigen::Vector3d position_W
void setFromYawRate(double yaw_rate)
EigenRateThrust(const Eigen::Vector3d &_angular_rates, const Eigen::Vector3d _thrust)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int64_t timestamp_ns
void setFromYawRate(double yaw_rate)
EigenMavState(const Eigen::Vector3d &position_W, const Eigen::Vector3d &velocity_W, const Eigen::Vector3d &acceleration_B, const Eigen::Quaterniond &orientation_W_B, const Eigen::Vector3d &angular_velocity_B, const Eigen::Vector3d &angular_acceleration_B)
std::string toString() const
double getYaw() const
EigenTrajectoryPoint(int64_t _time_from_start_ns, const Eigen::Vector3d &_position, const Eigen::Vector3d &_velocity, const Eigen::Vector3d &_acceleration, const Eigen::Vector3d &_jerk, const Eigen::Vector3d &_snap, const Eigen::Quaterniond &_orientation, const Eigen::Vector3d &_angular_velocity)
EigenActuators(const Eigen::VectorXd &_angular_velocities)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EigenMavState()
Initializes all members to zero / identity.
Eigen::Vector3d velocity_B
EigenOdometry(const Eigen::Vector3d &_position, const Eigen::Quaterniond &_orientation, const Eigen::Vector3d &_velocity_body, const Eigen::Vector3d &_angular_velocity)
std::vector< EigenMavState, Eigen::aligned_allocator< EigenMavState > > Vector
std::string toString() const
void setFromYaw(double yaw)
Eigen::Matrix< double, 6, 6 > twist_covariance_
Eigen::Matrix< double, 6, 6 > pose_covariance_
Eigen::Quaterniond orientation_W_B
void setVelocityWorld(const Eigen::Vector3d &velocity_world)
void getEulerAnglesFromQuaternion(const Eigen::Quaternion< double > &q, Eigen::Vector3d *euler_angles)
Definition: common.h:132
EigenAttitudeThrust(const Eigen::Quaterniond &_attitude, const Eigen::Vector3d &_thrust)
EigenTorqueThrust(const Eigen::Vector3d &_torque, const Eigen::Vector3d _thrust)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d angular_rates
Eigen::VectorXd angular_velocities
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int64_t timestamp_ns
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::VectorXd angles
EigenRollPitchYawrateThrust(double _roll, double _pitch, double _yaw_rate, const Eigen::Vector3d &_thrust)
Eigen::Quaterniond orientation_W_B
std::vector< EigenTrajectoryPoint, Eigen::aligned_allocator< EigenTrajectoryPoint > > Vector
Eigen::Vector3d position_W
Eigen::Vector3d angular_acceleration_B
double yawFromQuaternion(const Eigen::Quaterniond &q)
Extracts the yaw part from a quaternion, using RPY / euler (z-y&#39;-z&#39;&#39;) angles. RPY rotates about the f...
Definition: common.h:105
void getEulerAngles(Eigen::Vector3d *euler_angles) const
void setFromYawAcc(double yaw_acc)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Quaterniond attitude
Container holding the state of a MAV: position, velocity, attitude and angular velocity. In addition, holds the acceleration expressed in body coordinates, which is what the accelerometer usually measures.
Eigen::Vector3d angular_velocity_B
double getYawRate() const
Eigen::Vector3d angular_acceleration_W
Eigen::Quaterniond orientation_W_B
EigenTrajectoryPoint(int64_t _time_from_start_ns, const Eigen::Vector3d &_position, const Eigen::Vector3d &_velocity, const Eigen::Vector3d &_acceleration, const Eigen::Vector3d &_jerk, const Eigen::Vector3d &_snap, const Eigen::Quaterniond &_orientation, const Eigen::Vector3d &_angular_velocity, const Eigen::Vector3d &_angular_acceleration)
Eigen::Quaterniond quaternionFromYaw(double yaw)
Definition: common.h:110
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d torque
Eigen::Vector3d velocity_W
Eigen::Vector3d angular_velocity_B
Eigen::Vector3d acceleration_B
EigenTrajectoryPoint operator*(const Eigen::Affine3d &lhs, const EigenTrajectoryPoint &rhs)


mav_msgs
Author(s): Simon Lynen, Markus Achtelik, Pascal Gohl, Sammy Omari, Michael Burri, Fadri Furrer, Helen Oleynikova, Mina Kamel, Karen Bodie, Rik Bähnemann
autogenerated on Sat Jun 15 2019 19:55:13