Namespaces | Classes | Enumerations | Functions | Variables
mav_msgs Namespace Reference

Namespaces

 default_topics
 

Classes

struct  EigenActuators
 
struct  EigenAttitudeThrust
 
class  EigenMavState
 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. More...
 
struct  EigenOdometry
 
struct  EigenRateThrust
 
struct  EigenRollPitchYawrateThrust
 
struct  EigenTorqueThrust
 
struct  EigenTrajectoryPoint
 

Enumerations

enum  MavActuation { DOF4 = 4, DOF6 = 6 }
 Actuated degrees of freedom. More...
 

Functions

void eigenActuatorsFromMsg (const Actuators &msg, EigenActuators *actuators)
 
void eigenAttitudeThrustFromMsg (const AttitudeThrust &msg, EigenAttitudeThrust *attitude_thrust)
 
void EigenMavStateFromEigenTrajectoryPoint (const Eigen::Vector3d &acceleration, const Eigen::Vector3d &jerk, const Eigen::Vector3d &snap, double yaw, double yaw_rate, double yaw_acceleration, double magnitude_of_gravity, Eigen::Quaterniond *orientation, Eigen::Vector3d *acceleration_body, Eigen::Vector3d *angular_velocity_body, Eigen::Vector3d *angular_acceleration_body)
 Computes the MAV state (position, velocity, attitude, angular velocity, angular acceleration) from the flat state. Additionally, computes the acceleration expressed in body coordinates, i.e. the acceleration measured by the IMU. No air-drag is assumed here. More...
 
void EigenMavStateFromEigenTrajectoryPoint (const Eigen::Vector3d &acceleration, const Eigen::Vector3d &jerk, const Eigen::Vector3d &snap, double yaw, double yaw_rate, double yaw_acceleration, Eigen::Quaterniond *orientation, Eigen::Vector3d *acceleration_body, Eigen::Vector3d *angular_velocity_body, Eigen::Vector3d *angular_acceleration_body)
 
void EigenMavStateFromEigenTrajectoryPoint (const EigenTrajectoryPoint &trajectory_point, double magnitude_of_gravity, EigenMavState *mav_state)
 
void EigenMavStateFromEigenTrajectoryPoint (const EigenTrajectoryPoint &flat_state, EigenMavState *mav_state)
 Convenience function with EigenTrajectoryPoint as input and EigenMavState as output with default value for the magnitude of the gravity vector. More...
 
void eigenOdometryFromMsg (const nav_msgs::Odometry &msg, EigenOdometry *odometry)
 
void eigenRateThrustFromMsg (const RateThrust &msg, EigenRateThrust *rate_thrust)
 
void eigenRollPitchYawrateThrustFromMsg (const RollPitchYawrateThrust &msg, EigenRollPitchYawrateThrust *roll_pitch_yawrate_thrust)
 
void eigenTorqueThrustFromMsg (const TorqueThrust &msg, EigenTorqueThrust *torque_thrust)
 
void eigenTrajectoryPointDequeFromMsg (const trajectory_msgs::MultiDOFJointTrajectory &msg, EigenTrajectoryPointDeque *trajectory)
 
void eigenTrajectoryPointFromMsg (const trajectory_msgs::MultiDOFJointTrajectoryPoint &msg, EigenTrajectoryPoint *trajectory_point)
 
void eigenTrajectoryPointFromPoseMsg (const geometry_msgs::Pose &msg, EigenTrajectoryPoint *trajectory_point)
 
void eigenTrajectoryPointFromPoseMsg (const geometry_msgs::PoseStamped &msg, EigenTrajectoryPoint *trajectory_point)
 
void eigenTrajectoryPointFromTransformMsg (const geometry_msgs::TransformStamped &msg, EigenTrajectoryPoint *trajectory_point)
 
void eigenTrajectoryPointVectorFromMsg (const trajectory_msgs::MultiDOFJointTrajectory &msg, EigenTrajectoryPointVector *trajectory)
 
void getEulerAnglesFromQuaternion (const Eigen::Quaternion< double > &q, Eigen::Vector3d *euler_angles)
 
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)
 
bool isRotationMatrix (const Eigen::Matrix3d &mat)
 
double MagnitudeOfGravity (const double height, const double latitude_radians)
 
void matrixFromRotationVector (const Eigen::Vector3d &vec, Eigen::Matrix3d *mat)
 
void msgActuatorsFromEigen (const EigenActuators &actuators, Actuators *msg)
 
void msgAttitudeThrustFromEigen (const EigenAttitudeThrust &attitude_thrust, AttitudeThrust *msg)
 
