RflySimSDK v3.05
RflySimSDK说明文档
载入中...
搜索中...
未找到
mavlink_conversions.h 文件参考
#include <math.h>
+ mavlink_conversions.h 的引用(Include)关系图:
+ 此图展示该文件被哪些文件直接或间接地引用了:

浏览该文件的源代码.

宏定义

#define M_PI_2   ((float)asin(1))
 

函数

MAVLINK_HELPER void mavlink_quaternion_to_dcm (const float quaternion[4], float dcm[3][3])
 
MAVLINK_HELPER void mavlink_dcm_to_euler (const float dcm[3][3], float *roll, float *pitch, float *yaw)
 
MAVLINK_HELPER void mavlink_quaternion_to_euler (const float quaternion[4], float *roll, float *pitch, float *yaw)
 
MAVLINK_HELPER void mavlink_euler_to_quaternion (float roll, float pitch, float yaw, float quaternion[4])
 
MAVLINK_HELPER void mavlink_dcm_to_quaternion (const float dcm[3][3], float quaternion[4])
 
MAVLINK_HELPER void mavlink_euler_to_dcm (float roll, float pitch, float yaw, float dcm[3][3])
 

详细描述

These conversion functions follow the NASA rotation standards definition file available online.

Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the protocol as widely as possible.

作者
James Goppert
Thomas Gubler thoma.nosp@m.sgub.nosp@m.ler@g.nosp@m.mail.nosp@m..com

函数说明

◆ mavlink_dcm_to_euler()

MAVLINK_HELPER void mavlink_dcm_to_euler ( const float dcm[3][3],
float * roll,
float * pitch,
float * yaw )

Converts a rotation matrix to euler angles

参数
dcma 3x3 rotation matrix
rollthe roll angle in radians
pitchthe pitch angle in radians
yawthe yaw angle in radians
+ 这是这个函数的调用关系图:

◆ mavlink_dcm_to_quaternion()

MAVLINK_HELPER void mavlink_dcm_to_quaternion ( const float dcm[3][3],
float quaternion[4] )

Converts a rotation matrix to a quaternion Reference:

参数
dcma 3x3 rotation matrix
quaterniona [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)

◆ mavlink_euler_to_dcm()

MAVLINK_HELPER void mavlink_euler_to_dcm ( float roll,
float pitch,
float yaw,
float dcm[3][3] )

Converts euler angles to a rotation matrix

参数
rollthe roll angle in radians
pitchthe pitch angle in radians
yawthe yaw angle in radians
dcma 3x3 rotation matrix

◆ mavlink_euler_to_quaternion()

MAVLINK_HELPER void mavlink_euler_to_quaternion ( float roll,
float pitch,
float yaw,
float quaternion[4] )

Converts euler angles to a quaternion

参数
rollthe roll angle in radians
pitchthe pitch angle in radians
yawthe yaw angle in radians
quaterniona [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)

◆ mavlink_quaternion_to_dcm()

MAVLINK_HELPER void mavlink_quaternion_to_dcm ( const float quaternion[4],
float dcm[3][3] )

Converts a quaternion to a rotation matrix

参数
quaterniona [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
dcma 3x3 rotation matrix
+ 这是这个函数的调用关系图:

◆ mavlink_quaternion_to_euler()

MAVLINK_HELPER void mavlink_quaternion_to_euler ( const float quaternion[4],
float * roll,
float * pitch,
float * yaw )

Converts a quaternion to euler angles

参数
quaterniona [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
rollthe roll angle in radians
pitchthe pitch angle in radians
yawthe yaw angle in radians
+ 函数调用图: