目次

スタートゲートセンサー

 MCR_VCへの参加で知合いになった、京都のIさんから
 他のロボットコンテストに利用する超音波センサー
 の評価依頼が来ました。



 マイコンがついているようで、電源2ピンとTRG
 ECHOの2ピンだけで、測距ができます。

 そのままでは使いにくいため、4ピンのソケットをつけ
 信号線をArduinoに接続できるようにしました。



 電子部品をみると、中央にマイコン、左にOPアンプの
 LM324、右にシリアルインタフェース用ICのMAX232C
 互換品が実装されています。

 おそらく、次のように使われているのでしょう。

 MAX232C互換ICは、5Vから正負電圧を生成する電源IC。

 LM324で40kHzのパルスを増幅し、送信デバイスに出力。
 受信デバイスの反射波を検出し、マイコンで判定可能
 となる電圧まで増幅。

 マイコンは40kHzパルス生成と反射波が来るまでの時間計測。
 外部トリガーと距離相当パルス出力処理を担当。

 マイコンは14ピンで、クロックを内蔵しているようで
 PIC16F688クラスを利用しているようです。マイコンの
 型番刻印がないので、推定でしかないですが。

 配線は簡単にして、電源の逆接続防止にLEDをつけます。



 Iさんの情報で、次のタイミングチャートで動作しているとか。



 トリガーを与えると測距後に、パルス幅で距離を返してきます。

 トリガーのパルス幅は、最小で10usというので、どれくらい
 まで許容されるのかを調べていきます。

 スイッチサイエンスのページに、Arduinoのサンプルコードが
 ありましたが、評価用途では使いにくいので、自分でスケッチ
 を作成しました。

#define OFF 0
#define ON  OFF+1

/* pin assignment */
int TRG  = 8 ;
int ECHO = 9 ;

/* variables */
int   dtime ;
float distance ;
byte td ; /* trigger width */

/* control variables */
byte eflag ;
byte sflag ;
byte sindex ;
byte sbuf[4] ;
byte cmd ;

void setup()
{
  /* initialize serial port */
  Serial.begin(9600);
  /* define digital pin */
  pinMode(TRG ,OUTPUT);
  pinMode(ECHO,INPUT);
  /* set initial state */
  digitalWrite(TRG,LOW);
  /* clear variable */
  td = 10 ;
  /* command interpreter buffer */
  sflag = OFF ;
  eflag = OFF ;
  sindex = 0 ;
}

void loop()
{
  /* line sensing */
  if ( eflag == ON ) {
    /* clear flag */
    eflag = OFF ;
    /* send trigger */
    digitalWrite(TRG,HIGH);
    delayMicroseconds(td);
    digitalWrite(TRG,LOW);
    /* delaymicroseconds(); */
    dtime = pulseIn(ECHO,HIGH); 
    /* calculate */
    distance = (340 * 1.0 * dtime / 1000) ; /* format mm */
    /* adjust */
    distance /= 2 ;
    /* show */
    Serial.print("time -> ");
    Serial.print( dtime );    
    Serial.println(" us");
    Serial.print("distance -> ");
    Serial.print( distance );    
    Serial.println(" mm");
  }
  /* serial handling */
  if ( sflag == ON ) {
    /* clear flag */
    sflag = OFF ;
    /* new line */
    Serial.println("");
    /* get command */
    cmd = *(sbuf+0) ;
    /* judge */
    if ( cmd == '?' ) {
      Serial.println("? help");
      Serial.println("e execute");
      Serial.println("i increment trigger width");
      Serial.println("d decrement trigger width");
    }
    /* execute */
    if ( cmd == 'e' ) { eflag = ON ; }
    /* increment */
    if ( cmd == 'i' ) {
      /* now value */
      Serial.print( td );
      Serial.print(" -> ");
      /* update */
      td++ ;
      if ( td > 20 ) { td = 20 ; }
      /* show */
      Serial.println( td );
    }
    /* decrement */
    if ( cmd == 'd' ) {
      /* now value */
      Serial.print( td );
      Serial.print(" -> ");
      /* update */
      td-- ;
      if ( td == 0 ) { td = 1 ; }
      /* show */
      Serial.println( td );
    }
  }
}

/* receive interrupt */
void serialEvent()
{
  char ch;
  if ( Serial.available() > 0 ) {
    /* get 1 character */
    ch = Serial.read();
    /* store */
    *(sbuf+sindex) = ch ;
    /* increment */
    sindex++ ;
    /* judge */
    if ( ch == '\r' ) {
      sindex = 0 ; 
      sflag = ON ;
    }
  }
}

 シリアルインタフェースでArduinoとPCを接続し
 Arduinoに超音波センサーを制御させます。

 コマンドインタプリタを用意し、TRGパルス幅と
 測距結果を調べます。

 コマンドは、4種としました。

 測距は、パルスが物体とセンサー間を往復する時間を
 利用して算出します。

 パルス幅測定に、pulseInを利用し、時間換算で距離を取得します。
 往復時間を測定しているので、距離を求めたら半分にしますが
 浮動小数点の計算なので、次のように1.0を乗算し、コンパイラに
 整数での計算をさせないように指示します。

    distance = (340 * 1.0 * dtime / 1000) ;

 TeraTermでの評価は、次のようになりました。



 Arduinoとセンサーの接続は、次のようにしました。



 音速は、気温により変化しますが、340m/s固定として
 計算しています。使う場合は、距離に幅を持たせての
 判定をします。

 スタートゲートセンサーとして使うには、ゲートが開いて
 いるのか、閉じているのかを判断できればよいでしょう。
 Arduinoの出力を利用し、D/Aコンバータを構成して対応
 します。

 6ビットのD/Aコンバータを接続します。



 R-2Rの抵抗を使ったD/Aコンバータですが、スタートゲートの
 状態が2値なので、このような簡易タイプで充分です。

 抵抗、OPアンプがあったりで面倒に見えますが、表面実装品
 を利用すれば、意外に小型にできます。OPアンプは、電圧を
 電源電圧まで利用したければ、CMOSタイプのRailToRail品を
 使うだけです。

 マイコンによっては、A/Dコンバータによる電圧値を
 使った方がよい場合もあるので、次のようにArduino
 にD/Aコンバータを接続して、使うことも可能です。



 Arduinoのスケッチは、以下。

#include <MsTimer2.h>

#define OFF 0
#define ON  OFF+1

#define MASK8000 0x8000
#define CHA      0x7000
#define CHB      0xf000

#define XDELAY   5

#define TDX 11

