搜索
bottom↓
回复: 81

多旋翼直升机(四轴飞行器)之开源整合平台 [电路模组应用单元] 主题二:飞行姿态分析仪

[复制链接]

出0入0汤圆

发表于 2011-1-26 22:09:35 | 显示全部楼层 |阅读模式
多旋翼直升机(四轴飞行器)之开源整合平台
六、电路模组应用单元
    主题二:飞行姿态分析仪
      程式测试一:
         1.主旨:在无马达振动干扰下, 观察角度仪、陀螺仪及线性加速计的取样值, 以及先用PC 验证陀螺仪及线性加速计的角度位移转换公式。
         2.目的:
            a.将角度仪、陀螺仪及线性加速计的取样值, 依照示波器的方式画在电脑萤幕上, 以利于直觉观察, 用于调整取样时间, 正负值的调整, 比例值参数调整。
            b.将陀螺仪及线性加速计的取样值经过转换公式计算后, 其角位移值与角度仪的取样值差别, 可透过萤幕观察进而调整参数,使其同步一致。
            c.观察陀螺仪及线性加速计有无基值漂移现象, 若有的话, 调整OFFSET 值, 同时可以对温度造成的漂移做对应表处理。
            d.观察陀螺仪及线性加速计的误差特性比较。

         3.模块对应的程式清单:
            全部程式壓縮包:  点击此处下载 ourdev_613512XVDBG3.zip(文件大小:1.75M) (原文件名:APPSUB_02_MAG9DOF_01.zip)

             a.飞控模块测试程式     原理图〔修改增加角度仪〕(PDF档)+(Eagle档)  点击此处下载 ourdev_613513WVM9CK.zip(文件大小:41K) (原文件名:Reciver_Control.zip)

             b.USB TO TWI(I2C) 模组      程式+ WINDOWS XP USB 装置驱动程式
             c. 飞行姿态分析仪上位机(OPENGL GLUT 绘图+ IDE CODEBLOCK V8.02) 程式
                      陀螺仪的累积角位移程式  d = d + GD_y;
                      加速计顷角计算程式  roll = atan2( V_A_x, V_A_z) ;

         4. 观察心得:
              a. 陀螺仪抗振好, 零点漂移不大, 目前透过设定 OFFSET 值处理。若是用很小的死区处理, 则无漂移。 取样线性稳定度没有ENC-03 的问题。
              b. 振动对线性加速计影响大,要想办法进一步处理。
              c. 用人工模拟突发或不正常状态, 有助于写程式防止。
              d. 线性加速计的毛刺来源是两个物体碰触的瞬间, 力的转移或抵消现象。
              e. 陀螺仪的取样值总是平滑, 是因为它只对转动方向敏感, 故而不受其他方向力的影响。

         5. 备注:
              a. 下一个测试是将无刷马达接上, 观察实际的振动影响。
              b. 需要解说的网友不用急, 本主题测完后会发入门教学帖, 详细说明清楚。
                  
              飞行姿势分析仪用的测试机架(因角度仪关系, 目前测试转动角度为+-90度)
              
(原文件名:APPSUB_02_MAG9DOF_01.JPG)

              飞控+MAG9DOF飞行姿态+角度仪+USB TO TWI 模块, 机架(标示X,Y,Z 三轴)
              只取陀螺仪Y轴以及线性加速计X+Z轴的取样值做分析
              
(原文件名:APPSUB_02_MAG9DOF_02.JPG)

              用可变电阻做成的角度仪, 可测得机身的转动角度位置, 供程式校准时比对用。
              
(原文件名:APPSUB_02_MAG9DOF_03.JPG)


               
              由下图中可看出红绿青曲线交叠, 代表各个参数已经调整的差不多了。

                  红色:角度仪    青色:累积角度位移值    绿色:加速计的计算值
                  蓝色:陀螺仪(Y) 紫色:加速计(X)         黄色:加速计(Z)  
                    
                     
(原文件名:APPSUB_02_MAG9DOF_04.GIF)


               陀螺仪漂移观察  
                     
(原文件名:APPSUB_02_MAG9DOF_06.GIF)
                    

               用人工模拟振动的观察  
                     
(原文件名:APPSUB_02_MAG9DOF_05.GIF)

               用人工模拟突加外力时, 陀螺仪炸机, 线性加速计摇晃过关

(原文件名:APPSUB_02_MAG9DOF_07.PNG)

补充内容 (2012-3-28 14:55):
15楼:程式测试二: (电子罗盘)。
16楼:程式测试三: (AHRS 飞行姿态方位参考系统)
19楼:程式测试四:(震动干扰的解决方案)

阿莫论坛20周年了!感谢大家的支持与爱护!!

一只鸟敢站在脆弱的枝条上歇脚,它依仗的不是枝条不会断,而是自己有翅膀,会飞。

出0入0汤圆

 楼主| 发表于 2011-2-13 21:25:44 | 显示全部楼层
回复【楼主位】TADLAW  
-----------------------------------------------------------------------
多旋翼直升机(四轴飞行器)之开源整合平台
六、电路模组应用单元
    主题二:飞行姿态分析仪

        程式测试二: (电子罗盘)
            1.主旨:取MAG 9DOF 模组中的3轴加速计+3轴磁力计的取样值, 做出带倾角补偿的电子罗盘。
            2.目的: 使用PYTHON 的高阶程式语言, 处理MAG 9DOF 模组中的3轴加速计+3轴磁力计的取样值, 经由程式计算, 透过VPYTHON 3D绘图模组, 将电子罗盘画在电脑萤幕上, 以利于直觉观察。
            3. 模块对应的程式清单:
               a. 飞控模块 测试程式
               b. USB TO TWI(I2C) 模组程式
               c. 电子罗盘上位机(PYTHON26 + VPYTHON 3D绘图 + PYUSB) 程式
               d. MAG 9DOF 模组的 TWI 改用 +3.3V 版本  点击此处下载 ourdev_615868LIG9PV.zip(文件大小:54K) (原文件名:MAG9DOF_02.zip)

               全部程式压缩档:  点击此处下载 ourdev_615858UZFHQC.zip(文件大小:22.63M) (原文件名:APPSUB_02_MAG9DOF_02.zip)
            4. 心得报告:磁力计在使用前要做校正处理, 做立体8字绕法,取三轴的最小以及最大值当作单位范围(类似重力加速1g的概念)。当更换地点时是要重新校正的。四轴在天空飞, 飞行方位应该要与GPS 连结校正。
            5. 备注:接序的测试是将无刷马达接上, 观察实际的振动及磁场影响。      
            
            电子罗盘萤幕截图
            
(原文件名:APPSUB_02_MAG9DOF_08.PNG)
            
(原文件名:APPSUB_02_MAG9DOF_10.JPG)

            
(原文件名:APPSUB_02_MAG9DOF_11.JPG)

            
(原文件名:APPSUB_02_MAG9DOF_12.JPG)
======================================================================================
COMPASS_01.PY
======================================================================================

#====[COMPASS]======================================

import math
import usb.core
import usb.util
from visual import *
import string
from time import time

# Main scene
scene=display(title="COMPASS test")
scene.range=(1.2,1.2,1.2)
#scene.forward = (0,-1,-0.25)
scene.forward = (1,0,-0.25)
scene.up=(0,0,1)

