Gyroscope Code


#1

For those who might be interested, I’ve just posted updated gyroscope interface code for IFI’s robot controllers. The code has been significantly reworked to use the new ADC interface code, which allows the programmer to use other analog sensors alongside a gyroscope without affecting the performance or operation of the gyroscope. In addition, significant performance improvements can be realized using the new oversampling and deadband features. The code can be found here: http://kevin.org/frc. As always, if you find a bug in the code or a problem with the documentation, please let me know.

-Kevin

Here’s the readme file:


The source code in gyro.c/.h contains a driver and supporting 
software to interface a variety of inexpensive gyros to your
robot controller. This software was tested with Analog Devices'
ADXRS401EB, ADXRS150EB and ADXRS300EB gyros. Data sheets for 
these devices are included. By default, this software is 
configured to work with a ADXRS150EB gyro, sampling at 800Hz, 
downconverting to an update rate of 50Hz by averaging sixteen 
samples per update. These parameters can be changed by editing 
gyro.h and/or adc.h.
 
Version 0.5 of the gyro interface software has been altered
to use the ADC interface provided by adc.c/.h. This change 
allows the programmer to use additional ADC channels for other 
analog sensors without affecting the performance or operation 
of your gyro. See the documentation included with adc.c/.h for 
information on how to use this new functionality.
Another new feature is the ability to specify a measurement 
deadband centered about the gyro bias. ADC measurements within 
this deadband will not be used to calculate the gyro angle or 
angular rate. This feature can have a significant impact at 
minimizing short-term drift just after a bias calculation has
taken place. To use this feature, follow the instructions 
embedded within gyro.h.
 
This source code will work with the Robovation (A/K/A EDU-RC) 
robot controller and the FIRST Robotics robot controller.
Wiring-up the ADXRS401EB, ADXRS150EB and ADXRS300EB gyro
evaluation boards is straightforward: Grab a PWM cable and cut
off the male end and strip the three wires back a centimeter 
or so. With a low wattage soldering iron, solder the white wire 
to the RATEOUT pin, solder the black wire to the AGND pin, the 
red wire to the AVCC pin, and finally connect a jumper wire 
between the AVCC and PDD pins. Plug the female end into one of 
the robot controller's analog inputs. These gyro evaluation
boards can be purchased from analog devices ([www.analog.com](http://www.analog.com/)),
and Digi-Key ([www.digikey.com](http://www.digikey.com/)). Another great source for
Analog Devices gyros is SparkFun Electronics ([www.sparkfun.com](http://www.sparkfun.com/)).
 
For optimum performance, you'll need to calibrate the scaling
factor to match that of your gyro. One way to calibrate your 
gyro is to mount it very securely to a hefty, square or 
rectangular object. Mounting the gyro to a hefty object will 
help dampen higher frequency vibrations that can adversely 
effect your measurements. Place the mounted gyro against 
another square object and start the included demonstration 
software. To get good results, the mount must be absolutely 
still when the "Calibrating Gyro Bias..." message appears on 
the terminal screen. After a few seconds, the gyro angular rate 
and angle will be sent to the terminal screen. If the angle 
drifts rapidly while the mounted gyro is motionless, you need 
to restart the software to acquire a new gyro bias measurement. 
Again, gyros are very sensitive and must be still while the bias 
is calculated. Once the gyro is running with little drift, 
rotate the mount 180 degrees and note the reported angle. If the 
angular units are set to tenths of a degree, the ideal reported 
angle is 1800. If set to milliradians, the ideal angle 1s 3142 
(Pi times a thousand). For every tenth of a percent that the 
angle is high, decrease the GYRO_CAL_FACTOR numerator by one.
Conversly, for every tenth of a percent low, increase the 
numerator by one. Repeat until you're satisfied with the 
accuracy.
 
The included project files were built with MPLAB version 7.20.
If your version of MPLAB complains about the project version, 
the best thing to do is just create a new project with MPLAB's 
project wizard. Include every file except: FRC_alltimers.lib 
and ifi_alltimers.lib and you should be able to build the code.
 
****************************************************************
Eight things must be done before this software will work 
correctly on your robot controller:
 
1) The gyro's rate output is wired to one of the analog inputs
of your robot controller and gyro.h/#define GYRO_CHANNEL is
updated with the analog channel your gyro is attached to.
 
2) A #include statement for the gyro.h header file must be 
included at the beginning of each source file that calls the 
functions in gyro.c. The statement should look like this: 
#include "gyro.h".
 
3) Initialize_Gyro() must be called from user_routines.c/
User_Initialization().
 
4) You must select the gyro you're using from a list in gyro.h
and if needed, remove the // in front of its #define.
 
5) The default angular unit is milliradians. If desired, this
can be changed to tenths of a degree by editing gyro.h
 
6) A gyro bias calculation must take place using the functions 
Start_Gyro_Bias_Calc() & Stop_Gyro_Bias_Calc() described below.
This must be done several hundred milliseconds after the gyro 
powers-up and is allowed to stabilize.
 