/* pin assignment */
#define TRG0_BIT 2
#define TRG1_BIT 4
#define TRG2_BIT 7
#define TRG3_BIT 0

#define ECHO0_BIT 3
#define ECHO1_BIT 5
#define ECHO2_BIT 6
#define ECHO3_BIT 9

#define CS0_BIT   0
#define CS1_BIT   1
#define XSCK_BIT  2
#define XMOSI_BIT 3
#define XLOAD_BIT 4

#define DLEDX 5

#define XTIMOUT 13000

/* global variables */
volatile byte xcnt ;
volatile unsigned long dtime[4] ;
volatile word dacv[4] ;
volatile word dacvx[4] ;
volatile byte eflag ;

/* function prototype */
void  send_dac_primitive(byte which,word xa,word xb);
void  send_dac(void);
void  send_led(byte x);
void  send_trg(byte x);
unsigned long get_duration(byte x);
word  convertv(unsigned long x);
void  update_trigger(void);

void  setup()
{
  byte i ;
  /* set initial state */
  PORTB = 0x00 ;
  PORTC = 0x13 ;
  PORTD = 0x00 ;
  /* define digital pin */
  DDRB = 0xfd ;
  DDRC = 0xff ; /* all outputs */
  DDRD = 0x96 ;
  /* clear flag */
  eflag = OFF ;
  /* clear variable */
  xcnt = 0 ;
  for ( i = 0 ; i < 4 ; i++ ) {
    *(dacv+i)  = 0 ; 
    *(dacvx+i) = 4000 ;
  } 
  /* initialize DAC */
  send_dac();
  /* 100ms period */
  MsTimer2::set(100,update_trigger);
  /* enable */ 
  MsTimer2::start();
}

void  loop()
{
  byte i ;
  /* scan */
  if ( eflag == ON ) {
    /* clear flag */
    eflag = OFF ;
    /* sensing */
    for ( i = 0 ; i < 4 ; i++ ) {
      /* trigger */
      send_trg(i) ;
      /* measure */
      *(dtime+i) = get_duration( i );
      /* wait 1ms */
      delay( 1 ) ; 
    }
    /* calculate */
    for ( i = 0 ; i < 4 ; i++ ) { *(dacvx+i) = convertv(*(dtime+i)) ; }
    /* send data to DAC */
    send_dac();
  }
}

void  send_dac_primitive(byte which,word xa,word xb)
{
  word tmp ;
  byte i ;
  byte j ;
  /* judge */
  if ( which > 1 ) return ;
  /* disable chips */
  PORTC |= 0x03 ;
  /* double transfer */
  for ( j = 0 ; j < 2 ; j++ ) {
    /* generate code */
    tmp = (CHA | (xa & 0x0fff)) ;
    if ( j == 1 ) { tmp = (CHB | (xb & 0x0fff)) ; } 
    /* enable chip select */
    if ( which == 0 ) { PORTC &= ~(1 << CS0_BIT) ; }
    if ( which == 1 ) { PORTC &= ~(1 << CS1_BIT) ; }
    /* bit transfer */
    for ( i = 0 ; i < 16 ; i++ ) {
      /* impress data */
      PORTC &= ~(1 << XMOSI_BIT) ;
      if ( tmp & MASK8000 ) { PORTC |= (1 << XMOSI_BIT) ; }
      delayMicroseconds(1);
      /* SCK : H */
      PORTC |=  (1 << XSCK_BIT) ;
      /* shift */
      tmp <<= 1 ;
      /* SCK : L */
      PORTC &= ~(1 << XSCK_BIT) ;
    }
    /* disable chip select */
    PORTC |= 0x03 ;
    delayMicroseconds(1);
  }
}

void send_dac(void)
{
  byte j ;
  /* update */
  for ( j = 0 ; j < 4 ; j++ ) {
    if ( *(dacv+j) != *(dacvx+j) ) { *(dacv+j) = *(dacvx+j) ; }
  }
  /* send chip0 */
  send_dac_primitive(0,*(dacv+0),*(dacv+1));
  /* send chip1 */
  send_dac_primitive(1,*(dacv+2),*(dacv+3));
  /* impress DAC */
  PORTC &= ~(1 << XLOAD_BIT) ;
  delayMicroseconds(1);
  PORTC |=  (1 << XLOAD_BIT) ;
}

void send_led(byte x)
{
  if ( x ) { PORTB |=  (1 << DLEDX) ; }
  else     { PORTB &= ~(1 << DLEDX) ; }
}

void  send_trg(byte x)
{
  /* send trigger (H) */
  if ( x == 0 ) { PORTD |=  (1 << TRG0_BIT) ; }
  if ( x == 1 ) { PORTD |=  (1 << TRG1_BIT) ; }
  if ( x == 2 ) { PORTD |=  (1 << TRG2_BIT) ; }
  if ( x == 3 ) { PORTB |=  (1 << TRG3_BIT) ; }
  /* greater than 11us */
  delayMicroseconds(TDX);
  /* send trigger (L) */
  if ( x == 0 ) { PORTD &= ~(1 << TRG0_BIT) ; }
  if ( x == 1 ) { PORTD &= ~(1 << TRG1_BIT) ; }
  if ( x == 2 ) { PORTD &= ~(1 << TRG2_BIT) ; }
  if ( x == 3 ) { PORTB &= ~(1 << TRG3_BIT) ; }
  delayMicroseconds(1);
}

unsigned long get_duration(byte x)
{
  unsigned long result ;
  /* default */
  result = 0 ;
  /* judge */
  if ( x == 0 ) { result = pulseIn(ECHO0_BIT,HIGH,XTIMOUT); }
  if ( x == 1 ) { result = pulseIn(ECHO1_BIT,HIGH,XTIMOUT); }
  if ( x == 2 ) { result = pulseIn(ECHO2_BIT,HIGH,XTIMOUT); }
  if ( x == 3 ) { result = pulseIn(ECHO3_BIT,HIGH,XTIMOUT); }

  return result ;
}

word  convertv(unsigned long x)
{
  word result ;
  /* default */
  result = 4000 ;
  /* 
    bitween distance with mili meter format 
      1000us : 170mm = x : 1mm
      x = (100 / 17)us <- 1mm
  */
  if ( 0 < x && x < 2353 ) { result = word( (17.0 * x) / 10 ) ; }
  
  return result ;
}