# Second scene (Roll, Pitch, Yaw)
scene2 = display(title='COMPASS test',x=0, y=0, width=500, height=200,center=(0,0,0), background=(0,0,0))
scene2.range=(1,1,1)
scene.width=500
scene.y=200

scene2.select()
#Roll, Pitch, Yaw
cil_roll = cylinder(pos=(-0.4,0,0),axis=(0.2,0,0),radius=0.01,color=color.red)
cil_roll2 = cylinder(pos=(-0.4,0,0),axis=(-0.2,0,0),radius=0.01,color=color.red)
cil_pitch = cylinder(pos=(0.1,0,0),axis=(0.2,0,0),radius=0.01,color=color.green)
cil_pitch2 = cylinder(pos=(0.1,0,0),axis=(-0.2,0,0),radius=0.01,color=color.green)
#cil_course = cylinder(pos=(0.6,0,0),axis=(0.2,0,0),radius=0.01,color=color.blue)
#cil_course2 = cylinder(pos=(0.6,0,0),axis=(-0.2,0,0),radius=0.01,color=color.blue)
arrow_course = arrow(pos=(0.6,0,0),color=color.cyan,axis=(-0.2,0,0), shaftwidth=0.02, fixedwidth=1)

#Roll,Pitch,Yaw labels
label(pos=(-0.4,0.3,0),text="Roll",box=0,opacity=0)
label(pos=(0.1,0.3,0),text="Pitch",box=0,opacity=0)
label(pos=(0.55,0.3,0),text="Yaw",box=0,opacity=0)
label(pos=(0.6,0.22,0),text="N",box=0,opacity=0,color=color.yellow)
label(pos=(0.6,-0.22,0),text="S",box=0,opacity=0,color=color.yellow)
label(pos=(0.38,0,0),text="W",box=0,opacity=0,color=color.yellow)
label(pos=(0.82,0,0),text="E",box=0,opacity=0,color=color.yellow)
label(pos=(0.75,0.15,0),height=7,text="NE",box=0,color=color.yellow)
label(pos=(0.45,0.15,0),height=7,text="NW",box=0,color=color.yellow)
label(pos=(0.75,-0.15,0),height=7,text="SE",box=0,color=color.yellow)
label(pos=(0.45,-0.15,0),height=7,text="SW",box=0,color=color.yellow)

L1 = label(pos=(-0.4,0.22,0),text="-",box=0,opacity=0)
L2 = label(pos=(0.1,0.22,0),text="-",box=0,opacity=0)
L3 = label(pos=(0.7,0.3,0),text="-",box=0,opacity=0)

# Main scene objects
scene.select()
# Reference axis (x,y,z)
arrow(color=color.green,axis=(1,0,0), shaftwidth=0.02, fixedwidth=1)
arrow(color=color.green,axis=(0,-1,0), shaftwidth=0.02 , fixedwidth=1)
arrow(color=color.green,axis=(0,0,-1), shaftwidth=0.02, fixedwidth=1)
# labels
label(pos=(0,0,0.8),text="COMPASS test",box=0,opacity=0)
label(pos=(1,0,0),text="X",box=0,opacity=0)
label(pos=(0,-1,0),text="Y",box=0,opacity=0)
label(pos=(0,0,-1),text="Z",box=0,opacity=0)
# IMU object
platform = box(length=1, height=0.05, width=1, color=color.red)
p_line = box(length=1,height=0.08,width=0.1,color=color.yellow)
plat_arrow = arrow(color=color.green,axis=(1,0,0), shaftwidth=0.06, fixedwidth=1)




# find our device
dev = usb.core.find(idVendor=0x16C0, idProduct=0x05DC)
#dev.set_configuration()

AX_MAX = 0.0
AY_MAX = 0.0
AZ_MAX = 0.0

AX_MIN = 0.0
AY_MIN = 0.0
AZ_MIN = 0.0

AX_MAX = 17296.0
AY_MAX = 16224.0
AZ_MAX = 17392.0

AX_MIN = -16688.0
AY_MIN = -16592.0
AZ_MIN = -16672.0

#MX_MAX = 0.0
#MY_MAX = 0.0
#MZ_MAX = 0.0

#MX_MIN = 0.0
#MY_MIN = 0.0
#MZ_MIN = 0.0

MX_MAX = 127.0
MY_MAX = 234.0
MZ_MAX = 174.0

MX_MIN = -367.0
MY_MIN = -255.0
MZ_MIN = -271.0


CT_MX = 5

while(1):
        
  ret = dev.ctrl_transfer(0xC0, 0x05, 0x00, 0x0, 18)
  
  if len(ret) == 18:

  
#    print ret

     A_XI = ret[0] + ret[1]*256
     A_YI = ret[2] + ret[3]*256
     A_ZI = ret[4] + ret[5]*256
     
     if A_XI > 32768:  A_XI = A_XI - 65536        
     if A_YI > 32768:  A_YI = A_YI - 65536
     if A_ZI > 32768:  A_ZI = A_ZI - 65536

     G_X = ret[6]  + ret[7]*256
     G_Y = ret[8]  + ret[9]*256
     G_Z = ret[10] + ret[11]*256
     
     if G_X > 32768:  G_X = G_X - 65536      
     if G_Y > 32768:  G_Y = G_Y - 65536
     if G_Z > 32768:  G_Z = G_Z - 65536

     M_XI = ret[12] + ret[13]*256
     M_YI = ret[14] + ret[15]*256
     M_ZI = ret[16] + ret[17]*256
     
     if M_XI > 32768:  M_XI = (M_XI - 65536)        
     if M_YI > 32768:  M_YI = (M_YI - 65536)
     if M_ZI > 32768:  M_ZI = (M_ZI - 65536)


#     if A_X > AX_MAX: AX_MAX = A_X
#     if A_Y > AY_MAX: AY_MAX = A_Y
#     if A_Z > AZ_MAX: AZ_MAX = A_Z

#     if A_X < AX_MIN: AX_MIN = A_X
#     if A_Y < AY_MIN: AY_MIN = A_Y
#     if A_Z < AZ_MIN: AZ_MIN = A_Z

#     if M_X > MX_MAX: MX_MAX = M_X
#     if M_Y > MY_MAX: MY_MAX = M_Y
#     if M_Z > MZ_MAX: MZ_MAX = M_Z

#     if M_X < MX_MIN: MX_MIN = M_X
#     if M_Y < MY_MIN: MY_MIN = M_Y
#     if M_Z < MZ_MIN: MZ_MIN = M_Z

#     A_X = (A_XI - AX_MIN) / (AX_MAX - AX_MIN) * 2.0 - 1.0
#     A_Y = (A_YI - AY_MIN) / (AY_MAX - AY_MIN) * 2.0 - 1.0
#     A_Z = (A_ZI - AZ_MIN) / (AZ_MAX - AZ_MIN) * 2.0 - 1.0

     A_X = A_XI / 32768.0
     A_Y = A_YI / 32768.0
     A_Z = A_ZI / 32768.0   
     
     M_X = (M_XI - MX_MIN) / (MX_MAX - MX_MIN) * 2.0 - 1.0
     M_Y = (M_YI - MY_MIN) / (MY_MAX - MY_MIN) * 2.0 - 1.0
     M_Z = (M_ZI - MZ_MIN) / (MZ_MAX - MZ_MIN) * 2.0 - 1.0

