原帖由 xunicheng 于 2008-5-21 20:02 发表 
刚看到,单位代理挂了,白天上不了大网只能在油田网转悠。
我会尽快画PCB,然后请Gale兄审查,然后打板,然后试验…………
好像还有很多工作要做啊!!
晚上调通了二维跟踪,录像上传在这个顶楼。
http://bbs.mx3g.com/viewthread.php?tid=19061&page=1&extra=page%3D1
但现在只能说是“调通”,不能说“调好”,还是一个非常粗糙的东西。
本来晚上想要调PPM发射接收的,结果时间来不及,明天要出差,二周以后继续调。
LZ,不知道你做板子要不要钱,如果是我业余制作,我会用二颗单片机!两路检测1颗单片机,PPM信号分析重组1颗单片机,这样精度最好,开发起来也容易。而对于非工厂制作来说,多个10块钱也无所谓。
源代码我是不保守的,之前的源码也发给LZ的,但是最头疼的问题就是,我不愿意承担答疑的责任。这个小项目我分为了几个模块:
PPM.C PPM.H
SERVO.C SERVO.H
FPV.C
下面是舵机驱动模块SERVO的完整源码
--------------------
SERVO.C
--------------------
#include "Servo.h"
#include "Delay.h"
#define SERVO1 0b00100000
#define SERVO2 0b00010000
volatile BYTE Servo1,Servo2;
/////////////////////////////////////////////////////
//
// 定时器0用于舵机信号发生器
//
//5.333us计数1个
//初值为0时1.365ms中断一次
#define COUNT20MS 15 //需中断15次约为20ms
#define COUNT1MS 187 //初值为187为1ms
volatile BYTE iSignalCount;
volatile BYTE iSignal; //发送信号标志
#define IS_HEAD1 0
#define IS_SIG1 1
#define IS_HEAD2 2
#define IS_SIG2 3
#define IS_TAIL 4
SIGNAL (SIG_OVERFLOW0)
{
if(iSignal==IS_HEAD1)//发送舵机1的1ms信号头
{
PORTC|=SERVO1;//舵机1信号电平拉高
iSignal=IS_SIG1;
TCNT0=255-COUNT1MS;
}
else if(iSignal==IS_SIG1)//发送舵机1的0~1ms信号
{
iSignal=IS_HEAD2;
iSignalCount=COUNT20MS;
TCNT0=255-Servo1;
}
else if(iSignal==IS_HEAD2)//发送舵机2的1ms信号头
{
PORTC&=~SERVO1;//舵机1信号电平拉低
PORTC|=SERVO2;//舵机2信号电平拉高
iSignal=IS_SIG2;
TCNT0=255-COUNT1MS;
}
else if(iSignal==IS_SIG2)//是发送舵机2的0~1ms信号
{
iSignal=IS_TAIL;
iSignalCount=COUNT20MS;
TCNT0=255-Servo2;
}
else//发送20ms延时
{
PORTC&=~SERVO2;//信号电平拉低
iSignalCount--;
if(iSignalCount==0)
{
iSignal=IS_HEAD1;
}
}
}
void ServoInit(void)
{
DDRC|=SERVO1|SERVO2;
//////////////////////////////////////////////////////////////////
//用定时器0作为舵机信号发生器
//12M主频下64分频=5.33us计1个数
TCCR0 = 0b00000011; //定时器/计数器0控制寄存器bit7~3保留,bit2~0时钟选择
//000定时器计数器停止
//001=CK 010=CK/8 011=CK/64 100=CK/256 101=CK/1024
//110=外部T0脚,下降沿
//111=外部T0脚,上升沿
//////////////////////////////////////////////////////////////////
//初始化舵机
Servo1=100;
Servo2=100;
//////////////////////////////////////////////////////////////////
//定时器中断开关
TIMSK|= 0b00000001; //定时器中断控制OCIE2.TOIE2.TICIE1.OCIE1A.OCIE1B.TOIE1.--.TOIE0
Delay100ms(10);//等待舵机稳定
sei();//打开中断才能启动舵机
}
-----------------------
SERVO.H
-----------------------
#include <inttypes.h>
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/signal.h>
#ifndef _BYTE_
#define _BYTE_
typedef unsigned char BYTE;
typedef unsigned int WORD;
typedef unsigned long DWORD;
#endif
extern volatile BYTE Servo1,Servo2;
void ServoInit(void);
共100行代码
-------------------------------------------------------
该模块对外提供三个接口,一个是ServoInit,启动时需要调用它,然后其他程序只要设置Servo1 Servo2为0~200的值即可,模块自身会完成两路舵机的驱动。采用模块化程序设计之后,主程序专心于锁尾算法,结构就很清晰简单了。 |