#include <geometry_msgs/Point.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Vector3.h>
#include <Eigen/Geometry>
Go to the source code of this file.
Namespaces | |
namespace | mav_msgs |
Functions | |
void | mav_msgs::getEulerAnglesFromQuaternion (const Eigen::Quaternion< double > &q, Eigen::Vector3d *euler_angles) |
void | mav_msgs::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) |
double | mav_msgs::MagnitudeOfGravity (const double height, const double latitude_radians) |
double | mav_msgs::nanosecondsToSeconds (int64_t nanoseconds) |
void | mav_msgs::pointEigenToMsg (const Eigen::Vector3d &eigen, geometry_msgs::Point *msg) |
void | mav_msgs::quaternionEigenToMsg (const Eigen::Quaterniond &eigen, geometry_msgs::Quaternion *msg) |
Eigen::Quaterniond | mav_msgs::quaternionFromMsg (const geometry_msgs::Quaternion &msg) |
Eigen::Quaterniond | mav_msgs::quaternionFromYaw (double yaw) |
int64_t | mav_msgs::secondsToNanoseconds (double seconds) |
void | mav_msgs::setAngularVelocityMsgFromYawRate (double yaw_rate, geometry_msgs::Vector3 *msg) |
void | mav_msgs::setQuaternionMsgFromYaw (double yaw, geometry_msgs::Quaternion *msg) |
Eigen::Vector3d | mav_msgs::vector3FromMsg (const geometry_msgs::Vector3 &msg) |
Eigen::Vector3d | mav_msgs::vector3FromPointMsg (const geometry_msgs::Point &msg) |
void | mav_msgs::vectorEigenToMsg (const Eigen::Vector3d &eigen, geometry_msgs::Vector3 *msg) |
double | mav_msgs::yawFromQuaternion (const Eigen::Quaterniond &q) |
Extracts the yaw part from a quaternion, using RPY / euler (z-y'-z'') angles. RPY rotates about the fixed axes in the order x-y-z, which is the same as euler angles in the order z-y'-x''. | |
Variables | |
const double | mav_msgs::kNumNanosecondsPerSecond = 1.e9 |