void  update_trigger(void)
{
  eflag = ON ;
  xcnt++ ;
  send_led( xcnt & ON ); 
}

 利用D/Aコンバータは、MCP4922ですが
 1個¥200くらいで入手できます。

 物体とArduino間の距離が400mmになると
 最大値4000を設定しています。この部分
 は、最大4095まで設定できるので、走行
 させてから、範囲を確定します。

 一度測定が終わると、60ms以上時間をおいて
 測定にしないといけないようです。

 ゲートが開いたのか否かの判定は、1秒くらいで
 よいので、スタートゲートセンサーとしての問題
 は、ないでしょう。

 D/Aコンバータの動作を調べたArduinoのスケッチは以下。

#define OFF 0
#define ON  OFF+1

#define MASK8000 0x8000
#define CHA      0x7000
#define CHB      0xf000

#define XDELAY   6

/* pin assignment */
#define CS0_BIT   0
#define CS1_BIT   1
#define XSCK_BIT  2
#define XMOSI_BIT 3
#define XLOAD_BIT 4

volatile byte sflag ;
volatile byte sindex ;
volatile byte sbuf[8] ;
volatile byte cmd ;
volatile word xregx ;
volatile word xchx ;
volatile word xcha ;
volatile word xchb ;

void send_dac_data(byte xch,word x);
void show_help();
byte get_hex(char x);

void show_help()
{
  Serial.println("? help");
  Serial.println("C set or clear Chip Select");
  Serial.println("I set or clear SI signal");
  Serial.println("K set or clear SCK signal");
  Serial.println("L set or clear LOAD signal");
  Serial.println("S set DAC value 0000-4095(integer)");
  Serial.println("A show both values");
}

void setup()
{
  /* initialize serial */
  Serial.begin(9600);
  /* define digital pin */
  DDRD = 0x96 ;
  DDRB = 0xfd ;
  DDRC = 0xff ; /* all outputs */
  /* set initial state */
  PORTD = 0x00 ;
  PORTB = 0x00 ;
  PORTC = 0x13 ;
  /* clear event flag */
  sflag = OFF ;
  /* clear variables */
  xregx = 0 ;
  xcha  = 0 ;
  xchb  = 0 ;
}

void loop()
{
  /* command interpreter */
  if ( sflag == ON ) {
    /* clear flag */
    sflag = OFF ;
    /* new line */
    Serial.println("");
    /* get command */
    cmd = *(sbuf+sindex);
    /* help */
    if ( cmd == '?' ) { show_help() ; }
    /* control chip select signal */
    if ( cmd == 'C' ) {
      PORTC &= ~(1 << CS0_BIT) ;
      if ( *(sbuf+1) == '1' ) { PORTC |= (1 << CS0_BIT) ; }
    }
    /* control data signal */
    if ( cmd == 'D' ) {
      PORTC &= ~(1 << XMOSI_BIT) ;
      if ( *(sbuf+1) == '1' ) { PORTC |=  (1 << XMOSI_BIT) ; }
    }
    /* control sck signal */
    if ( cmd == 'K' ) {
      PORTC &= ~(1 << XSCK_BIT) ;
      if ( *(sbuf+1) == '1' ) { PORTC |=  (1 << XSCK_BIT) ; }
    }
    /* control load signal */
    if ( cmd == 'L' ) {
      PORTC &= ~(1 << XLOAD_BIT) ;
      if ( *(sbuf+1) == '1' ) { PORTC |=  (1 << XLOAD_BIT) ; }
    }
    /* send data to DAC */
    if ( cmd == 'S' ) {
      /* get 12 bits data */
      xregx = 0 ;
      xregx = xregx * 10 + get_hex( *(sbuf+1) ) ;
      xregx = xregx * 10 + get_hex( *(sbuf+2) ) ;
      xregx = xregx * 10 + get_hex( *(sbuf+3) ) ;
      xregx = xregx * 10 + get_hex( *(sbuf+4) ) ;
      /* judge channel */
      xchx = get_hex( *(sbuf+5) ) ;
      /* store */
      if ( xchx ) { xchb = xregx ; }
      else        { xcha = xregx ; }
      /* impress */
      send_dac_data(xchx,xregx);
    }
    /* show both values */
    if ( cmd == 'A' ) {
      /* channel 0 */
      Serial.println( xcha );
      /* channel 1 */
      Serial.println( xchb );
    }
  }
}

void send_dac_data(byte xch,word x)
{
  byte ii ;
  word tmp ;
  /* generate code */
  tmp = CHA | x ;
  if ( xch & 1 ) { tmp = CHB | x ; }
  /* enable chip select */
  PORTC &= ~(1 << CS0_BIT) ;
  /* repeat */
  for ( ii = 0 ; ii < 16 ; ii++ ) {
    /* impress data */
    PORTC &= ~(1 << XMOSI_BIT) ;
    if ( tmp & MASK8000 ) { PORTC |=  (1 << XMOSI_BIT) ; }
    /* clock : H */
    PORTC |=  (1 << XSCK_BIT) ;
    /* shift */
    tmp <<= 1 ;
    /* clock : L */
    PORTC &= ~(1 << XSCK_BIT) ;
  }
  /* disable chip select */
  PORTC |=  (1 << CS0_BIT) ;
  /* send latch pulse */
  PORTC &= ~(1 << XLOAD_BIT) ;
  delayMicroseconds(XDELAY);
  PORTC |=  (1 << XLOAD_BIT) ;
}

/* receive interrupt */
void serialEvent()
{
  char ch;
  if ( Serial.available() > 0 ) {
    /* get 1 character */
    ch = Serial.read();
    /* store */
    *(sbuf+sindex) = ch ;
    /* increment */
    sindex++ ;
    /* judge */
    if ( ch == '\r' ) {
      sindex = 0 ; 
      sflag = ON ;
    }
  }
}

byte get_hex(char x)
{
  byte result ;
  /* default */
  result = 0 ;
  /* judge */
  if ( '0' <= x && x <= '9' ) { result = x - '0' ; } 
  if ( 'A' <= x && x <= 'F' ) { result = x - 'A' + 10 ; } 
  if ( 'a' <= x && x <= 'f' ) { result = x - 'a' + 10 ; } 
 
  return result ;
}

 Arduinoから出力する信号nCS0、SDI、SCK、nLOADを
 各々0か1に設定できるようにしました。

 各信号を担当するコマンドを用意し、それらの
 ピンの論理値が仕様通りかを確認後、DACチップ
 にパラメータを転送し、出力電圧を確認しました。

 コマンドを用意し、次の仕様で使えるように設定。

 CPLDでもDAC1個の動作を確認しました。
 VHDLコードは、以下。