#     print 'AX_MAX:%6d, AY_MAX:%6d, AZ_MAX:%6d' % (AX_MAX,AY_MAX,AZ_MAX)
#     print 'AX_MIN:%6d, AY_MIN:%6d, AZ_MIN:%6d' % (AX_MIN,AY_MIN,AZ_MIN)

#     print 'M_X:%f, M_Y:%f, M_Z:%f' % (M_X,M_Y,M_Z)
#     print 'MX_MAX:%6d, MY_MAX:%6d, MZ_MAX:%6d' % (MX_MAX,MY_MAX,MZ_MAX)
#     print 'MX_MIN:%6d, MY_MIN:%6d, MZ_MIN:%6d' % (MX_MIN,MY_MIN,MZ_MIN)

     
#     print 'A_x:%9f, A_y:%9f, A_z:%9f  ||  G_x:%6d, G_y:%6d, G_z:%6d  ||  M_x:%9f, M_y:%9f, M_z:%9f' % (A_X,A_Y,A_Z,G_X,G_Y,G_Z,M_X,M_Y,M_Z)
     print 'A_x:%9f, A_y:%9f, A_z:%9f' % (A_X,A_Y,A_Z)
     
     roll  = math.atan2(A_Y,math.sqrt(A_X*A_X+A_Z*A_Z))
     pitch = math.atan2(A_X,math.sqrt(A_Y*A_Y+A_Z*A_Z))

     if A_Z < 0:
       if A_Y > 0:
          roll = pi - roll
       else:
          roll = -(roll + pi)
     #====[COMPASS]==========================  
     cos_roll  = math.cos(roll)
     sin_roll  = math.sin(roll)
     cos_pitch = math.cos(pitch)
     sin_pitch = math.sin(pitch)
     
     # Tilt compensated Magnetic filed X:
     MH_X = M_X*cos_pitch - M_Z*sin_pitch
     # Tilt compensated Magnetic filed Y:
     MH_Y = M_X*sin_roll*sin_pitch + M_Y*cos_roll - M_Z*sin_roll*cos_pitch
     # Magnetic Heading
     yaw = math.atan2(MH_Y,MH_X)

     axis=(math.cos(pitch)*math.cos(yaw),-math.cos(pitch)*math.sin(yaw),math.sin(pitch))
     up=(math.sin(roll)*math.sin(yaw)+math.cos(roll)*math.sin(pitch)*math.cos(yaw),math.sin(roll)*math.cos(yaw)-math.cos(roll)*math.sin(pitch)*math.sin(yaw),-math.cos(roll)*math.cos(pitch))

#     print axis,up
     
     platform.axis=axis
     platform.up=up
     platform.length=1.0
     platform.width=0.65
     plat_arrow.axis=axis
     plat_arrow.up=up
     plat_arrow.length=0.8
     p_line.axis=axis
     p_line.up=up        

     cil_roll.axis=(0.2*cos(roll),0.2*sin(roll),0)
     cil_roll2.axis=(-0.2*cos(roll),-0.2*sin(roll),0)
     cil_pitch.axis=(0.2*cos(pitch),0.2*sin(pitch),0)
     cil_pitch2.axis=(-0.2*cos(pitch),-0.2*sin(pitch),0)
     arrow_course.axis=(0.2*sin(yaw),0.2*cos(yaw),0)
     L1.text = '%5.1f' % (math.degrees(roll))
     L2.text = '%5.1f' % (math.degrees(pitch))
     L3.text = '%5.1f' % (math.degrees(yaw))

出0入0汤圆

 楼主| 发表于 2011-2-13 22:40:35 | 显示全部楼层
回复【楼主位】TADLAW  
-----------------------------------------------------------------------
多旋翼直升机(四轴飞行器)之开源整合平台
六、电路模组应用单元
    主题二:飞行姿态分析仪

        程式测试三: (AHRS 飞行姿态方位参考系统)
            1.主旨:取MAG 9DOF 模组中的3轴陀螺仪+3轴加速计+3轴磁力计的取样值, 做出AHRS 姿态方位参考系统。
            2.目的:
                a. 使用PYTHON 的高阶程式语言, 处理MAG 9DOF 模组中的3轴陀螺仪+3轴加速计+3轴磁力计的取样值, 经由程式计算, 透过VPYTHON 3D绘图模组, 将AHRS画在电脑萤幕上, 以利于直觉观察。
                b. AHRS 程式模组是四元数+DCM(Direction Cosine Matrix)滤波实作, 可平缓手动摇晃以及振动干扰的影响。
            3.模块对应的程式清单:
                a. 飞控模块 测试程式 (同电子罗盘,在14楼)
                b. USB TO TWI(I2C) 模组程式 (同电子罗盘)
                c. 上位机安装程式(PYTHON+VPYTHON 3D绘图+PYUSB) (同电子罗盘)
                d. AHRS 上位机程式 点击此处下载 ourdev_615876AOB5E8.zip(文件大小:3K) (原文件名:AHRS_01.zip)

            4.心得:
                a. 磁力计在使用前要做校正处理。
                b. 会自动修正陀罗仪累积误差。
                c. pitch 锁在 磁北上, 不知道对不对?
                d. 与电子罗盘比较, 反应比较慢。
                e. 四轴飞行姿态分析的重点在陀罗仪, 当机体转动时的动能,会由陀罗仪的角速值表现出来。此时透过马达转速改变将机体推回, 若是推回力道小于机体转动时的动能, 则此一控制是阻尼器的观念。若是等于则是平衡器的观念。由此可知, 机体要前后左右重量平衡, 马达推力要线性一致, 四轴的调校才会比较容易。
                f. 当陀罗仪以平衡器的观念来做即时控制时, 加速计的角色则转化为绝对参考值,用比较长时间累积的平均值就可以获得, 过滤干扰就有可能不用数学概念的浮点计算了。

            5. 备注:接序的测试是将无刷马达接上, 观察实际的振动及磁场影响。
         
            AHRS萤幕截图
            
(原文件名:APPSUB_02_MAG9DOF_09.PNG)


====================================================================================
AHRS_01.PY
====================================================================================

#====[AHRS ]==================================================================
#=====================================================================================================
# AHRS
# S.O.H. Madgwick
# 25th August 2010
#=====================================================================================================
# Description:
#
# Quaternion implementation of the 'DCM filter' [Mayhony et al].  Incorporates the magnetic distortion
# compensation algorithms from my filter [Madgwick] which eliminates the need for a reference
# direction of flux (bx bz) to be predefined and limits the effect of magnetic distortions to yaw
# axis only.
#
# User must define 'halfT' as the (sample period / 2), and the filter gains 'Kp' and 'Ki'.
#
# Global variables 'q0', 'q1', 'q2', 'q3' are the quaternion elements representing the estimated
# orientation.  See my report for an overview of the use of quaternions in this application.
#
# User must call 'AHRSupdate()' every sample period and parse calibrated gyroscope ('gx', 'gy', 'gz'),
# accelerometer ('ax', 'ay', 'ay') and magnetometer ('mx', 'my', 'mz') data.  Gyroscope units are
# radians/second, accelerometer and magnetometer units are irrelevant as the vector is normalised.
#
#=====================================================================================================

import math
import usb.core
import usb.util
from visual import *
import string
from time import time

