概述
LSM6DSV16X包含三軸陀螺儀與三軸加速度計(jì)。
姿態(tài)有多種數(shù)學(xué)表示方式,常見的是四元數(shù),歐拉角,矩陣和軸角。他們各自有其自身的優(yōu)點(diǎn),在不同的領(lǐng)域使用不同的表示方式。在四軸飛行器中使用到了四元數(shù)和歐拉角。
姿態(tài)解算選用的旋轉(zhuǎn)順序?yàn)閆YX,即IMU坐標(biāo)系初始時(shí)刻與大地坐標(biāo)系重合,然后依次繞自己的Z、Y、X軸進(jìn)行旋轉(zhuǎn):
繞IMU的Z軸旋轉(zhuǎn):航向角yaw
繞IMU的Y軸旋轉(zhuǎn):俯仰角pitch
繞IMU的X軸旋轉(zhuǎn):橫滾角row
最近在弄ST和瑞薩RA的課程,需要樣片的可以加群申請(qǐng):615061293 。
橫滾roll,俯仰pitch,偏航y(tǒng)aw的實(shí)際含義如下圖:
由于需要解析姿態(tài)角,故將陀螺儀速度修改快一點(diǎn)。
視頻教學(xué)
https://www.bilibili.com/video/BV18M411d7Wg/
樣品申請(qǐng)
https://www.wjx.top/vm/OhcKxJk.aspx#
完整代碼下載
https://download.csdn.net/download/qq_24312945/88598263
歐拉角
橫滾角φ:機(jī)體繞OBXB轉(zhuǎn)動(dòng),軸Y'B與平面OBXBYB構(gòu)成的夾角。
俯仰角θ:機(jī)體繞OBYB轉(zhuǎn)動(dòng),軸Z'B與平面OBYBZB構(gòu)成的夾角。
偏航角ψ:機(jī)體繞OBZB轉(zhuǎn)動(dòng),軸X'B與平面OBXBZB構(gòu)成的夾角。
將姿態(tài)角從機(jī)體坐標(biāo)系轉(zhuǎn)換到慣性坐標(biāo)系中是為了便于分析無人機(jī)狀態(tài),反映無人機(jī)在慣性坐標(biāo)系下的姿態(tài)運(yùn)動(dòng)狀態(tài),利用齊次線性變換可實(shí)現(xiàn)坐標(biāo)系的轉(zhuǎn)換,旋轉(zhuǎn)矩陣就是在線性變化中產(chǎn)生的,用REB表示慣性坐標(biāo)系{E}到機(jī)體坐標(biāo)系{B}的變換。
例如,繞OBXB旋轉(zhuǎn)必角,此時(shí)兩個(gè)坐標(biāo)系存在必的角度差,不再重合。點(diǎn)(x, y, z)的轉(zhuǎn)換方程為:
可提取轉(zhuǎn)換矩陣:
同理,繞口OBYB旋轉(zhuǎn)θ角得:
而繞OBZB旋轉(zhuǎn)ψ角得:
不同旋轉(zhuǎn)順序有不同的旋轉(zhuǎn)矩陣,按照偏航,俯仰,橫滾的順序,即分別繞X-Y-Z旋轉(zhuǎn),就可計(jì)算出旋轉(zhuǎn)矩陣REB,REB等于依次旋轉(zhuǎn)所得的矩陣連乘,且順序?yàn)閺挠蚁蜃笈帕小?/p>
萬向節(jié)死鎖
當(dāng)俯仰角θ=±Π/2時(shí),橫滾運(yùn)動(dòng)與偏航運(yùn)動(dòng)的旋轉(zhuǎn)軸重合,出現(xiàn)萬向節(jié)死鎖現(xiàn)象,在空間失去了一個(gè)自由度。如式所示,φ或ψ的變化具有相同的效果,因此不再具有唯一性啊。
四元數(shù)法
本文選擇的是四元數(shù)法進(jìn)行姿態(tài)解算。無人機(jī)姿態(tài)解算方法主要有四種,它們各自的優(yōu)缺點(diǎn)如下圖所示。歐拉角法不能用于計(jì)算飛行器的全姿態(tài)角,且難以實(shí)時(shí)計(jì)算而不易于工程應(yīng)用。方向余弦法不會(huì)出現(xiàn)“奇點(diǎn)”現(xiàn)象,但計(jì)算量大,效率低。四元數(shù)法避免了復(fù)雜的三角函數(shù)運(yùn)算,變?yōu)榍蠼饩€性微分方程,算法簡(jiǎn)單易操作,且不存在角度奇異性問題,可以更好的線性化系統(tǒng),是一種更實(shí)用的工程方法。
四元數(shù)的概念誕生在1843年的愛爾蘭,是數(shù)學(xué)家哈密頓研究空間幾何時(shí)提出。在如今的導(dǎo)航技術(shù)領(lǐng)域,四元數(shù)的優(yōu)勢(shì)逐漸被發(fā)現(xiàn),得到了研究者們的廣泛關(guān)注,并逐漸應(yīng)用在姿態(tài)解算領(lǐng)域。
四元數(shù)是由四個(gè)元構(gòu)成的數(shù)Q(q0,q1,q2,q3) = q0 + q1i + q2j + q3k;其中,q0,q1,q2,q3是實(shí)數(shù),i,j,k既是互相正交的單位向量,又是虛單位根號(hào)-1。四元數(shù)即可看作四維空間中的一個(gè)向量,又可以看做一個(gè)超復(fù)數(shù)。對(duì)于后續(xù)有一個(gè)重要的變化需要記?。?br /> Q=q0 + q1i + q2j + q3k
可視為一個(gè)超復(fù)數(shù),Q 的共軛復(fù)數(shù)記為
Q'=q0 - q1i - q2j - q3k
Q°稱為Q的共軛四元數(shù)。
同時(shí),有
ij=k,jk=i,ki=j,ji=-k,kj=-i,ik=-j
i2 = j2 = k2 =ijk=-1
其中,i、j、k是相互正交的單位向量,其幾何意義可理解為分別繞三個(gè)坐標(biāo)軸的旋轉(zhuǎn),q0、q1、q2、q3為常數(shù),有
通過四元數(shù)進(jìn)行歐拉角求解,可以減少芯片運(yùn)算負(fù)擔(dān),提高運(yùn)算速度。
一個(gè)矢量V相對(duì)于坐標(biāo)系OXYZ固定:V = xi + yj + zk;坐標(biāo)系OXYZ轉(zhuǎn)動(dòng)了Q得到一個(gè)新坐標(biāo)系OX’Y’Z’:V = x’i’ + y’j‘ + z’k’;設(shè)四元數(shù)Ve、Ve‘
Ve = xi + yj + zk;
Ve’ = x’i + y’j + z’k;
則Ve’ = Q* Ve * Q';
設(shè)Q = q0 + q1i + q2j + q3k;則Q' = q0 - q1i - q2j - q3k;
則Ve’ = Q* Ve * Q'=(q0 + q1i + q2j + q3k) * (0+xi + yj + zk) + (q0 - q1i - q2j - q3k)
可以算出
x’=(q0 ^2+q1 ^2-q2 ^2-q3 ^2)x+2(q1q2+ q1q3)y+2(q1q3-q0q2)z
y’ = 2(q1q2-q0q3)x+(q0 ^2-q1 ^2+q2 ^2-q3 ^2)y+2(q2q3+q0q1)z
z’ = 2(q1q3+q0q2)x+2(q2q3-q0q1)y+(q0 ^2-q1 ^2-q2 ^2+q3 ^2)z
結(jié)合
可以反推
Pitch = asin(2 * q2 * q3 + 2 * q0* q1)* 57.3; // pitch ,轉(zhuǎn)換為度數(shù)
Roll = atan2(-2 * q1 * q3 + 2 * q0 * q2, q0*q0-q1*q1-q2*q2+q3*q3)* 57.3; // rollv
Yaw = atan2(2*(q1*q2 - q0*q3),q0*q0-q1*q1+q2*q2-q3*q3) * 57.3; //偏移太大,
將加速度的三維向量轉(zhuǎn)為單位向量
// 測(cè)量正?;?/span>
norm = sqrt(ax*ax + ay*ay + az*az);
ax = ax / norm; //單位化
ay = ay / norm;
az = az / norm;
世界坐標(biāo)系重力分向量是通過方向旋轉(zhuǎn)矩陣的最后一列的三個(gè)元素乘上加速度就可以算出機(jī)體坐標(biāo)系中的重力向量。
// 估計(jì)方向的重力
vx = 2*(q1*q3 - q0*q2);//由下向上方向的加速度在加速度計(jì)X分量
vy = 2*(q0*q1 + q2*q3);//由下向上方向的加速度在加速度計(jì)X分量
vz = q0*q0 - q1*q1 - q2*q2 + q3*q3;//由下向上方向的加速度在加速度計(jì)Z分量
姿態(tài)解算
雙環(huán)PI控制器
陀螺儀能夠迅速響應(yīng)設(shè)備的旋轉(zhuǎn),在短時(shí)間內(nèi)誤差較小且可靠。然而,因?yàn)闇囟绕?、零漂移和積分誤差會(huì)隨時(shí)間累積,陀螺儀的長時(shí)間精度受到影響。在靜止?fàn)顟B(tài)下,加速度計(jì)的漂移很小,其傾角求解過程中不存在積分誤差,但在飛行過程中,加速度計(jì)受到發(fā)動(dòng)機(jī)和機(jī)架振動(dòng)以及轉(zhuǎn)動(dòng)和運(yùn)動(dòng)加速度的干擾。磁羅盤測(cè)量的地磁向量在特定地理范圍內(nèi)可視為不變,但磁羅盤易受硬磁場(chǎng)和軟磁場(chǎng)干擾。
因此,若系統(tǒng)外環(huán)采用九軸姿態(tài)傳感器(包括三軸加速度計(jì)、三軸磁羅盤和三軸陀螺儀)進(jìn)行數(shù)據(jù)融合,磁羅盤易受干擾可能導(dǎo)致融合后的數(shù)據(jù)仍有較大誤差。為此,在內(nèi)環(huán)使用六軸姿態(tài)傳感器(包括三軸加速度計(jì)和三軸陀螺儀)進(jìn)行數(shù)據(jù)融合,對(duì)融合后的傳感器姿態(tài)偏差進(jìn)行二次修正,以提高整體精度。
外環(huán)九軸姿態(tài)傳感器數(shù)據(jù)融合,記在飛行器機(jī)體坐標(biāo)系下an=[ax ay az]T和mn=[mx my mz]T分別為加速度計(jì)和磁羅盤實(shí)際測(cè)量得到的重力向量和地磁向量。
記vn=[vx vy vz]T和wn=[mx my mz]T是將地理坐標(biāo)系下重力向量kb=[0 0 1g]T和地磁向量nb=[nx 0 nz]T(不考慮地理磁偏角因素,將機(jī)頭固定向北)通過四元數(shù)坐標(biāo)換算成機(jī)體坐標(biāo)系下的重力向量和地磁向量。向量之間的誤差為坐標(biāo)軸的旋轉(zhuǎn)誤差,可以用向量的叉積en=[ex ey ez]T表示,如下所示。
由于我的LSM6DS3TR-C為六軸,不帶三軸陀螺儀,故代碼如下。
//這個(gè)叉積向量仍舊是位于機(jī)體坐標(biāo)系上的,而陀螺積分誤差也是在機(jī)體坐標(biāo)系,而且叉積的大小與陀螺積分誤差成正比,正好拿來糾正陀螺。
//(你可以自己拿東西想象一下)由于陀螺是對(duì)機(jī)體直接積分,所以對(duì)陀螺的糾正量會(huì)直接體現(xiàn)在對(duì)機(jī)體坐標(biāo)系的糾正。
ex = (ay*vz - az*vy);
ey = (az*vx - ax*vz);
ez = (ax*vy - ay*vx);
由于陀螺儀是對(duì)機(jī)體直接積分,所以,陀螺儀的誤差可以體現(xiàn)為機(jī)體坐標(biāo)的誤差。因此修正坐標(biāo)軸的誤差可以達(dá)到修正陀螺儀誤差的目的,從而將加速度計(jì)和磁羅盤進(jìn)行修正陀螺儀,實(shí)現(xiàn)了九軸的數(shù)據(jù)融合。即如果陀螺儀按照叉積誤差的軸,轉(zhuǎn)動(dòng)叉積誤差的角度,就可以消除機(jī)體坐標(biāo)上實(shí)際測(cè)量的重力向量和地磁向量和坐標(biāo)換算后的重力向量和地磁向量之間的誤差。
PI調(diào)節(jié)器的比例部分用于迅速糾正陀螺儀誤差,積分部分用于消除穩(wěn)態(tài)偏差。PI調(diào)節(jié)器的比例系數(shù)和積分系數(shù)自己去修正。陀螺儀經(jīng)過外環(huán)PI控制器修正姿態(tài)誤差后輸出值為了gn =[gx gy gz]T
// 積分誤差比例積分增益,計(jì)算陀螺儀測(cè)量的重力向量與估計(jì)方向的重力向量之間的誤差。
exInt = exInt + ex*Ki;
eyInt = eyInt + ey*Ki;
ezInt = ezInt + ez*Ki;
// 調(diào)整后的陀螺儀測(cè)量,使用叉積誤差來進(jìn)行比例-積分(PI)修正陀螺儀的零偏。將修正量乘以比例增益Kp,并加上之前計(jì)算的積分誤差exInt、eyInt和ezInt。
gx = gx + Kp*ex + exInt;
gy = gy + Kp*ey + eyInt;
gz = gz + Kp*ez + ezInt;
內(nèi)環(huán)的六軸姿態(tài)傳感器數(shù)據(jù)融合是將地理坐標(biāo)系下的重力場(chǎng)向量與加速度計(jì)在機(jī)體坐標(biāo)系下采集到的重力向量進(jìn)行叉乘,求出兩者向量誤差。并通過PI控制器修正向量誤差,從而達(dá)到修正外環(huán)九軸數(shù)據(jù)融合后的陀螺儀的偏差的目的。在每個(gè)姿態(tài)解算周期讀取出機(jī)體坐標(biāo)系下雙環(huán)PI控制后的陀螺儀的角速率
整合四元數(shù)率和正?;?根據(jù)陀螺儀的測(cè)量值和比例-積分修正值,對(duì)四元數(shù)進(jìn)行更新。
// 整合四元數(shù)率和正?;?根據(jù)陀螺儀的測(cè)量值和比例-積分修正值,對(duì)四元數(shù)進(jìn)行更新。根據(jù)微分方程的離散化形式,將四元數(shù)的每個(gè)分量加上相應(yīng)的微分項(xiàng)乘以采樣周期的一半(halfT)。
q0 = q0 + (-q1*gx - q2*gy - q3*gz)*halfT;
q1 = q1 + (q0*gx + q2*gz - q3*gy)*halfT;
q2 = q2 + (q0*gy - q1*gz + q3*gx)*halfT;
q3 = q3 + (q0*gz + q1*gy - q2*gx)*halfT;
// 正常化四元數(shù)
norm = sqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3);
q0 = q0 / norm;
q1 = q1 / norm;
q2 = q2 / norm;
q3 = q3 / norm;
偏航角
六軸傳感器(包括三軸加速度計(jì)和三軸陀螺儀)可以用于估算設(shè)備在空間中的姿態(tài),包括俯仰角(Pitch)、橫滾角(Roll)和偏航角(Yaw)。然而,六軸傳感器僅依賴陀螺儀和加速度計(jì)數(shù)據(jù),可能無法準(zhǔn)確測(cè)量偏航角(Yaw),原因如下:
無磁場(chǎng)參考:六軸傳感器缺少磁羅盤,沒有固定的參考方向。因此,在長時(shí)間內(nèi),陀螺儀的積分誤差可能導(dǎo)致偏航角估計(jì)漂移。
陀螺儀誤差累積:陀螺儀測(cè)量的是角速度,要得到偏航角,需要將角速度積分。由于陀螺儀存在零漂、噪聲和溫度漂移等誤差,這些誤差在積分過程中會(huì)累積,使得偏航角估計(jì)產(chǎn)生較大的漂移。
雖然六軸傳感器可能無法準(zhǔn)確測(cè)量偏航角,但可以通過將其與磁羅盤(三軸磁場(chǎng)傳感器)結(jié)合,形成九軸傳感器(包括三軸加速度計(jì)、三軸磁羅盤和三軸陀螺儀),以提高偏航角估計(jì)的準(zhǔn)確性。九軸傳感器融合了磁場(chǎng)信息,為偏航角提供了一個(gè)穩(wěn)定的參考方向,有助于減小陀螺儀誤差對(duì)偏航角估計(jì)的影響。
陀螺儀解析代碼
//加速度單位g,陀螺儀rad/s
void IMUupdate(float gx, float gy, float gz, float ax, float ay, float az)
{
float norm;
float vx, vy, vz;
float ex, ey, ez;
// 測(cè)量正?;?把加計(jì)的三維向量轉(zhuǎn)成單位向量。
norm = sqrt(ax*ax + ay*ay + az*az);
ax = ax / norm; //單位化
ay = ay / norm;
az = az / norm;
// 估計(jì)方向的重力,世界坐標(biāo)系重力分向量是通過方向旋轉(zhuǎn)矩陣的最后一列的三個(gè)元素乘上加速度就可以算出機(jī)體坐標(biāo)系中的重力向量。
vx = 2*(q1*q3 - q0*q2);//由下向上方向的加速度在加速度計(jì)X分量
vy = 2*(q0*q1 + q2*q3);//由下向上方向的加速度在加速度計(jì)X分量
vz = q0*q0 - q1*q1 - q2*q2 + q3*q3;//由下向上方向的加速度在加速度計(jì)Z分量
//這個(gè)叉積向量仍舊是位于機(jī)體坐標(biāo)系上的,而陀螺積分誤差也是在機(jī)體坐標(biāo)系,而且叉積的大小與陀螺積分誤差成正比,正好拿來糾正陀螺。
//(你可以自己拿東西想象一下)由于陀螺是對(duì)機(jī)體直接積分,所以對(duì)陀螺的糾正量會(huì)直接體現(xiàn)在對(duì)機(jī)體坐標(biāo)系的糾正。
ex = (ay*vz - az*vy);
ey = (az*vx - ax*vz);
ez = (ax*vy - ay*vx);
// 積分誤差比例積分增益,計(jì)算陀螺儀測(cè)量的重力向量與估計(jì)方向的重力向量之間的誤差。
exInt = exInt + ex*Ki;
eyInt = eyInt + ey*Ki;
ezInt = ezInt + ez*Ki;
// 調(diào)整后的陀螺儀測(cè)量,使用叉積誤差來進(jìn)行比例-積分(PI)修正陀螺儀的零偏。將修正量乘以比例增益Kp,并加上之前計(jì)算的積分誤差exInt、eyInt和ezInt。
gx = gx + Kp*ex + exInt;
gy = gy + Kp*ey + eyInt;
gz = gz + Kp*ez + ezInt;
// 整合四元數(shù)率和正常化,根據(jù)陀螺儀的測(cè)量值和比例-積分修正值,對(duì)四元數(shù)進(jìn)行更新。根據(jù)微分方程的離散化形式,將四元數(shù)的每個(gè)分量加上相應(yīng)的微分項(xiàng)乘以采樣周期的一半(halfT)。
q0 = q0 + (-q1*gx - q2*gy - q3*gz)*halfT;
q1 = q1 + (q0*gx + q2*gz - q3*gy)*halfT;
q2 = q2 + (q0*gy - q1*gz + q3*gx)*halfT;
q3 = q3 + (q0*gz + q1*gy - q2*gx)*halfT;
// 正?;脑獢?shù)
norm = sqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3);
q0 = q0 / norm;
q1 = q1 / norm;
q2 = q2 / norm;
q3 = q3 / norm;
Pitch = asin(2 * q2 * q3 + 2 * q0* q1)* 57.3; // pitch ,轉(zhuǎn)換為度數(shù)
Roll = atan2(-2 * q1 * q3 + 2 * q0 * q2, q0*q0-q1*q1-q2*q2+q3*q3)* 57.3; // rollv
Yaw = atan2(2*(q1*q2 - q0*q3),q0*q0-q1*q1+q2*q2-q3*q3) * 57.3; //偏移太大,等我找一個(gè)好用的
}
上位機(jī)通訊
這里使用的是匿名助手的上位機(jī)
[https://gitee.com/anotc/AnoAssistant]
有專門的通訊協(xié)議
串口通訊協(xié)議格式如下所示,需要注意傳輸為小端模式傳輸。
對(duì)應(yīng)的源地址和目標(biāo)地址分別為0xFD和0xFE。
我們只需要上報(bào)加速度和陀螺儀數(shù)據(jù),所以功能碼為0x01,數(shù)據(jù)長度為0x0D,需要主要為小端模式傳輸。
加速度演示
實(shí)測(cè)移動(dòng)模塊分別為X、Y、Z軸向下,可以看見數(shù)值基本上為1000mg。
陀螺儀工作方式
加速度計(jì)測(cè)量線性加速度,而陀螺儀測(cè)量角旋轉(zhuǎn)。為此,他們測(cè)量了科里奧利效應(yīng)產(chǎn)生的力。
陀螺儀是一種運(yùn)動(dòng)傳感器,能夠感測(cè)物體在一軸或多軸上的旋轉(zhuǎn)角速度。它能夠精確地感測(cè)自由空間中復(fù)雜的移動(dòng)動(dòng)作,因此成為追蹤物體移動(dòng)方位和旋轉(zhuǎn)動(dòng)作的必要設(shè)備。與加速計(jì)和電子羅盤不同,陀螺儀不需要依賴外部力量(如重力或磁場(chǎng)),可以自主地發(fā)揮其功能。因此,從理論上講,只使用陀螺儀就可以完成姿態(tài)導(dǎo)航的任務(wù)。
陀螺儀的每個(gè)通道檢測(cè)一個(gè)軸的旋轉(zhuǎn)。也就是說陀螺儀通過測(cè)量自身的旋轉(zhuǎn)狀態(tài),判斷出設(shè)備當(dāng)前運(yùn)動(dòng)狀態(tài),是向前、向后、向上、向下、向左還是向右呢,是加速(角速度)還是減速(角速度)呢,都可以實(shí)現(xiàn),但是要判斷出設(shè)備的方位(東西南北),陀螺儀就沒有辦法。
MEMS陀螺儀主要利用科里奧利力(旋轉(zhuǎn)物體在有徑向運(yùn)動(dòng)時(shí)所受到的切向力)原理,公開的微機(jī)械陀螺儀均采用振動(dòng)物體傳感角速度的概念,利用振動(dòng)來誘導(dǎo)和探測(cè)科里奧利力。
MEMS陀螺儀的核心是一個(gè)微加工機(jī)械單元,在設(shè)計(jì)上按照一個(gè)音叉機(jī)制共振運(yùn)動(dòng),通過科里奧利力原理把角速率轉(zhuǎn)換成一個(gè)特定感測(cè)結(jié)構(gòu)的位移。
兩個(gè)相同的質(zhì)量塊以方向相反的做水平震蕩。當(dāng)外部施加一個(gè)角速率,就會(huì)出現(xiàn)一個(gè)科氏力,力的方向垂直于質(zhì)量運(yùn)動(dòng)方向,如垂直方向箭頭所示。產(chǎn)生的科氏力使感測(cè)質(zhì)量發(fā)生位移,位移大小與所施加的角速率大小成正比,科氏力引起的電容變化即可計(jì)算出角速率大小。
科里奧利效應(yīng)指出,當(dāng)質(zhì)量 (m) 以速度 (v) 沿特定方向移動(dòng)并施加外部角速率 (Ω)(紅色箭頭)時(shí),科里奧利效應(yīng)會(huì)產(chǎn)生一個(gè)力(黃色箭頭),導(dǎo)致質(zhì)量垂直移動(dòng)。該位移的值與應(yīng)用的角速率直接相關(guān)。
/* USER CODE BEGIN 2 */
printf("123123123");
lsm6dsv16x_reset_t rst;
stmdev_ctx_t dev_ctx;
/* Initialize mems driver interface */
dev_ctx.write_reg = platform_write;
dev_ctx.read_reg = platform_read;
dev_ctx.handle = &SENSOR_BUS;
HAL_GPIO_WritePin(CS_GPIO_Port, CS_Pin, GPIO_PIN_SET);
HAL_GPIO_WritePin(SA0_GPIO_Port, SA0_Pin, GPIO_PIN_RESET);
/* Wait sensor boot time */
platform_delay(BOOT_TIME);
/* Check device ID */
lsm6dsv16x_device_id_get(&dev_ctx, &whoamI);
printf("LSM6DSV16X_ID=0x%x,whoamI=0x%x",LSM6DSV16X_ID,whoamI);
if (whoamI != LSM6DSV16X_ID)
while (1);
/* Restore default configuration */
lsm6dsv16x_reset_set(&dev_ctx, LSM6DSV16X_RESTORE_CTRL_REGS);
do {
lsm6dsv16x_reset_get(&dev_ctx, &rst);
} while (rst != LSM6DSV16X_READY);
/* Enable Block Data Update */
lsm6dsv16x_block_data_update_set(&dev_ctx, PROPERTY_ENABLE);
/* Set Output Data Rate.
* Selected data rate have to be equal or greater with respect
* with MLC data rate.
*/
lsm6dsv16x_xl_data_rate_set(&dev_ctx, LSM6DSV16X_ODR_AT_960Hz);
lsm6dsv16x_gy_data_rate_set(&dev_ctx, LSM6DSV16X_ODR_AT_960Hz);
/* Set full scale */
lsm6dsv16x_xl_full_scale_set(&dev_ctx, LSM6DSV16X_2g);
lsm6dsv16x_gy_full_scale_set(&dev_ctx, LSM6DSV16X_2000dps);
/* Configure filtering chain */
filt_settling_mask.drdy = PROPERTY_ENABLE;
filt_settling_mask.irq_xl = PROPERTY_ENABLE;
filt_settling_mask.irq_g = PROPERTY_ENABLE;
lsm6dsv16x_filt_settling_mask_set(&dev_ctx, filt_settling_mask);
lsm6dsv16x_filt_gy_lp1_set(&dev_ctx, PROPERTY_ENABLE);
lsm6dsv16x_filt_gy_lp1_bandwidth_set(&dev_ctx, LSM6DSV16X_GY_ULTRA_LIGHT);
lsm6dsv16x_filt_xl_lp2_set(&dev_ctx, PROPERTY_ENABLE);
lsm6dsv16x_filt_xl_lp2_bandwidth_set(&dev_ctx, LSM6DSV16X_XL_STRONG);
int16_t acc_int16[3] ={0,0,0};
int16_t gyr_int16[3] ={0,0,0};
float acc[3] = {0};
float gyr[3] = {0};
uint8_t data[21]={0};
data[0]=0xAB;//幀頭
data[1]=0xFD;//源地址
data[2]=0xFE;//目標(biāo)地址
data[3]=0x01;//功能碼ID
data[4]=0x0D;//數(shù)據(jù)長度LEN
data[5]=0x00;//數(shù)據(jù)長度LEN 13
uint8_t sumcheck = 0;
uint8_t addcheck = 0;
int16_t angular_rate_raw[3]={0,0,0}; //pitch,roll,yaw
uint8_t data_angular_rate_raw[16]={0};
data_angular_rate_raw[0]=0xAB;//幀頭
data_angular_rate_raw[1]=0xFD;//源地址
data_angular_rate_raw[2]=0xFE;//目標(biāo)地址
data_angular_rate_raw[3]=0x03;//功能碼ID
data_angular_rate_raw[4]=0x08;//數(shù)據(jù)長度LEN
data_angular_rate_raw[5]=0x00;//數(shù)據(jù)長度LEN 8
data_angular_rate_raw[6]=0x01;//mode = 1
data_angular_rate_raw[13]=0x00;//FUSION _STA:融合狀態(tài)
/* USER CODE END 2 */
主程序
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
lsm6dsv16x_data_ready_t drdy;
/* Read output only if new xl value is available */
lsm6dsv16x_flag_data_ready_get(&dev_ctx, &drdy);
if (drdy.drdy_xl) {
/* Read acceleration field data */
memset(data_raw_acceleration, 0x00, 3 * sizeof(int16_t));
lsm6dsv16x_acceleration_raw_get(&dev_ctx, data_raw_acceleration);
acceleration_mg[0] =
lsm6dsv16x_from_fs2_to_mg(data_raw_acceleration[0]);
acceleration_mg[1] =
lsm6dsv16x_from_fs2_to_mg(data_raw_acceleration[1]);
acceleration_mg[2] =
lsm6dsv16x_from_fs2_to_mg(data_raw_acceleration[2]);
// printf("Acceleration [mg]:%4.2ft%4.2ft%4.2frn",acceleration_mg[0], acceleration_mg[1], acceleration_mg[2]);
}
/* Read output only if new xl value is available */
if (drdy.drdy_gy) {
/* Read angular rate field data */
memset(data_raw_angular_rate, 0x00, 3 * sizeof(int16_t));
lsm6dsv16x_angular_rate_raw_get(&dev_ctx, data_raw_angular_rate);
angular_rate_mdps[0] =
lsm6dsv16x_from_fs2000_to_mdps(data_raw_angular_rate[0]);
angular_rate_mdps[1] =
lsm6dsv16x_from_fs2000_to_mdps(data_raw_angular_rate[1]);
angular_rate_mdps[2] =
lsm6dsv16x_from_fs2000_to_mdps(data_raw_angular_rate[2]);
// printf("Angular rate [mdps]:%4.2ft%4.2ft%4.2frn",angular_rate_mdps[0], angular_rate_mdps[1], angular_rate_mdps[2]);
}
if (drdy.drdy_temp) {
/* Read temperature data */
memset(&data_raw_temperature, 0x00, sizeof(int16_t));
lsm6dsv16x_temperature_raw_get(&dev_ctx, &data_raw_temperature);
temperature_degC = lsm6dsv16x_from_lsb_to_celsius(
data_raw_temperature);
// printf("Temperature [degC]:%6.2frn", temperature_degC);
}
IMUupdate(angular_rate_mdps[0]/1000,angular_rate_mdps[1]/1000,angular_rate_mdps[2]/1000,acceleration_mg[0]/1000,acceleration_mg[1]/1000,acceleration_mg[2]/1000);
Roll=Roll*100;
Pitch=Pitch*100;
Yaw=Yaw*100;
data_angular_rate_raw[8]=(int16_t)Roll > >8;//roll
data_angular_rate_raw[7]=(int16_t)Roll;
data_angular_rate_raw[10]=(int16_t)Pitch > >8;//pitch
data_angular_rate_raw[9]=(int16_t)Pitch;
data_angular_rate_raw[12]=(int16_t)Yaw > >8;//yaw
data_angular_rate_raw[11]=(int16_t)Yaw;
sumcheck = 0;
addcheck = 0;
for(uint16_t i=0; i < 14; i++)
{
sumcheck += data_angular_rate_raw[i]; //從幀頭開始,對(duì)每一字節(jié)進(jìn)行求和,直到 DATA 區(qū)結(jié)束
addcheck += sumcheck; //每一字節(jié)的求和操作,進(jìn)行一次 sumcheck 的累加
}
data_angular_rate_raw[14]=sumcheck;
data_angular_rate_raw[15]=addcheck;
HAL_UART_Transmit(&huart1 , (uint8_t *)&data_angular_rate_raw, 16, 0xFFFF);
//printf("Roll=%.2f,Pitch=%.2f,Yaw=%.2fn",Roll,Pitch,Yaw);
HAL_Delay(100);
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
演示
上報(bào)匿名助手能正常進(jìn)行解析。
審核編輯:湯梓紅
-
陀螺儀
+關(guān)注
關(guān)注
44文章
776瀏覽量
98488 -
AI
+關(guān)注
關(guān)注
87文章
29805瀏覽量
268098 -
飛行器
+關(guān)注
關(guān)注
13文章
713瀏覽量
45453 -
姿態(tài)解算
+關(guān)注
關(guān)注
0文章
49瀏覽量
8235 -
stm32cubemx
+關(guān)注
關(guān)注
5文章
280瀏覽量
14713
發(fā)布評(píng)論請(qǐng)先 登錄
相關(guān)推薦
評(píng)論