改发送
This commit is contained in:
parent
bac96f42e6
commit
5207a45727
@ -25,6 +25,10 @@ extern "C" {
|
||||
#define M_PI 3.14159265358979323846f
|
||||
#endif
|
||||
|
||||
#ifndef M_PI_2
|
||||
#define M_PI_2 1.57079632679489661923f
|
||||
#endif
|
||||
|
||||
#ifndef M_2PI
|
||||
#define M_2PI 6.28318530717958647692f
|
||||
#endif
|
||||
|
||||
@ -6,6 +6,7 @@
|
||||
/* Includes ----------------------------------------------------------------- */
|
||||
#include "task/user_task.h"
|
||||
/* USER INCLUDE BEGIN */
|
||||
#include "component/user_math.h"
|
||||
#include "bsp/can.h"
|
||||
#include "bsp/time.h"
|
||||
#include "component/ahrs.h"
|
||||
@ -26,12 +27,12 @@
|
||||
#define ACCEL_CAN_MIN (-58.8f)
|
||||
#define GYRO_CAN_MAX (34.88f)
|
||||
#define GYRO_CAN_MIN (-34.88f)
|
||||
#define PITCH_CAN_MAX (90.0f)
|
||||
#define PITCH_CAN_MIN (-90.0f)
|
||||
#define ROLL_CAN_MAX (180.0f)
|
||||
#define ROLL_CAN_MIN (-180.0f)
|
||||
#define YAW_CAN_MAX (180.0f)
|
||||
#define YAW_CAN_MIN (-180.0f)
|
||||
#define PITCH_CAN_MAX (M_PI_2) /* π/2 弧度 ≈ 90° */
|
||||
#define PITCH_CAN_MIN (-M_PI_2) /* -π/2 弧度 ≈ -90° */
|
||||
#define ROLL_CAN_MAX (M_2PI)
|
||||
#define ROLL_CAN_MIN (-M_2PI)
|
||||
#define YAW_CAN_MAX (M_2PI)
|
||||
#define YAW_CAN_MIN (-M_PI_2) /* -π 弧度 ≈ -180° */
|
||||
#define QUATERNION_MIN (-1.0f)
|
||||
#define QUATERNION_MAX (1.0f)
|
||||
|
||||
|
||||
Loading…
Reference in New Issue
Block a user