# Main scene
scene=display(title="MAG9DOF AHRS test")
scene.range=(1.2,1.2,1.2)
#scene.forward = (0,-1,-0.25)
scene.forward = (1,0,-0.25)
scene.up=(0,0,1)

# Second scene (Roll, Pitch, Yaw)
scene2 = display(title='MAG9DOF AHRS test',x=0, y=0, width=500, height=200,center=(0,0,0), background=(0,0,0))
scene2.range=(1,1,1)
scene.width=500
scene.y=200

scene2.select()
#Roll, Pitch, Yaw
cil_roll = cylinder(pos=(-0.4,0,0),axis=(0.2,0,0),radius=0.01,color=color.red)
cil_roll2 = cylinder(pos=(-0.4,0,0),axis=(-0.2,0,0),radius=0.01,color=color.red)
cil_pitch = cylinder(pos=(0.1,0,0),axis=(0.2,0,0),radius=0.01,color=color.green)
cil_pitch2 = cylinder(pos=(0.1,0,0),axis=(-0.2,0,0),radius=0.01,color=color.green)
#cil_course = cylinder(pos=(0.6,0,0),axis=(0.2,0,0),radius=0.01,color=color.blue)
#cil_course2 = cylinder(pos=(0.6,0,0),axis=(-0.2,0,0),radius=0.01,color=color.blue)
arrow_course = arrow(pos=(0.6,0,0),color=color.cyan,axis=(-0.2,0,0), shaftwidth=0.02, fixedwidth=1)

#Roll,Pitch,Yaw labels
label(pos=(-0.4,0.3,0),text="Roll",box=0,opacity=0)
label(pos=(0.1,0.3,0),text="Pitch",box=0,opacity=0)
label(pos=(0.55,0.3,0),text="Yaw",box=0,opacity=0)
label(pos=(0.6,0.22,0),text="N",box=0,opacity=0,color=color.yellow)
label(pos=(0.6,-0.22,0),text="S",box=0,opacity=0,color=color.yellow)
label(pos=(0.38,0,0),text="W",box=0,opacity=0,color=color.yellow)
label(pos=(0.82,0,0),text="E",box=0,opacity=0,color=color.yellow)
label(pos=(0.75,0.15,0),height=7,text="NE",box=0,color=color.yellow)
label(pos=(0.45,0.15,0),height=7,text="NW",box=0,color=color.yellow)
label(pos=(0.75,-0.15,0),height=7,text="SE",box=0,color=color.yellow)
label(pos=(0.45,-0.15,0),height=7,text="SW",box=0,color=color.yellow)

L1 = label(pos=(-0.4,0.22,0),text="-",box=0,opacity=0)
L2 = label(pos=(0.1,0.22,0),text="-",box=0,opacity=0)
L3 = label(pos=(0.7,0.3,0),text="-",box=0,opacity=0)

# Main scene objects
scene.select()
# Reference axis (x,y,z)
arrow(color=color.green,axis=(1,0,0), shaftwidth=0.02, fixedwidth=1)
arrow(color=color.green,axis=(0,-1,0), shaftwidth=0.02 , fixedwidth=1)
arrow(color=color.green,axis=(0,0,-1), shaftwidth=0.02, fixedwidth=1)
# labels
label(pos=(0,0,0.8),text="9DOF Razor IMU test",box=0,opacity=0)
label(pos=(1,0,0),text="X",box=0,opacity=0)
label(pos=(0,-1,0),text="Y",box=0,opacity=0)
label(pos=(0,0,-1),text="Z",box=0,opacity=0)
# IMU object
platform = box(length=1, height=0.05, width=1, color=color.red)
p_line = box(length=1,height=0.08,width=0.1,color=color.yellow)
plat_arrow = arrow(color=color.green,axis=(1,0,0), shaftwidth=0.06, fixedwidth=1)




# find our device
dev = usb.core.find(idVendor=0x16C0, idProduct=0x05DC)
#dev.set_configuration()

AX_MAX = 0.0
AY_MAX = 0.0
AZ_MAX = 0.0

AX_MIN = 0.0
AY_MIN = 0.0
AZ_MIN = 0.0

AX_MAX = 17296.0
AY_MAX = 16224.0
AZ_MAX = 17392.0

AX_MIN = -16688.0
AY_MIN = -16592.0
AZ_MIN = -16672.0

#MX_MAX = 0.0
#MY_MAX = 0.0
#MZ_MAX = 0.0

#MX_MIN = 0.0
#MY_MIN = 0.0
#MZ_MIN = 0.0

MX_MAX = 127.0
MY_MAX = 234.0
MZ_MAX = 174.0

MX_MIN = -367.0
MY_MIN = -255.0
MZ_MIN = -271.0


CT_MX = 5

#====[AHRS]===========================================================================================
Kp = 2.0                # 2.0 proportional gain governs rate of convergence to accelerometer/magnetometer
Ki = 0.005                # 0.005 integral gain governs rate of convergence of gyroscope biases
halfT = 0.02          # 0.02 half the sample period

# quaternion elements representing the estimated orientation
q0 = 1.0
q1 = 0.0
q2 = 0.0
q3 = 0.0
# scaled integral error
exInt = 0.0
eyInt = 0.0
ezInt = 0.0

while(1):
        
  ret = dev.ctrl_transfer(0xC0, 0x05, 0x00, 0x0, 18)
  
  if len(ret) == 18:


     # auxiliary variables to reduce number of repeated operations
     q0q0 = q0*q0
     q0q1 = q0*q1
     q0q2 = q0*q2
     q0q3 = q0*q3
     q1q1 = q1*q1
     q1q2 = q1*q2
     q1q3 = q1*q3
     q2q2 = q2*q2   
     q2q3 = q2*q3
     q3q3 = q3*q3
       
#    print ret

     A_XI = ret[0] + ret[1]*256
     A_YI = ret[2] + ret[3]*256
     A_ZI = ret[4] + ret[5]*256
     
     if A_XI > 32768:  A_XI = A_XI - 65536        
     if A_YI > 32768:  A_YI = A_YI - 65536
     if A_ZI > 32768:  A_ZI = A_ZI - 65536

     A_X = A_XI / 32768.0
     A_Y = A_YI / 32768.0
     A_Z = A_ZI / 32768.0   
     
     G_X = ret[6]  + ret[7]*256
     G_Y = ret[8]  + ret[9]*256
     G_Z = ret[10] + ret[11]*256
     
     if G_X > 32768:  G_X = G_X - 65536      
     if G_Y > 32768:  G_Y = G_Y - 65536
     if G_Z > 32768:  G_Z = G_Z - 65536     
     
     M_XI = ret[12] + ret[13]*256
     M_YI = ret[14] + ret[15]*256
     M_ZI = ret[16] + ret[17]*256
     
     if M_XI > 32768:  M_XI = (M_XI - 65536)        
     if M_YI > 32768:  M_YI = (M_YI - 65536)
     if M_ZI > 32768:  M_ZI = (M_ZI - 65536)

#     if M_X > MX_MAX: MX_MAX = M_X
#     if M_Y > MY_MAX: MY_MAX = M_Y
#     if M_Z > MZ_MAX: MZ_MAX = M_Z