7) For optimal performance, you'll need to calibrate the gyro 
scaling factor using the instructions above or those included
in gyro.h.
 
8) Follow the instructions found in adc_readme.txt for
installation instructions.	
 
****************************************************************
Here's a description of the functions in gyro.c:
 
Initialize_Gyro()
This function initializes the gyro software. It should be called 
from user_routines.c/User_Initialization().
 
Get_Gyro_Rate()
This function returns the current angular rate of change in 
units of milliradians per second. If desired, the angular unit 
can be changed to tenths of a degree per second by modifying
the angular units #define entry in gyro.h
 
Get_Gyro_Angle()
This function returns the change in heading angle, in 
milliradians, since the software was initialized or 
Reset_Gyro_Angle() was called. If desired, the angular unit
can be changed to tenths of a degree by modifying the angular
units #define entry in gyro
 
Start_Gyro_Bias_Calc()
Stop_Gyro_Bias_Calc()
These functions start/stop a new gyro bias calculation. For best 
results, Start_Gyro_Bias_Calc() should be called about a second 
after the robot powers-up and while the robot is perfectly still 
with all vibration sources turned off (e.g., compressor). After
at least a second (longer is better), call Stop_Gyro_Bias_Calc()
to terminate the calibration. While a calibration is taking
place, gyro rate and angle are not updated. Once calibrated, a
call to Reset_Gyro_Angle() should take place.
 
Get_Gyro_Bias()
This function returns the current calculated gyro bias. For
extra precision, this software internally maintains a gyro bias
value that is the sum of GYRO_SAMPLES_PER_UPDATE samples of the 
gyro's analog output. By default, GYRO_SAMPLES_PER_UPDATE is
set to a value of eight in gyro.h
 
Set_Gyro_Bias()
This function can be called to manually set the gyro bias. For
extra precision, this software internally maintains a gyro bias
value that is the sum of GYRO_SAMPLES_PER_UPDATE samples of the 
gyro's analog output. By default, GYRO_SAMPLES_PER_UPDATE is
set to a value of eight in gyro.h
 
Reset_Gyro_Angle()
This function resets the integrated gyro heading angle to zero.
 
Process_Gyro_Data()
This function should be called when the ADC software reports
that new gyro data is available. Ideally this should be done
within the user_routines_fast.c/Process_Data_From_Local_IO()
function. See the enclosed copy of user_routines_fast.c for
an example of how to do this.


#2

Well, I just discovered that I left one step out of the installation instructions found in gyro_readme.txt. Here are the revised instructions:

Nine things must be done before this software will work
correctly on your robot controller:

  1. The gyro’s rate output is wired to one of the analog inputs
    of your robot controller and gyro.h/#define GYRO_CHANNEL is
    updated with the analog channel your gyro is attached to.

  2. A #include statement for the gyro.h header file must be
    included at the beginning of each source file that calls the
    functions in gyro.c. The statement should look like this:
    #include “gyro.h”.

  3. Initialize_Gyro() must be called from user_routines.c/
    User_Initialization().

  4. Process_Gyro_Data() must be called when the ADC software
    generates an update. An example of how to do this can be found
    in user_routines_fast.c/Process_Data_From_Local_IO().

  5. You must select the gyro you’re using from a list in gyro.h
    and if needed, remove the // in front of its #define.

  6. The default angular unit is milliradians. If desired, this
    can be changed to tenths of a degree by editing gyro.h

  7. A gyro bias calculation must take place using the functions
    Start_Gyro_Bias_Calc() & Stop_Gyro_Bias_Calc() described below.
    This must be done several hundred milliseconds after the gyro
    powers-up and is allowed to stabilize.

  8. For optimal performance, you’ll need to calibrate the gyro
    scaling factor using the instructions above or those included
    in gyro.h.

  9. Follow the instructions found in adc_readme.txt for
    installation instructions.

-Kevin


#3

Thanks for the contribution to the First effort. I have a What if question.

What if First includes the EasyC environment for the 2006 season? Could your code be wrapped up and included into it? How about your serial port code?

Just curios as to you opinion if First goes down this path.


#4

Yes, the code can be ported fairly easily.

-Kevin


#5

Is it possible to use a Murata gyro with the innovation controllers. If so, what changes would have to be made to the code so the controller can read the output from the gyro?