library IEEE;
use IEEE.STD_LOGIC_1164.ALL;
use IEEE.STD_LOGIC_ARITH.ALL;
use IEEE.STD_LOGIC_UNSIGNED.ALL;

entity cdac is
  Port (
    -- system 
    nRESET : in  std_logic;
    CLOCK  : in  std_logic;
    -- dac control
    nCS    : out std_logic ;
    SIX    : out std_logic ;
    CKX    : out std_logic ;
    nLOAD  : out std_logic ;
    -- control
    ATRG   : in  std_logic ;
    BTRG   : in  std_logic ;
    DATX   : in  std_logic_vector(7 downto 0) --;
  );
end cdac;

architecture Behavioral of cdac is
  -- trigger 
  signal iATRG_SFT : std_logic_vector(2 downto 0) ;
  signal iBTRG_SFT : std_logic_vector(2 downto 0) ;
  signal iATRG     : std_logic ;
  signal iBTRG     : std_logic ;
  -- DAC control
  signal iCS   : std_logic ;
  signal iSIX  : std_logic ;
  signal iCKX  : std_logic ;
  signal iLOAD : std_logic ;
  -- sequencer
  signal iSTATE : integer range 0 to 7 ;
  signal iCNT   : integer range 0 to 16 ;
  signal iREG   : std_logic_vector(15 downto 0) ;
begin
  -- output 
  nCS   <= not iCS ;
  SIX   <= iSIX ;
  CKX   <= iCKX ;
  nLOAD <= not iLOAD ;

  -- synchronizer
  process( nRESET , CLOCK )
  begin
    if ( nRESET = '0' ) then
      iATRG_SFT <= "000" ;
      iBTRG_SFT <= "000" ;
    elsif rising_edge( CLOCK ) then
      iATRG_SFT <= iATRG_SFT(1 downto 0) & ATRG ;
      iBTRG_SFT <= iBTRG_SFT(1 downto 0) & BTRG ;
    end if;
  end process;
  iATRG <= '1' when ( iATRG_SFT = "011" ) else '0' ;
  iBTRG <= '1' when ( iBTRG_SFT = "011" ) else '0' ;

  -- sequencer
  process( nRESET , CLOCK )
  begin
    if ( nRESET = '0' ) then
      iSTATE <= 0 ;
      iCNT   <= 0 ;
      iREG   <= (others => '0') ;
    elsif rising_edge( CLOCK ) then
      case iSTATE is
        -- wait trigger
        when 0 => if ( iATRG = '1' ) then
                    iSTATE <= 1 ;
                    iREG(15 downto 8) <= "01111001" ;
                  elsif ( iBTRG = '1' ) then
                    iSTATE <= 1 ;
                    iREG(15 downto 8) <= "11110111" ;
                  else
                    iSTATE <= 0 ;
                  end if ;
        -- get lower byte 
        when 1 => iSTATE <= 2 ;
                  iREG(7 downto 0) <= DATX ;
        -- set counter
        when 2 => iSTATE <= 3 ;
                  iCNT   <= 16 ;
        -- judge
        when 3 => if ( iCNT = 0 ) then
                    iSTATE <= 6 ;
                  else
                    iSTATE <= 4 ;
                  end if ;
        -- send trigger
        when 4 => iSTATE <= 5 ;
        -- counter decrement and shift
        when 5 => iSTATE <= 3 ;
                  iREG   <= iREG(14 downto 0) & '0' ;
                  iCNT   <= iCNT - 1 ;
        -- send LOAD
        when 6 => iSTATE <= 7 ;
        -- return first state 
        when 7 => iSTATE <= 0 ;
        -- default 
        when others => 
                  iSTATE <= 0 ;
      end case ;
    end if;
  end process;
  iCS   <= '1' when ( iSTATE > 2 and iSTATE < 6 ) else '0' ;
  iSIX  <= iREG(15) ;
  iCKX  <= '1' when ( iSTATE = 4 ) else '0' ;
  iLOAD <= '1' when ( iSTATE = 6 ) else '0' ;

end Behavioral;

 CPLDには、XC9572を利用しました。
 ピンアサインは、以下。

# system 
NET "CLOCK"  LOC = "P5"  ;
NET "nRESET" LOC = "P39" ;

# BUS
NET "DATX<7>" LOC = "P44" ;
NET "DATX<6>" LOC = "P43" ;
NET "DATX<5>" LOC = "P42" ;
NET "DATX<4>" LOC = "P40" ;
NET "DATX<3>" LOC = "P38" ;
NET "DATX<2>" LOC = "P37" ;
NET "DATX<1>" LOC = "P36" ;
NET "DATX<0>" LOC = "P35" ;

# trigger
NET "ATRG" LOC = "P8" ;
NET "BTRG" LOC = "P9" ;

# DAC control
NET "nCS"   LOC = "P11" ;
NET "SIX"   LOC = "P12" ;
NET "CKX"   LOC = "P13" ;
NET "nLOAD" LOC = "P14" ;


 スタートゲートセンサーとバンパーに接続する
 マイクロスイッチの実験は、ブレッドボード上
 でもやっています。



 マイクロスイッチのテストに利用するメカは
 以下です。



 無限軌道を持ったメカが、マイクロスイッチの
 ヒンジを押せば、GUI画面に接触したと文字列
 を表示します。



 MCRで利用する場合、スタートゲートがオープンか
 クローズだけでよいので、次の仕様で動作する電子
 回路で充分です。

 トリガー出力後、3ms以内にECHOがHとなれば
 ゲートはクローズ。3msを超え、ECHOがHに
 なったなら、ゲートはオープン。

 音速を340m/sとすると、3msでは1020mmになり
 音波が往復するとすると、マシンとゲート間の
 距離は510mmあることに。実際は、100mm程度に
 するので、ECHOが3ms後にHになるのはゲートが
 オープンと判断します。

 AVRやPICのような、ピン数の少ないマイコンで
 対応できますが、CPLDでも実現できます。

 XC9572の中に入れるデジタル回路を作成しました。

library IEEE;
use IEEE.STD_LOGIC_1164.ALL;
use IEEE.STD_LOGIC_ARITH.ALL;
use IEEE.STD_LOGIC_UNSIGNED.ALL;

entity usensor is
  port (
    -- system
    nRESET : in  std_logic ;
    CLOCK  : in  std_logic ; -- 4MHz
    -- sensor handler signal
    UTRG   : out std_logic ; -- TRG
    URES   : in  std_logic ; -- ECHO
    -- gate status (1:close 0:open)
    GSTATE : out std_logic ;
    -- monitor
    MCLK   : out std_logic ;
    MGSTATE: out std_logic --;
  );