#     if M_X < MX_MIN: MX_MIN = M_X
#     if M_Y < MY_MIN: MY_MIN = M_Y
#     if M_Z < MZ_MIN: MZ_MIN = M_Z


     M_X = (M_XI - MX_MIN) / (MX_MAX - MX_MIN) * 2.0 - 1.0
     M_Y = (M_YI - MY_MIN) / (MY_MAX - MY_MIN) * 2.0 - 1.0
     M_Z = (M_ZI - MZ_MIN) / (MZ_MAX - MZ_MIN) * 2.0 - 1.0


#     print 'M_X:%f, M_Y:%f, M_Z:%f' % (M_X,M_Y,M_Z)
#     print 'MX_MAX:%6d, MY_MAX:%6d, MZ_MAX:%6d' % (MX_MAX,MY_MAX,MZ_MAX)
#     print 'MX_MIN:%6d, MY_MIN:%6d, MZ_MIN:%6d' % (MX_MIN,MY_MIN,MZ_MIN)

     gx = (G_X / 32768.0) * 250.0 * (pi / 180.0)
     gy = (G_Y / 32768.0) * 250.0 * (pi / 180.0)
     gz = (G_Z / 32768.0) * 250.0 * (pi / 180.0)
     
     #====[normalise the measurements]====================
     norm = math.sqrt(A_X*A_X+A_Y*A_Y+A_Z*A_Z)
     ax = A_X / norm
     ay = A_Y / norm
     az = A_Z / norm
     
     norm = math.sqrt(M_X*M_X+M_Y*M_Y+M_Z*M_Z)        
     mx = M_X / norm
     my = M_Y / norm
     mz = M_Z / norm

     #====[compute reference direction of flux]==========================================
     hx = 2*mx*(0.5 - q2q2 - q3q3) + 2*my*(q1q2 - q0q3)       + 2*mz*(q1q3 + q0q2)
     hy = 2*mx*(q1q2 + q0q3)       + 2*my*(0.5 - q1q1 - q3q3) + 2*mz*(q2q3 - q0q1)
     hz = 2*mx*(q1q3 - q0q2)       + 2*my*(q2q3 + q0q1)       + 2*mz*(0.5 - q1q1 - q2q2)        
     bx = sqrt((hx*hx) + (hy*hy))
     bz = hz      
       
     #====[estimated direction of gravity and flux (v and w)]================
     vx = 2*(q1q3 - q0q2)
     vy = 2*(q0q1 + q2q3)
     vz = q0q0 - q1q1 - q2q2 + q3q3
     wx = 2*bx*(0.5 - q2q2 - q3q3) + 2*bz*(q1q3 - q0q2)
     wy = 2*bx*(q1q2 - q0q3) + 2*bz*(q0q1 + q2q3)
     wz = 2*bx*(q0q2 + q1q3) + 2*bz*(0.5 - q1q1 - q2q2)
       
     #====[error is sum of cross product between reference direction of fields and direction measured by sensors
     ex = (ay*vz - az*vy) + (my*wz - mz*wy)
     ey = (az*vx - ax*vz) + (mz*wx - mx*wz)
     ez = (ax*vy - ay*vx) + (mx*wy - my*wx)
       
     #====[integral error scaled integral gain
     exInt = exInt + ex*Ki
     eyInt = eyInt + ey*Ki
     ezInt = ezInt + ez*Ki

     #====[adjusted gyroscope measurements
     gx = gx + Kp*ex + exInt
     gy = gy + Kp*ey + eyInt
     gz = gz + Kp*ez + ezInt
       
     #====[integrate quaternion rate and normalise
     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
       
     #====[normalise quaternion]==========================
     norm = math.sqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3)
     q0 = q0 / norm
     q1 = q1 / norm
     q2 = q2 / norm
     q3 = q3 / norm
     
     #====[quaternionToEuler]===========================================================
     euler0 =  math.atan2(2*q1*q2 - 2*q0*q3, 2*q0*q0 + 2*q1*q1 - 1)    #====[psi]====
     euler1 = -math.asin(2*q1*q3 + 2*q0*q2)                           #====[theta]==
     euler2 =  math.atan2(2*q2*q3 - 2*q0*q1, 2*q0*q0 + 2*q3*q3 - 1)    #====[phi]====
     
     print 'euler0=%9f,  euler1=%9f,  euler2=%9f' %(math.degrees(euler0),math.degrees(euler1),math.degrees(euler2))

     pitch = euler1
     roll  = euler2
     yaw   = euler0

     #====[Tilt compensated Magnetic filed X:]=============================
#    MH_X = M_X*cos_pitch - M_Z*sin_pitch
     #====[Tilt compensated Magnetic filed Y:]=============================
#     MH_Y = M_X*sin_roll*sin_pitch + M_Y*cos_roll - M_Z*sin_roll*cos_pitch
     #====[Magnetic Heading]=============================
#     yaw = math.atan2(MH_Y,MH_X)

     axis=(math.cos(pitch)*math.cos(yaw),-math.cos(pitch)*math.sin(yaw),math.sin(pitch))
     up=(math.sin(roll)*math.sin(yaw)+math.cos(roll)*math.sin(pitch)*math.cos(yaw),math.sin(roll)*math.cos(yaw)-math.cos(roll)*math.sin(pitch)*math.sin(yaw),-math.cos(roll)*math.cos(pitch))

#     print axis,up
     
     platform.axis=axis
     platform.up=up
     platform.length=1.0
     platform.width=0.65
     plat_arrow.axis=axis
     plat_arrow.up=up
     plat_arrow.length=0.8
     p_line.axis=axis
     p_line.up=up        

     cil_roll.axis=(0.2*cos(roll),0.2*sin(roll),0)
     cil_roll2.axis=(-0.2*cos(roll),-0.2*sin(roll),0)
     cil_pitch.axis=(0.2*cos(pitch),0.2*sin(pitch),0)
     cil_pitch2.axis=(-0.2*cos(pitch),-0.2*sin(pitch),0)
     arrow_course.axis=(0.2*sin(yaw),0.2*cos(yaw),0)
     L1.text = '%5.1f' % (math.degrees(roll))
     L2.text = '%5.1f' % (math.degrees(pitch))
     L3.text = '%5.1f' % (math.degrees(yaw))

出0入0汤圆

 楼主| 发表于 2011-2-23 18:05:39 | 显示全部楼层
回复【楼主位】TADLAW  
-----------------------------------------------------------------------
多旋翼直升机(四轴飞行器)之开源整合平台