void msgMultiDofJointTrajectoryFromEigen (const EigenTrajectoryPoint &trajectory_point, const std::string &link_name, trajectory_msgs::MultiDOFJointTrajectory *msg)
 
void msgMultiDofJointTrajectoryFromEigen (const EigenTrajectoryPoint &trajectory_point, trajectory_msgs::MultiDOFJointTrajectory *msg)
 
void msgMultiDofJointTrajectoryFromEigen (const EigenTrajectoryPointVector &trajectory, const std::string &link_name, trajectory_msgs::MultiDOFJointTrajectory *msg)
 
void msgMultiDofJointTrajectoryFromEigen (const EigenTrajectoryPointVector &trajectory, trajectory_msgs::MultiDOFJointTrajectory *msg)
 
void msgMultiDofJointTrajectoryFromEigen (const EigenTrajectoryPointDeque &trajectory, const std::string &link_name, trajectory_msgs::MultiDOFJointTrajectory *msg)
 
void msgMultiDofJointTrajectoryFromEigen (const EigenTrajectoryPointDeque &trajectory, trajectory_msgs::MultiDOFJointTrajectory *msg)
 
void msgMultiDofJointTrajectoryFromPositionYaw (const Eigen::Vector3d &position, double yaw, trajectory_msgs::MultiDOFJointTrajectory *msg)
 
void msgMultiDofJointTrajectoryPointFromEigen (const EigenTrajectoryPoint &trajectory_point, trajectory_msgs::MultiDOFJointTrajectoryPoint *msg)
 
void msgOdometryFromEigen (const EigenOdometry &odometry, nav_msgs::Odometry *msg)
 
void msgPoseStampedFromEigenTrajectoryPoint (const EigenTrajectoryPoint &trajectory_point, geometry_msgs::PoseStamped *msg)
 
void msgRateThrustFromEigen (EigenRateThrust &rate_thrust, RateThrust *msg)
 
void msgRollPitchYawrateThrustFromEigen (const EigenRollPitchYawrateThrust &roll_pitch_yawrate_thrust, RollPitchYawrateThrust *msg)
 
void msgTorqueThrustFromEigen (EigenTorqueThrust &torque_thrust, TorqueThrust *msg)
 
double nanosecondsToSeconds (int64_t nanoseconds)
 
Eigen::Vector3d omegaDotFromRotationVector (const Eigen::Vector3d &rot_vec, const Eigen::Vector3d &rot_vec_vel, const Eigen::Vector3d &rot_vec_acc)
 
Eigen::Vector3d omegaFromRotationVector (const Eigen::Vector3d &rot_vec, const Eigen::Vector3d &rot_vec_vel)
 
EigenTrajectoryPoint operator* (const Eigen::Affine3d &lhs, const EigenTrajectoryPoint &rhs)
 
void pointEigenToMsg (const Eigen::Vector3d &eigen, geometry_msgs::Point *msg)
 
void quaternionEigenToMsg (const Eigen::Quaterniond &eigen, geometry_msgs::Quaternion *msg)
 
Eigen::Quaterniond quaternionFromMsg (const geometry_msgs::Quaternion &msg)
 
Eigen::Quaterniond quaternionFromYaw (double yaw)
 
int64_t secondsToNanoseconds (double seconds)
 
void setAngularVelocityMsgFromYawRate (double yaw_rate, geometry_msgs::Vector3 *msg)
 
void setQuaternionMsgFromYaw (double yaw, geometry_msgs::Quaternion *msg)
 
void skewMatrixFromVector (const Eigen::Vector3d &vec, Eigen::Matrix3d *vec_skew)
 
Eigen::Vector3d vector3FromMsg (const geometry_msgs::Vector3 &msg)
 
Eigen::Vector3d vector3FromPointMsg (const geometry_msgs::Point &msg)
 
void vectorEigenToMsg (const Eigen::Vector3d &eigen, geometry_msgs::Vector3 *msg)
 
bool vectorFromRotationMatrix (const Eigen::Matrix3d &mat, Eigen::Vector3d *vec)
 
bool vectorFromSkewMatrix (const Eigen::Matrix3d &vec_skew, Eigen::Vector3d *vec)
 
double 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''. More...
 

Variables

const double kGravity = MagnitudeOfGravity(kZurichHeight, kZurichLatitude)
 
const double kNumNanosecondsPerSecond = 1.e9
 
const double kSmallValueCheck = 1.e-6
 
const double kZurichHeight = 405.94
 
const double kZurichLatitude = 0.8267
 