end usensor ;

architecture behavioral of usensor is
  -- divider
  signal iCLK : std_logic ;
  signal iCNT : integer range 0 to 39 ;
  -- 60ms generator
  signal iSTRG : std_logic ;
  signal iSCNT : integer range 0 to 5999 ;
  -- timer out generator
  signal iTOUT : std_logic ;
  signal iTCNT : integer range 0 to 300 ;
  -- trigger
  signal iURES     : std_logic ;
  signal iURES_SFT : std_logic_vector(2 downto 0) ;
  -- sequencer
  signal iSTATE  : std_logic_vector(1 downto 0) ;
  signal iGSTATE : std_logic ;
begin
  -- output
  UTRG <= '1' when ( iSTATE = "01" ) else '0' ;
  GSTATE <= iGSTATE ;

  -- monitor
  MCLK    <= not iCLK ;
  MGSTATE <= not iGSTATE ;

  -- clock divider CLOCK = 4MHz
  process (nRESET,CLOCK)
  begin
    if ( nRESET = '0' ) then
      iCNT <= 0 ;
    elsif rising_edge(CLOCK) then
      if ( iCNT = 39 ) then
        iCNT <= 0 ;
      else
        iCNT <= iCNT + 1 ;
      end if ;
    end if ;
  end process ;
  iCLK <= '1' when ( iCNT = 0 ) else '0' ; -- 100kHz(10us)

  -- 60ms generator 
  process (nRESET,iCLK)
  begin
    if ( nRESET = '0' ) then
      iSCNT <= 0 ;
    elsif rising_edge(iCLK) then
      if ( iSCNT = 5999 ) then
        iSCNT <= 0 ;
      else
        iSCNT <= iSCNT + 1 ;
      end if ;
    end if ;
  end process ;
  iSTRG <= '1' when ( iSCNT = 0 ) else '0' ;

  -- time out
  process (nRESET,iCLK)
  begin
    if ( nRESET = '0' ) then
      iTCNT <= 0 ;
    elsif rising_edge(iCLK) then
      if ( iSTATE = "01" or iTCNT = 300 ) then
        iTCNT <= 0 ;
      else
        iTCNT <= iTCNT + 1 ;
      end if ;
    end if ;
  end process ;
  iTOUT <= '1' when ( iTCNT = 299 ) else '0' ;

  -- synchronizer
  process (nRESET,iCLK)
  begin
    if ( nRESET = '0' ) then
      iURES_SFT <= "000" ;
    elsif rising_edge(iCLK) then
      iURES_SFT <= iURES_SFT(1 downto 0) & URES ;
    end if ;
  end process ;
  iURES <= '1' when ( iURES_SFT = "001" ) else '0' ;

  -- sequencer
  process (nRESET,iCLK)
  begin
    if ( nRESET = '0' ) then
      iSTATE  <= "00" ;
      iGSTATE <= '0' ;
    elsif rising_edge(iCLK) then
      case conv_integer(iSTATE) is
        -- wait trigger
        when 0 => if ( iSTRG = '1' ) then
                    iSTATE <= "01" ;
                  else
                    iSTATE <= "00" ;
                  end if ;
        -- reset and send trigger
        when 1 => iSTATE <= "11" ;
        -- wait trigger
        when 3 => if ( iURES = '1' ) then -- answer back
                    iSTATE  <= "10" ;
                    iGSTATE <= '1' ;
                  elsif ( iTOUT = '1' ) then -- time out
                    iSTATE  <= "10" ;
                    iGSTATE <= '0' ;
                  else
                    iSTATE <= "11" ;
                  end if ;
        -- return first state
        when 2 => iSTATE <= "00" ;
        -- default
        when others => 
                  iSTATE <= "00" ;
      end case ;
    end if ;
  end process ;

end behavioral;

 シーケンサを利用し、60msごとに計測していきます。
 トリガーTRGを10usだけHにし、3ms以内にECHOがHに
 なるかタイムアウトするかで、ゲートの開閉情報を
 出力します。

 ピンアサインは、以下としました。

# system
NET "CLOCK"  LOC = "P5"  ;
NET "nRESET" LOC = "P39" ;

# sensor control
NET "UTRG" LOC = "P1" ;
NET "URES" LOC = "P2" ;
NET "MCLK" LOC = "P9" ; # monitor

# gate state
NET "GSTATE"  LOC = "P11" ;
NET "MGSTATE" LOC = "P12" ; # monitor

 京都のIさんが、送ってくれた超音波センサの基板。



 この基板を利用した動作チェックは、次のスケッチを使いました。

#include <MsTimer2.h>

#define OFF 0
#define ON  OFF+1

#define MASK8000 0x8000
#define CHA      0x7000
#define CHB      0xf000

#define XDELAY   5

/* pin assignment */
#define TRG0_BIT 2
#define TRG1_BIT 4
#define TRG2_BIT 7
#define TRG3_BIT 0

#define ECHO0_BIT 3
#define ECHO1_BIT 5
#define ECHO2_BIT 6
#define ECHO3_BIT 9

#define CS0_BIT   0
#define CS1_BIT   1
#define XSCK_BIT  2
#define XMOSI_BIT 3
#define XLOAD_BIT 4

#define DLEDX 5

#define XTIMOUT 20000
#define TDX     11

#define SRECORDMAX 30

#define OFFSET 2

volatile unsigned long d0[SRECORDMAX] ;
volatile unsigned long d1[SRECORDMAX] ;
volatile unsigned long d2[SRECORDMAX] ;
volatile unsigned long d3[SRECORDMAX] ;

/* global variables */
volatile byte xcnt ;
volatile word dacv[4] ;
volatile word dacvx[4] ;
volatile byte tflag ;
volatile byte uflag ;
volatile byte mflag ;
volatile byte cmd ;
volatile byte state ;
volatile byte sindex ;
volatile char sbuf[10] ;

void  send_dac_primitive(byte which,word xa,word xb);
void  send_dac(void);
void  send_led(byte x);
void  send_trg(byte x);
unsigned long get_duration(byte x);
word  convertv(unsigned long x);
void  rs_putchar(char x);
void  rs_puts(char *x);
void  crlf(void);
void  show_digit4(word x);
void  show_help(void);
byte  get_hex(char x);
void  update_trigger(void)
{
  tflag = ON ;
  send_led( xcnt & ON );
  xcnt++ ;
}
word  calcx(word x);