三、電路模組電路圖
六、电路模组应用单元

    主题一:全数位式双向收发遥控器
    主题二:飞行姿态分析仪

        程式测试四:
            1.主旨:在马达震动干扰下, 观察角度仪、陀螺仪及线性加速计的取样值, 尝试找出震动干扰的解决方案。
            2.目的:
              a. 将角度仪、陀螺仪及线性加速计的取样值, 依照示波器的方式画在电脑萤幕上, 以利于直觉观察。
              b. 观察马达震动是如何干扰陀螺仪及线性加速计的取样值。
              c. 观察将100个加速计的取样值做平均后画在萤幕上, 看能否与红线交叠。
            3.模块对应的程式清单:
              a. 飞控模块测试程式原理图〔修改增加角度仪〕(PDF档) (Eagle档)
              b. USB TO TWI(I2C) 模组程式+ WINDOWS XP USB 装置驱动程式
              c. 飞行姿态分析仪上位机(OPENGL GLUT 绘图+ IDE CODEBLOCKS V8.02) 程式
                 (1) 陀螺仪的累积角位移程式d = d + GD_y;
                 (2) 加速计倾角计算程式roll = atan2( V_A_x, V_A_z) ;
            4.观察心得:                 
               a. 陀螺仪不受马达震动影响以及能即时反应机体动态是优点, 缺点是随时间累积的误差无法处理。
               b. 加速计在没有马达震动影响下和陀螺仪一样能即时反应机体动态, 并且没有随时间累积的误差。但是在马达震动影响下, 测量出来的值误差太大, 已经无法再即时反应正确的机体动态。
               c. 当机体转至某角度定住时, 在马达震动下, 加速计所测量的重力为绝对值+振动值, 振动值有正有负(原处晃动),经由100个取样的平均值, 可取得接近无马达震动的值, 由此值与陀螺仪的差值, 可用来修正陀螺仪随时间累积的误差。
               d. 以机体[动与静]的观点来思考问题。 [动]的方面依陀螺仪的测量值来处理, 当测得转动4度, 则控制马达顶回4度。 [静]的方面依加速计的平均测量值, 以固定间隔的时间, 来处理陀螺仪随时间累积的误差。
               e. 陀螺仪与加速计互相校准的精度有限,机体不漂也难, 难怪德国人就用[老魔]的方法解决。 AR.drone就用[光流]解决。

            5.备注:
               a. 接下来的测试, 必须将无线摇杆控制、感测器, 马达控制做综合考量的飞行控制测试。
               b. 看来也要来研究[光流]一下。
                          
                  
            为了观察无刷马达的振动对传感器的影响, 所做的测试用机架。
            
(原文件名:APPSUB_02_Vibration_01.JPG)                     
            装上电调模组。
            
(原文件名:APPSUB_02_Vibration_02.JPG)
            飞控模组+无线模组+MAG9DOF(传感器)模组+USB TO TWI(连通PC)模组。
            
(原文件名:APPSUB_02_Vibration_03.JPG)                     
            CH6(值0~1023)对应控制马达转速, Buttons值=1:马达关闭, Buttons值=0:启动马达并且进入怠速。
            
(原文件名:APPSUB_02_Vibration_04.JPG)         
            马达转速参数CH6=0, Buttons值=1(切至最底), 表示要马达关闭。
            
(原文件名:APPSUB_02_Vibration_05.JPG)                    
            马达转速参数CH6=0, Buttons值=0(切至中间), 表示要马达启动后, 进入怠速。
            
(原文件名:APPSUB_02_Vibration_06.JPG)         
            转动旋钮调至马达转速参数CH6=445, Buttons值=0(切至中间), 表示要马达转速锁定在参数445=4300RPM(200g拉力1045桨)。
            
(原文件名:APPSUB_02_Vibration_07.JPG)         
            马达转速=0时, 陀螺仪(青色)及加速计(绿色)工作正常。
            
(原文件名:APPSUB_02_Vibration_10_RPM_0.PNG)         
            马达转速进入怠速后, 陀螺仪(青色)工作正常,而加速计(绿色)受到振动的干扰出现锯齿状。
            
(原文件名:APPSUB_02_Vibration_11_RPM_1000.PNG)         
            马达转速进入4300RPM后, 陀螺仪(青色)工作正常,而加速计(绿色)受到振动的干扰出现锯齿状。
            
(原文件名:APPSUB_02_Vibration_12_RPM_445.PNG)         
            单独显示陀螺仪(青色),马达转速=4300RPM, 陀螺仪(青色)工作正常, 与角度仪(红线)交叠。
            
(原文件名:APPSUB_02_Vibration_13_RPM_445.PNG)         
            加速计(绿色)受到振动的干扰出现锯齿状, 但基值跟随红线, 意思是机体转到某角度后轻轻的晃动。
            
(原文件名:APPSUB_02_Vibration_14_RPM_445.PNG)            
            观察到这里, 心冷一半, 这样加速计岂不是白买了!幸好后面有解!
            
(原文件名:APPSUB_02_Vibration_15_RPM_445.PNG)         
            将加速计最后100个取样值, 做平均值后, 画成紫线, 可看出当机体不动时紫线可以和红线(角度仪)交叠。但是当机体在转动中,则只有陀螺仪与红线交叠。
            
(原文件名:APPSUB_02_Vibration_16_RPM_0.PNG)         
            在马达震动干扰下, 可看出当机体在转动中,加速计无用武之地。
            
(原文件名:APPSUB_02_Vibration_17_RPM_1000.PNG)         
            在马达震动干扰下, 可看出当机体不动时紫线可以和红线(角度仪)交叠。但是当机体在转动中,则只有陀螺仪与红线交叠。
            
(原文件名:APPSUB_02_Vibration_18_RPM_1000.PNG)         
            马达在 3400 RPM
            
(原文件名:APPSUB_02_Vibration_19_RPM_445.PNG)

出0入0汤圆

 楼主| 发表于 2012-5-25 16:20:45 | 显示全部楼层
本帖最后由 TADLAW 于 2012-5-25 16:57 编辑

2010.05.25 重新上传附件档(共6个文件):
    1.
    2.
    3.
    4.

    5.
    6.

本帖子中包含更多资源

您需要 登录 才可以下载或查看,没有帐号?注册

x

出0入0汤圆

发表于 2011-1-26 22:44:49 | 显示全部楼层
好贴

出0入0汤圆

发表于 2011-1-26 22:50:51 | 显示全部楼层
前排支持了 这个项目很有看头

出0入0汤圆

发表于 2011-1-26 22:54:35 | 显示全部楼层
顶之。学习之。

出0入0汤圆

发表于 2011-1-26 23:29:51 | 显示全部楼层
好贴,以后可能用得上

出0入0汤圆

发表于 2011-1-26 23:36:29 | 显示全部楼层

(原文件名:路过.gif)

出0入0汤圆

发表于 2011-1-26 23:54:20 | 显示全部楼层
mark

出0入0汤圆

发表于 2011-1-27 08:47:26 | 显示全部楼层
好東西啊.頂項

出0入0汤圆

发表于 2011-1-31 12:20:14 | 显示全部楼层
mark!

出0入0汤圆

发表于 2011-1-31 21:07:28 | 显示全部楼层
看你的飞行模拟测试台是两轴的, 要是测试四轴飞行器, 是怎样的?

想在室内模拟测试四轴飞行器的GPS路线飞行:
取下GPS, 向串口模拟输入变化的NMEA语句, 观察飞行器是否能正确地根据PID算法得到的飞控指令改变其姿态(比如机架前倾: 表示向前飞向下一GPS点, 倾斜角越大则表示向前飞得越快).

出0入0汤圆

 楼主| 发表于 2011-2-3 12:32:49 | 显示全部楼层
回复【10楼】MAPGPS  
-----------------------------------------------------------------------
先用单一轴向测试台, 主要是为了化简飞行姿势的分析问题, 用角度仪取得绝对值, 用以验证陀罗仪及加速计的转换公式, 以及观察分析其误差值特性, 进而提出解决方案。 (例如:马达振动,温度,超过传感器侦测范围值...等等)
目前还在IMU 九轴(磁3+加3+陀3)输出测试阶段,准备迈向AHRS, 至于全机+ GPS测试, 还没谱呢。只能继续努力测试!