Enumeration Type Documentation

Actuated degrees of freedom.

Enumerator
DOF4 
DOF6 

Definition at line 33 of file eigen_mav_msgs.h.

Function Documentation

void mav_msgs::eigenActuatorsFromMsg ( const Actuators &  msg,
EigenActuators actuators 
)
inline

Definition at line 54 of file conversions.h.

void mav_msgs::eigenAttitudeThrustFromMsg ( const AttitudeThrust &  msg,
EigenAttitudeThrust attitude_thrust 
)
inline

Definition at line 46 of file conversions.h.

void mav_msgs::EigenMavStateFromEigenTrajectoryPoint ( const Eigen::Vector3d &  acceleration,
const Eigen::Vector3d &  jerk,
const Eigen::Vector3d &  snap,
double  yaw,
double  yaw_rate,
double  yaw_acceleration,
double  magnitude_of_gravity,
Eigen::Quaterniond *  orientation,
Eigen::Vector3d *  acceleration_body,
Eigen::Vector3d *  angular_velocity_body,
Eigen::Vector3d *  angular_acceleration_body 
)
inline

Computes the MAV state (position, velocity, attitude, angular velocity, angular acceleration) from the flat state. Additionally, computes the acceleration expressed in body coordinates, i.e. the acceleration measured by the IMU. No air-drag is assumed here.

Parameters
[in]accelerationAcceleration of the MAV, expressed in world coordinates.
[in]jerkJerk of the MAV, expressed in world coordinates.
[in]snapSnap of the MAV, expressed in world coordinates.
[in]yawYaw angle of the MAV, expressed in world coordinates.
[in]yaw_rateYaw rate, expressed in world coordinates.
[in]yaw_accelerationYaw acceleration, expressed in world coordinates.
[in]magnitude_of_gravityMagnitude of the gravity vector.
[out]orientationQuaternion representing the attitude of the MAV.
[out]acceleration_bodyAcceleration expressed in body coordinates, i.e. the acceleration usually by the IMU.
[out]angular_velocity_bodyAngular velocity of the MAV, expressed in body coordinates.
[out]angular_acceleration_bodyAngular acceleration of the MAV, expressed in body coordinates.

Definition at line 253 of file conversions.h.

void mav_msgs::EigenMavStateFromEigenTrajectoryPoint ( const Eigen::Vector3d &  acceleration,
const Eigen::Vector3d &  jerk,
const Eigen::Vector3d &  snap,
double  yaw,
double  yaw_rate,
double  yaw_acceleration,
Eigen::Quaterniond *  orientation,
Eigen::Vector3d *  acceleration_body,
Eigen::Vector3d *  angular_velocity_body,
Eigen::Vector3d *  angular_acceleration_body 
)
inline

Convenience function with default value for the magnitude of the gravity vector.

Definition at line 199 of file conversions.h.

void mav_msgs::EigenMavStateFromEigenTrajectoryPoint ( const EigenTrajectoryPoint trajectory_point,
double  magnitude_of_gravity,
EigenMavState mav_state 
)
inline

Convenience function with EigenTrajectoryPoint as input and EigenMavState as output.

Definition at line 213 of file conversions.h.

void mav_msgs::EigenMavStateFromEigenTrajectoryPoint ( const EigenTrajectoryPoint flat_state,
EigenMavState mav_state 
)
inline

Convenience function with EigenTrajectoryPoint as input and EigenMavState as output with default value for the magnitude of the gravity vector.

Definition at line 248 of file conversions.h.

void mav_msgs::eigenOdometryFromMsg ( const nav_msgs::Odometry &  msg,
EigenOdometry odometry 
)
inline

Definition at line 105 of file conversions.h.

void mav_msgs::eigenRateThrustFromMsg ( const RateThrust &  msg,
EigenRateThrust rate_thrust 
)
inline

Definition at line 78 of file conversions.h.

void mav_msgs::eigenRollPitchYawrateThrustFromMsg ( const RollPitchYawrateThrust &  msg,
EigenRollPitchYawrateThrust roll_pitch_yawrate_thrust 
)
inline

Definition at line 94 of file conversions.h.

void mav_msgs::eigenTorqueThrustFromMsg ( const TorqueThrust &  msg,
EigenTorqueThrust torque_thrust 
)
inline

Definition at line 86 of file conversions.h.

void mav_msgs::eigenTrajectoryPointDequeFromMsg ( const trajectory_msgs::MultiDOFJointTrajectory &  msg,
EigenTrajectoryPointDeque *  trajectory 
)
inline

