23 #ifndef MAV_MSGS_COMMON_H 24 #define MAV_MSGS_COMMON_H 26 #include <geometry_msgs/Point.h> 27 #include <geometry_msgs/Quaternion.h> 28 #include <geometry_msgs/Vector3.h> 29 #include <Eigen/Geometry> 38 const double latitude_radians) {
40 const double kGravity_0 = 9.780327;
41 const double kGravity_a = 0.0053024;
42 const double kGravity_b = 0.0000058;
43 const double kGravity_c = 3.155 * 1e-7;
45 double sin_squared_latitude = sin(latitude_radians) * sin(latitude_radians);
46 double sin_squared_twice_latitude =
47 sin(2 * latitude_radians) * sin(2 * latitude_radians);
48 return kGravity_0 * ((1 + kGravity_a * sin_squared_latitude -
49 kGravity_b * sin_squared_twice_latitude) -
54 return Eigen::Vector3d(msg.x, msg.y, msg.z);
58 return Eigen::Vector3d(msg.x, msg.y, msg.z);
62 const geometry_msgs::Quaternion& msg) {
65 Eigen::Quaterniond quaternion(msg.w, msg.x, msg.y, msg.z);
66 if (quaternion.norm() < std::numeric_limits<double>::epsilon()) {
67 quaternion.setIdentity();
69 quaternion.normalize();
75 geometry_msgs::Vector3* msg) {
83 geometry_msgs::Point* msg) {
91 geometry_msgs::Quaternion* msg) {
106 return atan2(2.0 * (q.w() * q.z() + q.x() * q.y()),
107 1.0 - 2.0 * (q.y() * q.y() + q.z() * q.z()));
111 return Eigen::Quaterniond(Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()));
115 geometry_msgs::Quaternion* msg) {
125 geometry_msgs::Vector3* msg) {
133 Eigen::Vector3d* euler_angles) {
135 assert(euler_angles != NULL);
137 *euler_angles << atan2(2.0 * (q.w() * q.x() + q.y() * q.z()),
138 1.0 - 2.0 * (q.x() * q.x() + q.y() * q.y())),
139 asin(2.0 * (q.w() * q.y() - q.z() * q.x())),
140 atan2(2.0 * (q.w() * q.z() + q.x() * q.y()),
141 1.0 - 2.0 * (q.y() * q.y() + q.z() * q.z()));
169 const Eigen::MatrixXd& allocation_inv,
const Eigen::Vector3d& inertia,
170 double mass,
const Eigen::Vector3d& angular_velocity_B,
171 const Eigen::Vector3d& angular_acceleration_B,
172 const Eigen::Vector3d& acceleration_B,
173 Eigen::VectorXd* rotor_rates_squared) {
174 const Eigen::Vector3d torque =
175 inertia.asDiagonal() * angular_acceleration_B +
176 angular_velocity_B.cross(inertia.asDiagonal() * angular_velocity_B);
177 const double thrust_force = mass * acceleration_B.norm();
178 Eigen::Vector4d input;
179 input << torque, thrust_force;
180 *rotor_rates_squared = allocation_inv * input;
189 int64_t nanoseconds =
196 #endif // MAV_MSGS_COMMON_H void quaternionEigenToMsg(const Eigen::Quaterniond &eigen, geometry_msgs::Quaternion *msg)
double MagnitudeOfGravity(const double height, const double latitude_radians)
void setAngularVelocityMsgFromYawRate(double yaw_rate, geometry_msgs::Vector3 *msg)
void getSquaredRotorSpeedsFromAllocationAndState(const Eigen::MatrixXd &allocation_inv, const Eigen::Vector3d &inertia, double mass, const Eigen::Vector3d &angular_velocity_B, const Eigen::Vector3d &angular_acceleration_B, const Eigen::Vector3d &acceleration_B, Eigen::VectorXd *rotor_rates_squared)
Eigen::Vector3d vector3FromMsg(const geometry_msgs::Vector3 &msg)
void setQuaternionMsgFromYaw(double yaw, geometry_msgs::Quaternion *msg)
const double kNumNanosecondsPerSecond
void getEulerAnglesFromQuaternion(const Eigen::Quaternion< double > &q, Eigen::Vector3d *euler_angles)
int64_t secondsToNanoseconds(double seconds)
double nanosecondsToSeconds(int64_t nanoseconds)
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 vectorEigenToMsg(const Eigen::Vector3d &eigen, geometry_msgs::Vector3 *msg)
Eigen::Quaterniond quaternionFromMsg(const geometry_msgs::Quaternion &msg)
Eigen::Vector3d vector3FromPointMsg(const geometry_msgs::Point &msg)
Eigen::Quaterniond quaternionFromYaw(double yaw)
void pointEigenToMsg(const Eigen::Vector3d &eigen, geometry_msgs::Point *msg)