全机测试方法可以参考这个网站(http://www.bldc.tw)

     [ MK版的UAV室内测试OK / 电源供应器供电/ 用万向节悬浮定位
     
(原文件名:IMG_2360M.jpg)

或是参考这个视频    点击此处下载 ourdev_614527UPFIZ2.zip(文件大小:2.45M) (原文件名:X600D_Test_Stand.zip)


(原文件名:IMG_1360M.jpg)

出0入0汤圆

发表于 2011-2-3 14:37:00 | 显示全部楼层
mark

出0入0汤圆

发表于 2011-2-10 09:47:04 | 显示全部楼层
马克#大巅 四轴

出0入0汤圆

发表于 2011-2-13 22:56:43 | 显示全部楼层
这个.........................才是行家,带上小板凳开始听课了!

出0入0汤圆

发表于 2011-2-21 11:57:37 | 显示全部楼层
开始学习!

出0入0汤圆

发表于 2011-2-23 18:30:49 | 显示全部楼层
用心的作品一定要讚美一下了。

出0入0汤圆

发表于 2011-2-24 13:24:58 | 显示全部楼层
学习!兴趣被你调动起来了,谢谢!

出0入0汤圆

发表于 2011-2-24 14:30:09 | 显示全部楼层
强帖留名

感觉这个贴要火

学习 学习  再学习  !!

出0入0汤圆

发表于 2011-2-24 14:32:51 | 显示全部楼层
请问楼主 无刷电机对LSM303DLH测磁场影响有多大?

出0入0汤圆

 楼主| 发表于 2011-2-24 17:45:19 | 显示全部楼层
回复【22楼】chengluoran  
-----------------------------------------------------------------------
    1. 马达震动会影响加速计,由加速计测到的倾角会影响方位计算,于是指南针变成跳跳针。
    2. LSM303DLH的定位是手持式电子罗盘, 在A点测量前要先校正(X+Y+Z轴旋转360度取最大及最小值,当作单元化的范围), 到B点时要再校正一次, 用加速计做倾角补偿后, 取得方位资料。问题是要开马达校正还是关马达时校正,有点困扰。
    3. 四轴的工作环境刚好是LSM303DLH的致命伤, 在0.4高斯下,解析度很低,测量总值230下会+-0~20跳动。所以必须用较长时间的平均值来处理,无法作出即时反应,变成GPS等级。
    4. 四轴的传感器应以陀螺仪为主,因为磁场以及震动对陀螺仪影响很小, 但是会随时间累积出误差, 而造成停悬时会飘向某方。 [老魔]的解决方法是,透人眼调中立值,若是还飘,一段时间就用万能的母指拨杆推回。 AR.drone 就用[光流]做的电子眼,对前后画面的特征处,在做位移比对后,得到机体飘移速度及方向。
    5. 设计四轴的定位若是[航模],配重平衡做好,动力线性一致,再用陀螺仪做成阻尼器就很好飞了(加速计+磁力计效果有限),其他都靠[老魔]的飞行技术。若是定位在[AR.drone],能自己锁定高度及位置,就要用[光流]+超音波测距,硬体就要三级跳了。
    6. 個人已经决定在自己的四轴上加[光流]。
[光流]例一, 透过OPENCV中的函式库将前后画面的特征点,标示移动方向。(以前看到这个功能时,不知有啥用,现在刚好用在四轴低高度的悬停上。)

(原文件名:OF_01.PNG)
[光流]例二, AR.drone 两个相机都做特征点的速度方向标记(在左上角的画面是往下看的镜头画面)

(原文件名:OF_04.png)
AR.drone 悬浮时的画面(看來不只可以固定不飄,還可以避障呢!)

(原文件名:OF_05.png)

出0入0汤圆

发表于 2011-2-24 18:21:04 | 显示全部楼层
学习了!
有个小疑惑:
   由于加速度计不再机体旋转的轴心,当机体旋转是会叠加上角加速度分量的(不考虑平移),所以
但还是可以由角速度值加以修正。
(力学分析还是很有必要的^ ^小弟愚见)

出0入0汤圆

发表于 2011-3-7 13:55:36 | 显示全部楼层
Mark一下,非常强的牛人!

出0入0汤圆

发表于 2011-5-21 23:38:54 | 显示全部楼层
顶上去
    想到个姿态解析算法,基于运动学分析的力学方程(用加速计与陀螺仪数据分析实现),暑假有空试试

出0入0汤圆

发表于 2011-5-21 23:46:05 | 显示全部楼层
想到的另一点:
    由于加速度传感器的采样频率较低(相对于电机震动),
  所以可以考虑加个机械式的低通滤波器,也就是给传感器加个合适的海绵减震,

请高人指点

出0入0汤圆

发表于 2011-5-23 06:59:30 | 显示全部楼层
海绵减震可以,有的飞控板下面就用海绵减震

出0入0汤圆

发表于 2011-5-23 09:25:58 | 显示全部楼层
这贴太强了 阿莫怎么不给酷

出0入0汤圆

发表于 2011-5-26 10:37:48 | 显示全部楼层
牛人!

出0入0汤圆

发表于 2011-5-26 14:08:04 | 显示全部楼层
回复【楼主位】TADLAW
多旋翼直升机(四轴飞行器)之开源整合平台
六、电路模组应用单元
    主题二:飞行姿态分析仪
      程式测试一:
         1.主旨:在无马达振动干扰下, 观察角度仪、陀螺仪及线性加速计的取样值, 以及先用pc 验证陀螺仪及线性加速计的角度位移转换公式。
         2.目的:
            a.将角度仪、陀螺仪及线性加速计的取样值, 依照示波器的方式画在电脑萤幕上, 以利于直觉观察, 用于调整取样时间, 正负值的调整, 比例值参数调整。
            b.将陀螺仪及线性加速计的取样值经过转换公式计算后, 其角位移值与角度仪的取样值差别, 可透过萤幕观察进而调整参数,使其同步一致。
            c.观察陀螺仪及线性加速计有无基值漂移现象, 若有的话, 调整offset 值, 同时可以对温度造成的漂移做对应表处理。
  ......
-----------------------------------------------------------------------

回复【29楼】skystalker
-----------------------------------------------------------------------

回复【29楼】skystalker
这贴太强了 阿莫怎么不给酷
-----------------------------------------------------------------------

回复【29楼】skystalker
-----------------------------------------------------------------------

回复【29楼】skystalker
这贴太强了 阿莫怎么不给酷
-----------------------------------------------------------------------

回复【29楼】skystalker
-----------------------------------------------------------------------

回复【29楼】skystalker
这贴太强了 阿莫怎么不给酷
-----------------------------------------------------------------------

回复【29楼】skystalker
-----------------------------------------------------------------------

回复【29楼】skystalker
这贴太强了 阿莫怎么不给酷
-----------------------------------------------------------------------

回复【29楼】skystalker
-----------------------------------------------------------------------

楼主 你好  我现在也要用到LSM303DLH芯片,可是老测试通不过!不知道是什么原因  麻烦你留个联系方式给我 我的电子邮箱:chenkan.123.1987@163.com

出0入0汤圆

发表于 2011-5-26 14:57:56 | 显示全部楼层
这动手能力如此的强大!

出0入0汤圆

发表于 2011-5-26 18:11:30 | 显示全部楼层
mark~

出0入0汤圆

发表于 2011-5-27 00:10:13 | 显示全部楼层
MARK

出0入0汤圆

发表于 2011-5-27 09:46:23 | 显示全部楼层
MARK!

出0入0汤圆

发表于 2011-5-27 11:01:18 | 显示全部楼层
MARK,强帖

出0入0汤圆

发表于 2011-5-28 10:47:47 | 显示全部楼层
学习了,看来是个有意义的差事。。。

出0入143汤圆

发表于 2011-5-28 14:13:45 | 显示全部楼层
要花大量的時間了,頂一下!

出0入0汤圆

发表于 2011-8-1 17:32:10 | 显示全部楼层
已经入手LSM303DLH,观看楼主的代码。

出0入0汤圆

发表于 2011-8-1 18:24:54 | 显示全部楼层
MARK

出0入0汤圆

发表于 2011-8-2 09:58:07 | 显示全部楼层
记号

出0入0汤圆

发表于 2011-8-2 18:55:24 | 显示全部楼层
记号一下.

出0入0汤圆

发表于 2011-8-3 18:57:49 | 显示全部楼层
这个必须记号啊!!!
这个平台太棒了

出0入0汤圆

发表于 2011-8-11 10:56:08 | 显示全部楼层
这个狠强大!

出0入0汤圆

发表于 2011-8-11 11:03:51 | 显示全部楼层
这个帖子很牛

出0入0汤圆

发表于 2011-9-8 10:26:34 | 显示全部楼层
mark

出0入0汤圆

发表于 2011-9-8 10:42:14 | 显示全部楼层
不顶不行

出0入0汤圆

发表于 2011-9-8 11:48:30 | 显示全部楼层
强帖!顶!

出0入0汤圆

发表于 2011-9-18 21:48:57 | 显示全部楼层
太牛了,佩服的五体投地

出0入0汤圆

发表于 2011-9-20 23:53:33 | 显示全部楼层
回复【楼主位】TADLAW
-----------------------------------------------------------------------

MARK

出0入0汤圆

发表于 2011-9-24 09:15:54 | 显示全部楼层
MARK~好贴~
头像被屏蔽

出0入0汤圆

发表于 2011-10-1 00:09:07 | 显示全部楼层
提示: 作者被禁止或删除 内容自动屏蔽

出0入0汤圆

发表于 2011-10-4 19:32:35 | 显示全部楼层
强帖!顶LZ

出0入0汤圆

发表于 2012-1-1 18:27:44 | 显示全部楼层
mark

出0入0汤圆

发表于 2012-1-1 19:23:55 | 显示全部楼层
很有分量的帖子,专业只是深厚!

出0入0汤圆

发表于 2012-1-7 18:26:25 | 显示全部楼层
楼主相当给力啊

出0入0汤圆

发表于 2012-1-7 21:24:05 | 显示全部楼层

出0入0汤圆

发表于 2012-1-10 15:10:28 | 显示全部楼层
很好 很强大,先做个记号 以后研究

出0入0汤圆

发表于 2012-1-10 17:34:30 | 显示全部楼层
回复【11楼】TADLAW
-----------------------------------------------------------------------
我的飞不起来,哎

出0入0汤圆

发表于 2012-1-13 16:51:25 | 显示全部楼层
回复【楼主位】TADLAW
-----------------------------------------------------------------------

顶!

出0入0汤圆

发表于 2012-2-22 16:58:32 | 显示全部楼层
恩,一直在学习你的这个帖子呵呵
加速计也需要norm?还是作为一个检验手段?

出0入0汤圆

发表于 2012-2-23 16:06:09 | 显示全部楼层
mark

出0入0汤圆

发表于 2012-2-26 02:39:12 | 显示全部楼层
顶之。学习之。

出0入0汤圆

发表于 2012-5-22 00:18:10 | 显示全部楼层
写得不错,正好在研究HMC5883L,学习

出0入0汤圆

发表于 2012-5-25 13:27:05 | 显示全部楼层
这次是研究的态度和做事的方法,LZ关注的算法上的,注重系统应用!不错,可惜资料下载不了!

出0入0汤圆

发表于 2012-5-25 16:10:31 | 显示全部楼层
顶楼主!阿莫倒是不给力啊

出0入0汤圆

发表于 2012-5-25 19:03:46 | 显示全部楼层
非常棒的分享及貼文!!!

出0入0汤圆

发表于 2012-7-15 23:07:10 | 显示全部楼层
没看懂啊 楼主

出0入0汤圆

发表于 2012-7-20 13:07:01 | 显示全部楼层
很强的东西,等手头的东西结束,参与这个项目

出50入0汤圆

发表于 2012-7-20 23:11:42 | 显示全部楼层
mark,这个有看头

出0入0汤圆

发表于 2012-9-2 00:45:23 | 显示全部楼层
真棒!!!!!!!

出0入0汤圆

发表于 2013-3-12 17:17:06 | 显示全部楼层
lsm303读出来的数据怎么处理   是 调用里面的math。h里面的函数了 但是能不能讲讲原理啊

出0入0汤圆

发表于 2013-3-19 14:59:14 | 显示全部楼层
TADLAW 发表于 2011-2-3 12:32
回复【10楼】MAPGPS  
-----------------------------------------------------------------------
先用单 ...

看不起他的连接部分怎么做的。楼主知道吗?

出0入0汤圆

发表于 2013-8-14 21:04:51 | 显示全部楼层
好东西 ,楼主能否加一下qq ,651553291, 其他方式都受限,我在用ST的lsm303d 电子罗盘 谢谢!

出0入0汤圆

发表于 2014-3-13 16:09:08 | 显示全部楼层
这个帖子竟然沉了

出0入0汤圆

发表于 2014-7-8 21:16:27 | 显示全部楼层
谢谢,VPYTHON,学习您有资料吗,能推荐一下不,谢谢

出0入0汤圆

发表于 2014-7-8 22:21:18 | 显示全部楼层
相当专业 值得好好学习

出0入0汤圆

发表于 2014-9-17 22:07:17 | 显示全部楼层
好帖必须顶!!

出0入0汤圆

发表于 2014-9-23 19:23:59 | 显示全部楼层
顶上去。
回帖提示: 反政府言论将被立即封锁ID 在按“提交”前,请自问一下:我这样表达会给举报吗,会给自己惹麻烦吗? 另外:尽量不要使用Mark、顶等没有意义的回复。不得大量使用大字体和彩色字。【本论坛不允许直接上传手机拍摄图片,浪费大家下载带宽和论坛服务器空间,请压缩后(图片小于1兆)才上传。压缩方法可以在微信里面发给自己(不要勾选“原图),然后下载,就能得到压缩后的图片】。另外,手机版只能上传图片,要上传附件需要切换到电脑版(不需要使用电脑,手机上切换到电脑版就行,页面底部)。
您需要登录后才可以回帖 登录 | 注册

本版积分规则

手机版|Archiver|amobbs.com 阿莫电子技术论坛 ( 粤ICP备2022115958号, 版权所有:东莞阿莫电子贸易商行 创办于2004年 (公安交互式论坛备案:44190002001997 ) )

GMT+8, 2024-6-11 03:22

© Since 2004 www.amobbs.com, 原www.ourdev.cn, 原www.ouravr.com

快速回复 返回顶部 返回列表