Definition at line 380 of file conversions.h.

void mav_msgs::eigenTrajectoryPointFromMsg ( const trajectory_msgs::MultiDOFJointTrajectoryPoint &  msg,
EigenTrajectoryPoint trajectory_point 
)
inline

Definition at line 326 of file conversions.h.

void mav_msgs::eigenTrajectoryPointFromPoseMsg ( const geometry_msgs::Pose &  msg,
EigenTrajectoryPoint trajectory_point 
)
inline

Definition at line 142 of file conversions.h.

void mav_msgs::eigenTrajectoryPointFromPoseMsg ( const geometry_msgs::PoseStamped &  msg,
EigenTrajectoryPoint trajectory_point 
)
inline

Definition at line 156 of file conversions.h.

void mav_msgs::eigenTrajectoryPointFromTransformMsg ( const geometry_msgs::TransformStamped &  msg,
EigenTrajectoryPoint trajectory_point 
)
inline

Definition at line 121 of file conversions.h.

void mav_msgs::eigenTrajectoryPointVectorFromMsg ( const trajectory_msgs::MultiDOFJointTrajectory &  msg,
EigenTrajectoryPointVector *  trajectory 
)
inline

Definition at line 368 of file conversions.h.

void mav_msgs::getEulerAnglesFromQuaternion ( const Eigen::Quaternion< double > &  q,
Eigen::Vector3d *  euler_angles 
)
inline

Definition at line 134 of file common.h.

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 
)
inline

Definition at line 334 of file common.h.

bool mav_msgs::isRotationMatrix ( const Eigen::Matrix3d &  mat)
inline

Definition at line 167 of file common.h.

double mav_msgs::MagnitudeOfGravity ( const double  height,
const double  latitude_radians 
)
inline

Magnitude of Earth's gravitational field at specific height [m] and latitude [rad] (from wikipedia).

Definition at line 39 of file common.h.

void mav_msgs::matrixFromRotationVector ( const Eigen::Vector3d &  vec,
Eigen::Matrix3d *  mat 
)
inline

Definition at line 184 of file common.h.

void mav_msgs::msgActuatorsFromEigen ( const EigenActuators actuators,
Actuators *  msg 
)
inline

Definition at line 394 of file conversions.h.

void mav_msgs::msgAttitudeThrustFromEigen ( const EigenAttitudeThrust attitude_thrust,
AttitudeThrust *  msg 
)
inline

Definition at line 414 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryFromEigen ( const EigenTrajectoryPoint trajectory_point,
const std::string &  link_name,
trajectory_msgs::MultiDOFJointTrajectory *  msg 
)
inline

Definition at line 494 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryFromEigen ( const EigenTrajectoryPoint trajectory_point,
trajectory_msgs::MultiDOFJointTrajectory *  msg 
)
inline

Definition at line 507 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryFromEigen ( const EigenTrajectoryPointVector &  trajectory,
const std::string &  link_name,
trajectory_msgs::MultiDOFJointTrajectory *  msg 
)
inline

Definition at line 526 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryFromEigen ( const EigenTrajectoryPointVector &  trajectory,
trajectory_msgs::MultiDOFJointTrajectory *  msg 
)
inline

Definition at line 547 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryFromEigen ( const EigenTrajectoryPointDeque &  trajectory,
const std::string &  link_name,
trajectory_msgs::MultiDOFJointTrajectory *  msg 
)
inline

Definition at line 553 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryFromEigen ( const EigenTrajectoryPointDeque &  trajectory,
trajectory_msgs::MultiDOFJointTrajectory *  msg 
)
inline

Definition at line 574 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryFromPositionYaw ( const Eigen::Vector3d &  position,
double  yaw,
trajectory_msgs::MultiDOFJointTrajectory *  msg 
)
inline

Definition at line 514 of file conversions.h.

void mav_msgs::msgMultiDofJointTrajectoryPointFromEigen ( const EigenTrajectoryPoint trajectory_point,
trajectory_msgs::MultiDOFJointTrajectoryPoint *  msg 
)
inline

Definition at line 471 of file conversions.h.

void mav_msgs::msgOdometryFromEigen ( const EigenOdometry odometry,
nav_msgs::Odometry *  msg 
)
inline

Definition at line 445 of file conversions.h.

void mav_msgs::msgPoseStampedFromEigenTrajectoryPoint ( const EigenTrajectoryPoint trajectory_point,
geometry_msgs::PoseStamped *  msg 
)
inline

Definition at line 460 of file conversions.h.

