21 #ifndef MAV_MSGS_EIGEN_MAV_MSGS_H 22 #define MAV_MSGS_EIGEN_MAV_MSGS_H 24 #include <Eigen/Eigen> 34 :
attitude(Eigen::Quaterniond::Identity()),
35 thrust(Eigen::Vector3d::Zero()) {}
37 const Eigen::Vector3d& _thrust) {
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51 angular_velocities = _angular_velocities;
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62 : angular_rates(Eigen::Vector3d::Zero()),
63 thrust(Eigen::Vector3d::Zero()) {}
66 const Eigen::Vector3d _thrust)
67 : angular_rates(_angular_rates),
thrust(_thrust) {}
69 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
76 : torque(Eigen::Vector3d::Zero()),
thrust(Eigen::Vector3d::Zero()) {}
79 const Eigen::Vector3d _thrust)
80 : torque(_torque),
thrust(_thrust) {}
82 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
89 : roll(0.0), pitch(0.0), yaw_rate(0.0),
thrust(Eigen::Vector3d::Zero()) {}
92 const Eigen::Vector3d& _thrust)
93 : roll(_roll), pitch(_pitch), yaw_rate(_yaw_rate),
thrust(_thrust) {}
111 Eigen::aligned_allocator<EigenMavState>>
Vector;
112 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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()) {}
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) {}
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()
146 <<
"angular_acceleration_body: " << angular_acceleration_B.transpose()
162 Eigen::aligned_allocator<EigenTrajectoryPoint>>
Vector;
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()) {}
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),
190 orientation_W_B(_orientation),
191 angular_velocity_W(_angular_velocity),
192 angular_acceleration_W(_angular_acceleration) {}
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()) {}
206 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
221 inline double getYawRate()
const {
return angular_velocity_W.z(); }
222 inline double getYawAcc()
const {
return angular_acceleration_W.z(); }
228 angular_velocity_W.x() = 0.0;
229 angular_velocity_W.y() = 0.0;
230 angular_velocity_W.z() = yaw_rate;
233 angular_acceleration_W.x() = 0.0;
234 angular_acceleration_W.y() = 0.0;
235 angular_acceleration_W.z() = yaw_acc;
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;
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()) {}
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) {}
291 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
305 inline double getYawRate()
const {
return angular_velocity_B.z(); }
311 angular_velocity_B.x() = 0.0;
312 angular_velocity_B.y() = 0.0;
313 angular_velocity_B.z() = yaw_rate;
317 return orientation_W_B * velocity_B;
320 velocity_B = orientation_W_B.inverse() * velocity_world;
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); 341 #endif // MAV_MSGS_EIGEN_MAV_MSGS_H Eigen::Vector3d acceleration_W
#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
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)
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::Vector3d velocity_W
Eigen::Vector3d angular_velocity_W
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)
double getYawRate() const
Eigen::Quaterniond orientation_W_B
std::vector< EigenTrajectoryPoint, Eigen::aligned_allocator< EigenTrajectoryPoint > > Vector
Eigen::Vector3d position_W
Eigen::Vector3d angular_acceleration_B
int64_t time_from_start_ns
double yawFromQuaternion(const Eigen::Quaterniond &q)
Extracts the yaw part from a quaternion, using RPY / euler (z-y'-z'') angles. RPY rotates about the f...
void getEulerAngles(Eigen::Vector3d *euler_angles) const
void setFromYawAcc(double yaw_acc)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Quaterniond attitude
Eigen::Vector3d position_W
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
EigenRollPitchYawrateThrust()
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)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d torque
Eigen::Vector3d velocity_W
void setFromYaw(double yaw)
Eigen::Vector3d angular_velocity_B
Eigen::Vector3d acceleration_B
EigenTrajectoryPoint operator*(const Eigen::Affine3d &lhs, const EigenTrajectoryPoint &rhs)