#6

Yes, they can be used. The code changes are very simple to make. If you provide me with a part number, I can add it to the list of supported gyros.

-Kevin


#7

Murata ENV-05DB


#8

I’ve updated the gyro code to support this device. As I don’t have one to test with, please let me know if you have any problems. The code can be found here: http://kevin.org/frc

-Kevin


#9

I’ve updated the gyro code with version 0.3 of the analog to digital conversion code. As always, the code can be found here: http://kevin.org/frc

-Kevin


#10

Well, I finally posted the ADC and Gyro code for the 2006 robot controller. Sorry about the delay, but I ran into a nasty bug that caused me to spend a few days in the fourth and fifth levels of programmer hell. The bug was in the design of the PIC18F8722 (yes, a bug in the sillicon) and I had to figure out what was going on. Anyway, the gyro code works really, really well with the gyro in the kit of parts. The accelerometers also work really well, but I need to do more testing before I unleash that code.

-Kevin


#11

Thanks for all the hard work! With all the great sensors this year, how many interrupts can we use? Last year we use 4 pair of Hall sensors as quad counters, which worked well. The team is reluctant to move past success…so if I use those 4 pair, is there anything left on the 18F8722? And will using the camera code claim those interrupts as well?

Thans

Jon Mittelman
mentor
Team236


#12

Kevin, you’re like my own personal Jesus.


#13

I just noticed that the gyro.h has DEFINEs to set the code to operate on a variety of gyro modules, but not the one that’s in the 2006 KOP. According to US First’s “2006_Sensor_Basic_Operation.pdf”,
The actual Yaw Rate Gyro chip used on the 2006 YRG is the AD22304.
As far as I can tell, the only significant difference is the 80 degree/sec turning rate limit (vs. 150 dps on the ADXRS150).

Is there anything that needs to be adjusted in the code to handle this particular chip, or is it good enough just to leave the DEFINE the way it came?

Thanks again,
Dave


#14

I’ve been having trouble getting the KOP gyro to work. I attached the two PWM cables to it and installed the gryo code. The output I get from the program seems to be in no way related to what is happening to the gyro. :confused: Also, why are two PWM cables used on the gyro, is one a temparture sensor(I read that it maybe somewhere)? I’m really a bit confused and any help would be greatly appreciated.


#15

I heard the head programmer from 68 talk about this…yes, it appears to have a temperature sensor onboard. He told me it measures in degrees Kelvin, but I don’t know any of the details because he is the one that tinkered with the code and got it working. The best guess we have is that the gyro readings differ based on the temp…??? Kinda strange…umm… :confused:

JBotAlan


#16

So, speaking as the only person here who has read the spec sheet, this second pwm output gives absolute temperature. There are nice little graphs relating the reading to the temperature of the chip. In that regard it could be useful. I, however, have not tinkered with that particular output.
EDIT: I set up a calibration algorithm that gives an average of the first ten values it pulls from the gyro, and sets that as neutral (after 20 program loops to give it a chance to spinup) So I feel okay ignoring the temperature output.


#17

i download the Gyro code and i think the result are not correct because when i move the gyro 90 degrees and back to 0 degrees then i not get the same values

what is the problem ??

-Naor


#18

I have a few questions again…

In adc.c, I notice that you divide the accumulated readings, to once again have a value that’s between 0 and 1024:

for(i=0; i < num_adc_channels; i++)
		{
			adc_result* = (long)(accum* >> adc_result_divisor);		
		}

But in gyro.c I notice you are factoring in ADC_RANGE in your calculations:

// Return the calculated gyro angle to the caller.
	return(((gyro_angle * GYRO_SENSITIVITY * 5L) / (ADC_RANGE * ADC_UPDATE_RATE * 2L)) * GYRO_CAL_FACTOR);

I guess I’m just a bit confused as to what is happening here. Is there a bit of math that I didn’t think about?

I have it set right now to sample four channels at 3200Hz, and to collect 16 samples before an update. This sets ADC_RANGE to 4096 and ADC_UPDATE_RATE to 3200/(16 * 4), which is 50Hz. So the ADC_RANGE seems out of place. Is the down shift of the accumulator in adc.c not supposed to be there, or is it doing something other than what I think it is?**


#19

Ugh, I’ll have to work through it. The gyro expression looks convoluted because it’s hand-tuned to minimize integer division rounding error while not overflowing the numerator. While I’m looking at it, you might consider working through it yourself using dimensional analysis. Keep in mind that gyro_angle is not in angular units <grin>.

-Kevin


#20

nvm. I’ll just wait for your response.