void  setup()
{
  byte i ;
  /* use serial terminal */
  Serial.begin(9600);
  /* set initial state */
  PORTB = 0b00000000 ;
  PORTC = 0b00011111 ;
  PORTD = 0b00000001 ;
  /* define digital pin */
  DDRB = 0b11111101 ;
  DDRC = 0b11111111 ; /* all outputs */
  DDRD = 0b10010110 ;
  /* clear flags */
  tflag = OFF ;
  mflag = OFF ;
  uflag = OFF ;
  /* initialize variables */
  sindex = 0 ;
  state = SRECORDMAX ;
  xcnt = 0 ;
  {
    for ( i = 0 ; i < 4 ; i++ ) {
      *(dacv+i) = 0 ;
      *(dacvx+i) = 4000 ;
    } 
    /* initialize DAC */
    send_dac();
  }
  /* 1000ms period */
  MsTimer2::set(1000,update_trigger);
  /* enable */ 
  MsTimer2::start();
}

void  loop()
{
  byte  i ;
  byte  j ;
  word  dv ;
  unsigned long dtime[4] ;
  /* command interpreter */
  if ( uflag == ON ) {
    /* clear flag */
    uflag = OFF ;
    /* new line */
    crlf();
    /* get command */
    cmd = *(sbuf+0) ;
    /* help */
    if ( cmd == '?' ) { show_help() ; }
    /* start measure */
    if ( cmd == 'B' ) {
      state = 0 ;
      mflag = ON ; 
      rs_puts("Start ");
    }
    /* set DAC */
    if ( cmd == 'D' ) {
      /* get channel number */
      i = get_hex( *(sbuf+1) ); 
      /* get value */
      dv = 0 ;
      for ( j = 0 ; j < 4 ; j++ ) {
        if ( *(sbuf+j+2) == '\r' ) break ;
        dv *= 10 ;
        dv += get_hex( *(sbuf+j+2) );
      }
      /* judge */
      if ( dv > 4095 ) {
        rs_puts("out of range !");
        crlf();
      }
      /* store and show */
      if ( i < 4 ) { *(dacvx+i) = dv ; }
      /* send data to DAC */
      send_dac();
    }
    /* show DAC values */
    if ( cmd == 'd' ) {
      for ( j = 0 ; j < 4 ; j++ ) {
        rs_putchar(' '); Serial.print( j ) ;
        rs_putchar(' '); Serial.print( *(dacvx+j) ) ;
        crlf();
      }
    }
    /* show records */
    if ( cmd == 'S' || cmd == 'R' ) {
      for ( i = 0 ; i < SRECORDMAX ; i++ ) {
        /* copy */
        *(dtime+0) = *(d0+i) ;
        *(dtime+1) = *(d1+i) ;
        *(dtime+2) = *(d2+i) ;
        *(dtime+3) = *(d3+i) ;
        /* repeat */
        if ( cmd == 'R' ) {
          /* copy */
          *(dacvx+0) = convertv( *(d0+i) ) ;
          *(dacvx+1) = convertv( *(d1+i) ) ;
          *(dacvx+2) = convertv( *(d2+i) ) ;
          *(dacvx+3) = convertv( *(d3+i) ) ;
          /* DAC handling */
          send_dac() ;
          /* */
          delay( 1000 ) ;
        }
        /* show */
        if ( i < 10 ) { rs_putchar(' ') ; }
        rs_putchar('<');
        Serial.print( i ) ; 
        rs_putchar('>');
        for ( j = 0 ; j < 4 ; j++ ) {
          rs_putchar(' '); 
          show_digit4( *(dtime+j) ); 
          rs_putchar('-'); 
          show_digit4( convertv(*(dtime+j)) );
        }
        crlf() ;
      }
      if ( cmd == 'R' ) {
        rs_putchar('\t');
        rs_puts("Exit repeat") ;
        crlf();
      }
    }
    if ( cmd == 'F' ) {
      /* get channel */
      i = get_hex( *(sbuf+1) );
      /* get value */
      dv = 0 ;
      for ( j = 0 ; j < 4 ; j++ ) {
        if ( *(sbuf+j+4) == '\r' ) break ;
        dv *= 10 ;
        dv += get_hex( *(sbuf+j+4) );
      }
      /* get location */
      j = 10 * get_hex( *(sbuf+2) ) + get_hex( *(sbuf+3) ) ;
      /* fill */
      if ( j < SRECORDMAX ) {
        if ( i == 0 ) { *(d0+j) = dv ; }
        if ( i == 1 ) { *(d1+j) = dv ; }
        if ( i == 2 ) { *(d2+j) = dv ; }
        if ( i == 3 ) { *(d3+j) = dv ; }
      }
    }
  }
  /* scan */
  if ( tflag == ON ) {
    /* clear flag */
    tflag = OFF ;
    /* measure */
    if ( mflag == ON ) {
      for ( i = 0 ; i < 4 ; i++ ) {
        /* trigger */
        send_trg( i ) ; 
        /* duration */
        *(dtime+i) = get_duration( i ) ;
        /* convert */
        *(dacvx+i) = convertv( *(dtime+i) ) ;
        /* 1ms */
        delay( 1 ) ;
      }
      /* send data to DAC */
      send_dac();
    }
    /* store */
    if ( state < SRECORDMAX ) {
      /* copy */
      *(d0+state) = *(dtime+0) ;
      *(d1+state) = *(dtime+1) ;
      *(d2+state) = *(dtime+2) ;
      *(d3+state) = *(dtime+3) ;
      /* monitor */
      i = '+' ;
      if ( state & ON ) { i = '-' ; }
      rs_putchar( i );
      /* update */
      state++ ;
      if ( state == SRECORDMAX ) { 
        rs_puts(" Complete !");
        crlf();
        mflag = OFF ;
      }
    }
  }
}

void  send_dac_primitive(byte which,word xa,word xb)
{
  word tmp ;
  byte  i ;
  byte  j ;
  /* judge */
  if ( which > 1 ) return ;
  /* disable chips */
  PORTC |= 0x03 ;
  /* double transfer */
  for ( j = 0 ; j < 2 ; j++ ) {
    /* generate code */
    tmp = (CHA | (xa & 0x0fff)) ;
    if ( j == 1 ) { tmp = (CHB | (xb & 0x0fff)) ; } 
    /* enable chip select */
    if ( which == 0 ) { PORTC &= ~(1 << CS0_BIT) ; }
    if ( which == 1 ) { PORTC &= ~(1 << CS1_BIT) ; }
    /* bit transfer */
    for ( i = 0 ; i < 16 ; i++ ) {
      /* impress data */
      PORTC &= ~(1 << XMOSI_BIT) ;
      if ( tmp & MASK8000 ) { PORTC |= (1 << XMOSI_BIT) ; }
      /* SCK : H */
      PORTC |=  (1 << XSCK_BIT) ;
      /* shift */
      tmp <<= 1 ;
      /* SCK : L */
      PORTC &= ~(1 << XSCK_BIT) ;
    }
    /* disable chip select */
    PORTC |= 0x03 ;
  }
}

