forked from Archive/PX4-Autopilot
Add pitch angle to AK8963 for Bebop
This commit is contained in:
parent
bc44ba2907
commit
6bb03f3665
|
@ -17,9 +17,9 @@ param set MC_YAWRATE_P 0.05
|
|||
param set MC_YAWRATE_I 0.001
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.7
|
||||
#df_ms5607_wrapper start
|
||||
df_ms5607_wrapper start
|
||||
df_mpu6050_wrapper start -R 8
|
||||
df_ak8963_wrapper start -R 4
|
||||
df_ak8963_wrapper start -R 32
|
||||
sensors start
|
||||
commander start
|
||||
attitude_estimator_q start
|
||||
|
|
|
@ -255,5 +255,15 @@ rotate_3f(enum Rotation rot, float &x, float &y, float &z)
|
|||
y = z; z = -tmp;
|
||||
return;
|
||||
}
|
||||
|
||||
case ROTATION_PITCH_9_YAW_180: {
|
||||
float tmpx = x;
|
||||
float tmpy = y;
|
||||
float tmpz = z;
|
||||
x = -0.987688f * tmpx + 0.000000f * tmpy + -0.156434f * tmpz;
|
||||
y = 0.000000f * tmpx + -1.000000f * tmpy + 0.000000f * tmpz;
|
||||
z = -0.156434f * tmpx + 0.000000f * tmpy + 0.987688f * tmpz;
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -80,6 +80,7 @@ enum Rotation {
|
|||
ROTATION_PITCH_90_ROLL_90 = 29,
|
||||
ROTATION_YAW_293_PITCH_68_ROLL_90 = 30,
|
||||
ROTATION_PITCH_90_ROLL_270 = 31,
|
||||
ROTATION_PITCH_9_YAW_180 = 32,
|
||||
ROTATION_MAX
|
||||
};
|
||||
|
||||
|
@ -122,6 +123,7 @@ const rot_lookup_t rot_lookup[] = {
|
|||
{ 90, 90, 0 },
|
||||
{ 90, 68, 293 },
|
||||
{270, 90, 0 },
|
||||
{ 0, 9, 180 },
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
Loading…
Reference in New Issue