To LUGNET HomepageTo LUGNET News HomepageTo LUGNET Guide Homepage
 Help on Searching
 
Post new message to lugnet.robotics.handyboardOpen lugnet.robotics.handyboard in your NNTP NewsreaderTo LUGNET News Traffic PageSign In (Members)
 Robotics / Handy Board / 3029
3028  |  3030
Subject: 
Handy Board PWM Routines
Newsgroups: 
lugnet.robotics.handyboard
Date: 
Thu, 27 Nov 1997 00:28:52 GMT
Original-From: 
Rick Moll <rickmoll@mvp.NOSPAMnet>
Viewed: 
565 times
  
I've recently been implementing a PD controller on the HB for use
in a line following robot, and have been having some problems with
instability, especially around the zero point.  I was beginning to
suspect that the 8 levels of PWM in the HB library routines were
at least part of the problem, and so started investigating the code
to see if it could be improved.

I soon discovered that there was a much more serious problem than
just the limit of only 8 different PWM levels.  It seems that the
HB library actually steps from 0% to 25% PWM!  As a first attempt
at improving the code I was able to significantly improve the
error between the input and actual PWM, by only rewriting the
"lib_hb.c" file, and with no changes to the interrupt routine in
"pcode_hb.s19".

Before I give the code I used, here's a table of the errors for
the current version of the PWM routines and the new version that
I wrote.

**********************
    Current Version

input   actual  error
----------------------
    0             0.0%
          0.0%
   10            10.0%
----------------------
   11            14.0%
         25.0%
   24             1.0%
----------------------
   25            12.5%
         37.5%
   38             0.5%
----------------------
   39            11.0%
         50.0%
   52             2.0%
----------------------
   53             9.5%
         62.5%
   66             3.5%
----------------------
   67             8.0%
         75.0%
   80             5.0%
----------------------
   81             6.5%
         87.5%
   94             6.5%
----------------------
   95             5.0%
        100.0%
  100             0.0%
**********************
**********************
    New Version

input   actual  error
----------------------
    0             0.0%
          0.0%
    6             6.0%
----------------------
    7             5.5%
         12.5%
   18             5.5%
----------------------
   19             6.0%
         25.0%
   31             6.0%
----------------------
   32             5.5%
         37.5%
   43             5.5%
----------------------
   44             6.0%
         50.0%
   56             6.0%
----------------------
   57             5.5%
         62.5%
   68             5.5%
----------------------
   69             6.0%
         75.0%
   81             6.0%
----------------------
   82             5.5%
         87.5%
   93             5.5%
----------------------
   94             6.0%
        100.0%
  100             0.0%
**********************

Note that the current version has a maximum error of 14% which is
well over twice the error of my new version.  As a matter of fact
the current version has worse error than could be achieved if only
4 levels of PWM were used.  My new version not only improves
the errors, but now allows you to achieve a PWM of 12.5%, while
the current version skips directly from 0% to 25% PWM; no wonder
I was having problems around the zero point!

While reworking the routines I also cleaned them up, flattening
the subroutine nesting to improve speed.

Note also, that I changed the bit codes in the "_speed_table"
as well.  This encoding works just as well for me, and also
keeps the PWM freq constant at 1000Hz/8 = 125Hz, rather than
having in vary between 125Hz to 500Hz as it does in the
current version.  Note that this simpler encoding could be
calculated on the fly, which would allow you to eliminate
the "_speed_talble" altogether.

--------------------------------------------------------------------

int _speed_table[9]= {
    0b00000000, /* 0 */
    0b00000001, /* 1 */
    0b00000011, /* 2 */
    0b00000111, /* 3 */
    0b00001111, /* 4 */
    0b00011111, /* 5 */
    0b00111111, /* 6 */
    0b01111111, /* 7 */
    0b11111111  /* 8 */
};

void fd(int m)
{
    if (m>=0 && m<4) {
        bit_clear(0x0e, 1<<m);   /* set dir forward */
        poke(0x22+m, 0xff);      /* set PWM 100% */
        bit_set(0x0e, 1<<(m+4)); /* turn motor on */
    }
}

void bk(int m)
{
    if (m>=0 && m<4) {
        bit_set(0x0e, 1<<m);     /* set dir backward */
        poke(0x22+m, 0xff);      /* set PWM 100% */
        bit_set(0x0e, 1<<(m+4)); /* turn motor on */
    }
}

void off(int m)
{
    bit_clear(0x0e, 1<<(m+4));
}

void alloff()
{
    poke(0x0e, 0x00);
}

void ao()
{
    alloff();
}

void motor(int m, int s)
{
    if (m>=0 && m<4) {
        if (s>100)  s =  100;
        if (s<-100) s = -100;
        if (s>=0)
            bit_clear(0x0e, 1<<m); /* set dir forward */
        else {
            bit_set(0x0e, 1<<m);   /* set dir backward */
            s = -s;
        }
                                /* (s+6) / 12.5 */
        poke(0x22+m, _speed_table[((s+6)*2)/25]); /* set PWM */
        bit_set(0x0e, 1 << (m+4)); /* turn motor on */
    }
}

--------------------------------------------------------------------

I would appreciate hearing from others who have played around with
the PWM code, or from those who have suggestions as to how the
PWM could be further improved to use more levels of PWM.

Later,

    Rick



Message has 1 Reply:
  Re: Handy Board PWM Routines
 
(...) <snip> LDAA speeda ; rotate bits in motor speed ASLA ;Rotate the speed bitmask one bit position. BCC SPDoffA ;Did we set the carry flag by shifting a "1" out ; of the MSB of the register? ADDA #1 ;We pushed a "1" out of the register, better ; (...) (27 years ago, 27-Nov-97, to lugnet.robotics.handyboard)

2 Messages in This Thread:

Entire Thread on One Page:
Nested:  All | Brief | Compact | Dots
Linear:  All | Brief | Compact
    

Custom Search

©2005 LUGNET. All rights reserved. - hosted by steinbruch.info GbR