void send_dac(void)
{
  byte j ;
  word msgx[4] ;
  /* update */
  for ( j = 0 ; j < 4 ; j++ ) { 
    if ( *(dacv+j) != *(dacvx+j) ) { *(dacv+j) = *(dacvx+j) ; } 
  }
  /* adjust */
  *(msgx+0) = calcx( *(dacv+0) );
  *(msgx+1) = calcx( *(dacv+1) );
  *(msgx+2) = calcx( *(dacv+2) );
  *(msgx+3) = calcx( *(dacv+3) );
  /* send chip0 */
  send_dac_primitive(0,*(msgx+0),*(msgx+1));
  /* send chip1 */
  send_dac_primitive(1,*(msgx+2),*(msgx+3));
  /* impress DAC */
  PORTC &= ~(1 << XLOAD_BIT) ;
  delayMicroseconds(1);
  PORTC |=  (1 << XLOAD_BIT) ;
}

void send_led(byte x)
{
  if ( x ) { PORTB |=  (1 << DLEDX) ; }
  else     { PORTB &= ~(1 << DLEDX) ; }
}

void  send_trg(byte x)
{
  /* send trigger (H) */
  if ( x == 0 ) { PORTD |=  (1 << TRG0_BIT) ; }
  if ( x == 1 ) { PORTD |=  (1 << TRG1_BIT) ; }
  if ( x == 2 ) { PORTD |=  (1 << TRG2_BIT) ; }
  if ( x == 3 ) { PORTB |=  (1 << TRG3_BIT) ; }
  /* greater than 11us */ 
  delayMicroseconds(TDX);
  /* send trigger (L) */
  if ( x == 0 ) { PORTD &= ~(1 << TRG0_BIT) ; }
  if ( x == 1 ) { PORTD &= ~(1 << TRG1_BIT) ; }
  if ( x == 2 ) { PORTD &= ~(1 << TRG2_BIT) ; }
  if ( x == 3 ) { PORTB &= ~(1 << TRG3_BIT) ; }
  delayMicroseconds(1);
}

unsigned long get_duration(byte x)
{
  unsigned long result ;
  /* default */
  result = 0 ;
  /* handling */
  if ( x == 0 ) { result = pulseIn(ECHO0_BIT,HIGH,XTIMOUT); }
  if ( x == 1 ) { result = pulseIn(ECHO1_BIT,HIGH,XTIMOUT); }
  if ( x == 2 ) { result = pulseIn(ECHO2_BIT,HIGH,XTIMOUT); }
  if ( x == 3 ) { result = pulseIn(ECHO3_BIT,HIGH,XTIMOUT); }

  return result ;
}

word  convertv(unsigned long x)
{
  word dv  ;
  /* bitween distance with mili meter format 
         1000us : 170mm = x : 1mm
         x = (100 / 17)us <- 1mm
     check range (over 400mm)
  */
  dv = 4000 ;
  if ( 0 < x && x < 2353 ) { dv = word( (17.0 * x) / 10 ) + OFFSET ; } 

  return dv ;
}

void  rs_putchar(char x)
{
  Serial.write(x);
}

void  rs_puts(char *x)
{
  while ( *x ) {
    rs_putchar(*x);
    x++ ;
  }
}

void  crlf(void)
{
  rs_putchar('\r');
  rs_putchar('\n');
}

void  show_digit4(word x)
{
  char msg[4] ;
  char i ;
  /* separate */
  for ( i = 0 ; i < 4 ; i++ ) {
    *(msg+3-i) = x % 10 + '0' ; 
    x /= 10 ;
  }
  /* zero suppress */
  if ( *(msg+0) == '0' ) {
    *(msg+0) = ' ' ;
    if ( *(msg+1) == '0' ) {
      *(msg+1) = ' ' ;
      if ( *(msg+2) == '0' ) { *(msg+2) = ' ' ; }
    }
  }
  /* send */
  for ( i = 0 ; i < 4 ; i++ ) { rs_putchar( *(msg+i) ); }
}

void  show_help(void)
{
  rs_puts("? help");                crlf();
  rs_puts("B start measure");       crlf();
  rs_puts("D put data to DAC");     crlf();
  rs_puts("d show DAC values");     crlf();
  rs_puts("S show measure record"); crlf();
  rs_puts("F put value");           crlf();
  rs_puts("R repeat");              crlf();
}

byte  get_hex(char x)
{
  byte result ;
  /* default */
  result = 0 ;
  /* convert */
  if ( '0' <= x && x <= '9' ) { result = x - '0' ; }
  if ( 'A' <= x && x <= 'F' ) { result = x - 'A' + 10 ; }
  if ( 'a' <= x && x <= 'f' ) { result = x - 'a' + 10 ; }
  
  return result ;
}

/* receive interrupt */
void serialEvent()
{
  char ch;
  if ( Serial.available() > 0 ) {
    /* get 1 character */
    ch = Serial.read();
    /* store */
    *(sbuf+sindex) = ch ;
    /* increment */
    sindex++ ;
    /* judge */
    if ( ch == '\r' ) {
      sindex = 0 ; 
      uflag = ON ;
    }
  }
}

