|
|
|
![]() |
|
|||||||
|
||||||||
![]() |
| Thread Tools | Rate Thread | Display Modes |
|
#1
|
|||
|
|||
|
Need help with Gyro = Analog Devices ADXRS150EB
I'm testing autonomous mode for IRI and "TURN" isn't working. Robot turns, but won't stop turning.
I'm working blind on this because our programmers were very capable, so I didn't stick my nose in the code, nor the control system. Also, I have no idea where the documentation for the gyro is. What I do know is: The code worked at the last regional, West Michigan. A printf shows that Gyro_TImer() counts up as expected. However, Gyro_Angle() also counts up (but at a much slower rate than the timer) even though the robot was stationary. Is that normal? I expected to see the angle change only when the robot rotated. |
|
#2
|
||||
|
||||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
Check the sensor and the wiring to the sensor for damage. Regards, Mike |
|
#3
|
|||
|
|||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
Wires are good & VOM measures a few K ohms between supply and ground, a few hundred K ohms between the output and either of those. Other than that and looking for a change when active, I don't know how to check the sensor. After it cools down a bit (it's been hot & muggy here) I may take a look at Get_Gyro_Rate(). However, I don't expect it to be any more informative than Gyro_Angle(), which doesn't care if the gyro is hooked up or not. It always drifts slowly upward. We could, in case the gyro is DOA, resort to counting wheel revs. But like I said - it's hot here. So maybe we'll spend those first 15 seconds/match in silent meditation. ![]() |
|
#4
|
||||
|
||||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
Quote:
Code:
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' ADXRS150EB and ADXRS300EB gyros. Data sheets for these devices are included. Support for the ADXRS401EB is also 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. This software makes the assumption that when it's running, it solely controls the analog to digital conversion hardware and that only the gyro, on analog input one, is being sampled. Calling Disable_Gyro() will disable the gyro software and allow you to use the ADC for other purposes. 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 the robot controller's analog input 1. For optimum performance, you'll need to calibrate the scaling factor to match that of your gyro's. 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 adversly 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 motonless, 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 6.60. 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. **************************************************************** 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. Disable_Gyro() This function should be called when the gyro functionality is no longer needed, thus reclaiming the time spent servicing the timer 2 interrupts. Initialize_ADC() This function initializes the analog to digital conversion hardware. This is called by Initialize_Gyro() above and shouldn't be called directly. Initialize_Timer_2() This function initializes and starts timer2. This is called by Initialize_Gyro() above and shouldn't be called directly. Timer_2_Int_Handler() This function is automatically called when timer 2 causes an interrupt and shouldn't be called directly. **************************************************************** Seven things must be done before this software will work correctly on the FRC-RC: 1) The gyro's rate output is wired to analog input 1. 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 this source file. The statement should look like this: #include "gyro.h". 3) Initialize_Gyro() must be called from user_routines.c/ User_Initialization(). 4) The timer 2 interrupt handler, Timer_2_Int_Handler(), must be installed in User_Routines_Fast.c/InterruptHandlerLow(). See the accompanying copy of User_Routines_Fast.c to see how this is done. 5) You must select the gyro you're using from a list in gyro.h and if needed, remove the // in front of it's #define. 6) A gyro bias calculation must take place using the functions Start_Gyro_Bias_Calc() & Stop_Gyro_Bias_Calc() described above. 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. Nine things must be done before this software will work correctly on the EDU-RC: 1) The gyro's rate output is wired to analog input 1. 2) IO1 must be configured as an "INPUT" in user_routines.c/ User_Initialization(). 3) The call to Set_Number_of_Analog_Channels() must configure at least one analog channel. 4) A #include statement for the gyro.h header file must be included at the beginning of each source file that calls the functions in this source file. The statement should look like this: #include "gyro.h". 5) Initialize_Gyro() must be called from user_routines.c/ User_Initialization(). 6) The timer 2 interrupt handler, Timer_2_Int_Handler(), must be installed in User_Routines_Fast.c/InterruptHandlerLow(). See the accompanying copy of User_Routines_Fast.c to see how this is done. 7) You must select the gyro you're using from a list in gyro.h and if needed, remove the // in front of it's #define. 8) A gyro bias calculation must take place using the functions Start_Gyro_Bias_Calc() & Stop_Gyro_Bias_Calc() described above. This must be done several hundred milliseconds after the gyro powers-up and is allowed to stabilize. 9) For optimal performance, you'll need to calibrate the gyro scaling factor using the instructions above or those included in gyro.h. Kevin Watson kevinw@jpl.nasa.gov |
|
#5
|
||||
|
||||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
|
|
#6
|
|||
|
|||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
Well, there is something going on there. With pots disconnected, Angle counts negative to -1200 in the time it takes the timer to count 5K. With pots hooked up, Angle counts positive to 283 in the same amount of time. In either case, rotating gyro had no effect on the outcome. Was going to launch autonomous with pots disconnected, but it started to rain. Driveway test site ![]() Been through most of Kevin's notes & code, which my kids had made use of to begin with. Nothing struck me as out of place; except that Start_Gyro_Bias_Calc() Stop_Gyro_Bias_Calc() wasn't called. Will give that a go, but seems to me that it's just fine tuning, not a show stopper. |
|
#7
|
||||||
|
||||||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
See this thread for more discussion about this issue and a few ideas for combining the gyro code with other analog sensors: http://www.chiefdelphi.com/forums/sh...ad.php?t=34500 |
|
#8
|
|||
|
|||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
Thanks again, OAO Jack Last edited by Jack Jones : 17-07-2005 at 23:13. |
|
#9
|
||||
|
||||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
-Kevin |
|
#10
|
|||
|
|||
|
Re: Need help with Gyro = Analog Devices ADXRS150EB
Quote:
OTOH, I've learned just enough to be curious so I'll take you up on the offer after we get back from IRI.Thanks, Jack |
![]() |
| Thread Tools | |
| Display Modes | Rate This Thread |
|
|
Similar Threads
|
||||
| Thread | Thread Starter | Forum | Replies | Last Post |
| Updated: Example Gyro Interface Code | Kevin Watson | Programming | 2 | 28-03-2005 04:36 |
| Example gyro code released. | Kevin Watson | Programming | 60 | 17-03-2005 18:32 |
| Using gyro with other analog sensors...again | demerski | Programming | 0 | 19-02-2005 08:23 |
| Gyro Troubles | SteveO | Programming | 13 | 30-01-2005 16:46 |
| How do you wire ADXRS150EB gyro? | MaxM | Electrical | 2 | 16-02-2004 13:43 |