void mav_msgs::msgRateThrustFromEigen ( EigenRateThrust rate_thrust,
RateThrust *  msg 
)
inline

Definition at line 421 of file conversions.h.

void mav_msgs::msgRollPitchYawrateThrustFromEigen ( const EigenRollPitchYawrateThrust roll_pitch_yawrate_thrust,
RollPitchYawrateThrust *  msg 
)
inline

Definition at line 435 of file conversions.h.

void mav_msgs::msgTorqueThrustFromEigen ( EigenTorqueThrust torque_thrust,
TorqueThrust *  msg 
)
inline

Definition at line 428 of file conversions.h.

double mav_msgs::nanosecondsToSeconds ( int64_t  nanoseconds)
inline

Definition at line 349 of file common.h.

Eigen::Vector3d mav_msgs::omegaDotFromRotationVector ( const Eigen::Vector3d &  rot_vec,
const Eigen::Vector3d &  rot_vec_vel,
const Eigen::Vector3d &  rot_vec_acc 
)
inline

Definition at line 269 of file common.h.

Eigen::Vector3d mav_msgs::omegaFromRotationVector ( const Eigen::Vector3d &  rot_vec,
const Eigen::Vector3d &  rot_vec_vel 
)
inline

Definition at line 242 of file common.h.

EigenTrajectoryPoint mav_msgs::operator* ( const Eigen::Affine3d &  lhs,
const EigenTrajectoryPoint rhs 
)
inline

Definition at line 267 of file eigen_mav_msgs.h.

void mav_msgs::pointEigenToMsg ( const Eigen::Vector3d &  eigen,
geometry_msgs::Point *  msg 
)
inline

Definition at line 84 of file common.h.

void mav_msgs::quaternionEigenToMsg ( const Eigen::Quaterniond &  eigen,
geometry_msgs::Quaternion *  msg 
)
inline

Definition at line 92 of file common.h.

Eigen::Quaterniond mav_msgs::quaternionFromMsg ( const geometry_msgs::Quaternion &  msg)
inline

Definition at line 63 of file common.h.

Eigen::Quaterniond mav_msgs::quaternionFromYaw ( double  yaw)
inline

Definition at line 112 of file common.h.

int64_t mav_msgs::secondsToNanoseconds ( double  seconds)
inline

Definition at line 354 of file common.h.

void mav_msgs::setAngularVelocityMsgFromYawRate ( double  yaw_rate,
geometry_msgs::Vector3 *  msg 
)
inline

Definition at line 126 of file common.h.

void mav_msgs::setQuaternionMsgFromYaw ( double  yaw,
geometry_msgs::Quaternion *  msg 
)
inline

Definition at line 116 of file common.h.

void mav_msgs::skewMatrixFromVector ( const Eigen::Vector3d &  vec,
Eigen::Matrix3d *  vec_skew 
)
inline

Definition at line 147 of file common.h.

Eigen::Vector3d mav_msgs::vector3FromMsg ( const geometry_msgs::Vector3 &  msg)
inline

Definition at line 55 of file common.h.

Eigen::Vector3d mav_msgs::vector3FromPointMsg ( const geometry_msgs::Point &  msg)
inline

Definition at line 59 of file common.h.

void mav_msgs::vectorEigenToMsg ( const Eigen::Vector3d &  eigen,
geometry_msgs::Vector3 *  msg 
)
inline

Definition at line 76 of file common.h.

bool mav_msgs::vectorFromRotationMatrix ( const Eigen::Matrix3d &  mat,
Eigen::Vector3d *  vec 
)
inline

Definition at line 202 of file common.h.

bool mav_msgs::vectorFromSkewMatrix ( const Eigen::Matrix3d &  vec_skew,
Eigen::Vector3d *  vec 
)
inline

Definition at line 154 of file common.h.

double mav_msgs::yawFromQuaternion ( const Eigen::Quaterniond &  q)
inline

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''.

Definition at line 107 of file common.h.

Variable Documentation

const double mav_msgs::kGravity = MagnitudeOfGravity(kZurichHeight, kZurichLatitude)

Definition at line 30 of file default_values.h.

const double mav_msgs::kNumNanosecondsPerSecond = 1.e9

Definition at line 35 of file common.h.

const double mav_msgs::kSmallValueCheck = 1.e-6

Definition at line 34 of file common.h.

const double mav_msgs::kZurichHeight = 405.94

Definition at line 29 of file default_values.h.

const double mav_msgs::kZurichLatitude = 0.8267

Definition at line 28 of file default_values.h.



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 Thu Jan 23 2020 03:14:00