word  calcx(word x)
{
  word result ;

  result = word( ((x * 4096.0) / 5000) );

  return result;
}

 コマンドは、次のようにして端末ソフトで計測とプレイバック
 ができるようにしてあります。

 D/Aコンバータの出力値設定は、次のようにタイプ。

  D01234{enter}
    Dに続けて、チャネル番号(0から3)、10進数で値設定
  値は1桁から4桁まで任意

 計測情報の上書きは、次のようにタイプ。

  F3053210{enter}
    Fに続けて、チャネル番号(0から3)、10進数で位置
  さらに、時間値を10進数で1桁から4桁まで任意設定

  位置は00から29の範囲の整数。

 このデバッグ用スケッチを利用し、30秒以内の
 計測をしたところ、複数の超音波センサー利用
 では、ひとつのセンサーの計測が終わったなら
 反射波が完全になくなるまで、次の計測に移ら
 ないということが、わかりました。

 今回、4チャネルの超音波センサーを利用して
 実験してみると、ECHOは1度しか出力されない
 のにも関わらず、反射波を他の超音波センサー
 が拾って、おかしな値がでる現象が発生。
 トラブルシューティングに5日ほどかかりました。

 Arduinoには、デバッガがないので、シリアル通信
 を利用しましたが、Serial.printやSerial.write
 は、メモリを消費するため、ラッパー関数を定義し
 対応しました。

 ラッパー関数は、1文字出力のSerial.writeを使い
 rs_putcharとしてあります。ラッパー関数を使って
 文字列出力関数rs_putsを定義しました。
 ラッパー関数を使うことで、フラッシュROMに入る
 コードを減らせています。

 4チャネル超音波センサー基板で使うスケッチに
 関連するメモを書いてあります。

 スケッチ概略仕様

 接続ピン
  1チャネルの超音波センサーは、4ピンを利用。
  そのうちTRGとECHOでトリガーと結果を取得する。
  各チャネルと接続ピン番号は、以下。

   チャネル0 D2  TRG0  (3)
           D3  ECHO0 (4)
   チャネル1  D4  TRG1  (5)
           D5  ECHO1 (6)
   チャネル2  D6  ECHO2 (7)
                  D7  TRG2  (8)
   チャネル3  D8  TRG3  (14)
                  D9  ECHO3 (15)

   ()内は、ATmega168のピンアサイン

  4チャネルのDAC出力は、5ピンで接続。
  ピンアサインは、以下。
   D14 DAC0_nCS0(23)
   D15 DAC0_nCS1(24)
   D16 SCK      (25)
   D17 DI       (26)
   D18 nLOAD    (27)

      チャネル0、1はDAC0_nCS0をLにしアクセス。
      チャネル2、3はDAC0_nCS1をLにしアクセス。
   チャネルに用意されているレジスタに、情報を
   転送するため、クロック(SCK)、データ(DI)、
   ロード(nLOAD)を利用。

  動作確認モニターLEDは、D13(19)に接続。

 loop処理
  120msごとに、イベントトリガーを受取り
  計測→計算→電圧出力を4回繰返す。

 スケッチ詳細仕様

 割込み
   割込みは、タイマー割込みだけを使う。
   MsTimer2ライブラリを利用し、120msごとに
   トリガーフラグをセットすると同時にLEDを
   点滅用電圧を印加。

   割込みハンドラは、関数update_triggerが担当。

   LED点灯消灯は、関数send_ledが担当。

 計測
   超音波センサーのトリガーを与え、組込み関数
   pulseInでECHOの時間長を測定。チャネル間の
   インターバルは23msほど。pulseInで13ms、測定
   後処理に2ms、他のチャネルのトリガーによる
   反射波の影響を受けなくするために8msの間隔を
   あける。

   トリガー出力は、関数send_trgが担当。
   パラメータは、チャネル番号(0->3)とした。

   エコー測定は、関数get_durationが担当。
   パラメータは、チャネル番号(0->3)とした。

 計算
   エコー測定で4チャネル分の時間を保存して
   おき、時間から距離に変換。
   時間から距離への変換は、関数convertvが担当。
   物体までの距離が400mmのとき、4000とする。

   400としないのは、浮動小数点計算による時間
   消費とDAC出力の数値変換誤差を少なくするため。

 電圧出力
   ひとつ前の計測と異なると、計算する。

   距離から電圧への換算は、関数calcxが担当。
    関数calcxは、距離を16ビット符号なし整数で
    入力し、計算結果を16ビット符号なし整数で
    出力する。

   電圧出力は、関数send_dacが担当。
    関数send_dacは、一つ前の距離と異なれば
    再計算して、4チャネル分の電圧を出力後
    関数send_dac_primitiveに情報転送を委託。

 関数仕様
  定義関数の動作概略は、以下。

  update_trigger
   タイマー割込み発生時の処理を記述。
   入力パラメータ なし
   出力パラメータ なし
   イベントフラグをセット後、モニターLEDを点滅。
   モニターLEDの点滅は、関数send_ledを利用。
   イベントフラグには、eflagを利用。
   出力パラメータを使えないので、eflagを
   グローバル変数で定義する。
   モニターLEDの点滅は、カウンタxcntの最下位ビット
   の値を利用。

  send_led
   モニターLED点滅を制御。
   入力パラメータ 点灯、消灯指定の1ビット
   出力パラメータ なし
   点灯、消灯の判定をし、ArduinoのD13ピンに
   1か0を出力。

  send_trg
   超音波センサーにTRGのパルスを出力。
   入力パラメータ 超音波センサーの番号(0->3)
   出力パラメータ なし
   対応ピンに1を出力後、11usに0に戻す。

  get_duration
   超音波センサーのECHOパルスの時間長を計測
   入力パラメータ 超音波センサーの番号(0->3)
   出力パラメータ 時間長(32ビット符号なし整数)
   対応ピンのHパルスの時間を計測。
   Arduinoの組込み関数にpulseInを利用。
   13msでタイムアウトする。
   タイムアウトまで、Hパルスが到着しないと
   ゼロとする。

  convertv
   時間長を距離に換算
   入力パラメータ 時間長(32ビット符号なし整数)
   出力パラメータ 距離の10倍値(16ビット符号なし整数)
   デフォルトは4000。
   時間長が2352.7usのとき、4000になるように計算。
   入力が0usより大きく、2353usを下回るときに計算。

  calcx
   距離に電圧に換算
   入力パラメータ 距離の10倍値(16ビット符号なし整数)
   出力パラメータ 換算値(16ビット符号なし整数)
   係数(4096/5000)を乗算

  send_dac
   電圧値を出力
   入力パラメータ なし
   出力パラメータ なし
   ひとつ前の測定値と異なれば、更新し
   距離を電圧換算値に変換。距離電圧値換算は
   関数calcxを利用。
   情報転送は、関数send_dac_primitiveを利用。
   全情報を転送後、電圧出力を指示。

  send_dac_primitive
   DACに情報を転送。
   入力パラメータ DAC番号(0->3)
           値1(16ビット符号なし整数)
           値2(16ビット符号なし整数)
   出力パラメータ なし
   DACは1デイバスに2レジスタを持つため
   値1、2で指定する。2レジスタはA、Bと
   なっているので値1はAレジスタに転送


目次

inserted by FC2 system