|
|
|
![]() |
|
|||||||
|
||||||||
![]() |
|
|
Thread Tools | Rate Thread | Display Modes |
|
|
|
#1
|
|||
|
|||
|
Ok, it is 11:30pm. I have been working on this dilemma off and on since 10am this morning; researching the WPI Library, USFirst Forum, FIRST Forge, Chief Delphi, and NI Communities and i have not been able to figure out if there is a class designed to communicate with the magnetic encoders over PWM. I am looking for something along the lines of the Jaguar class (used to control the Jaguar motor controllers) or the existing encoder class (optical only or requires the usage of 2 channels A and B) but to use the single PWM unfiltered out put from the Magnetic Encoder that was included in the KOP. I have not been able to find anything to date...
If there is something out there please let me know... With the understanding that there is nothing that I can find that exists already I am looking at creating something to do this task for me. I am thinking of using a Digital Input class with the Get() function (not sure if it will work or what it will 'get' me) or an interrupt in combination with a timer to time the rise and fall of the PWM signal to calculate the time of the pulse. The only other idea i have could be to use the Counter class with the Timer class to accomplish a similar effect. Any way it is after midnight now and my pregnant wife is telling me to shut the light off and go to sleep. So i look forward to your ideas...! Thanks for your help in this mater... John Erdelyan Team 2910 Jack in the Bot |
|
#2
|
|||
|
|||
|
Re: Magnetic Encoder Programming Question\Consult
The LabVIEW example for the magnetic encoder treats the sensor output as analog. It takes the default analog values and multiplies by 72. It also shows a simple filter to handle rollover.
If you have LV installed, you might run the example so you can debug the wiring and such. Greg McKaskle |
|
#3
|
|||
|
|||
|
Re: Magnetic Encoder Programming Question\Consult
I spent the better part of a day looking at the magnetic encoder I/O options. We ruled out the analog angle output because of the slow response at the rollover point. I did not give the PWM output much thought. I tried two different approaches for which I am including code samples. The first reads the data digitally using the SPI support and the second uses two analog channels to read the sin/cos outputs (be sure to remove the solder jumper to enable these ports).
Here is the digital one using SPI: Code:
/*
* To change this template, choose Tools | Templates
* and open the template in the editor.
*/
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.fpga.tSPI;
/**
*
* @author charris
*/
public class AS5030FourWireSPI extends SensorBase {
public class AS5030Result
{
public double angle;
public int agc;
}
tSPI spi;
DigitalModule module;
int slot;
int clockPin;
int dataOutPin;
int dataInPin;
int chipSelectPin;
public AS5030FourWireSPI( int slotParam, int clockPinParam, int dataOutPinParam, int dataInPinParam, int chipSelectPinParam )
{
slot = slotParam;
clockPin = clockPinParam;
dataOutPin = dataOutPinParam;
dataInPin = dataInPinParam;
chipSelectPin = chipSelectPinParam;
// get our module
module = DigitalModule.getInstance(slot);
// create SPI instance
//spi = new tSPI();
// allocate our pins
module.allocateDIO(clockPin, false);
module.allocateDIO(dataOutPin, false);
module.allocateDIO(dataInPin, true);
module.allocateDIO(chipSelectPin, false);
// setup for SPI
tSPI.writeChannels_SCLK_Module(DigitalModule.slotToIndex(slot));
tSPI.writeChannels_SCLK_Channel(DigitalModule.remapDigitalChannel(clockPin-1));
tSPI.writeChannels_MOSI_Module(DigitalModule.slotToIndex(slot));
tSPI.writeChannels_MOSI_Channel(DigitalModule.remapDigitalChannel(dataOutPin-1));
tSPI.writeChannels_MISO_Module(DigitalModule.slotToIndex(slot));
tSPI.writeChannels_MISO_Channel(DigitalModule.remapDigitalChannel(dataInPin-1));
}
public void initialize()
{
// set chip select low to start
module.setDIO(chipSelectPin, true);
// data is valid on rising edge of clock
tSPI.writeConfig_DataOnFalling(false);
// set the bit order
tSPI.writeConfig_MSBfirst(true);
tSPI.strobeReset();
tSPI.strobeClearReceivedData();
}
public AS5030Result getData( )
{
// select the chip
module.setDIO(chipSelectPin, false);
// write the 5 bit command
// set the width
tSPI.writeConfig_BusBitWidth(5);
// write the data to load
tSPI.writeDataToLoad(0x1F);
// strobe out the data
tSPI.strobeLoad();
// wait for completion
while( !tSPI.readStatus_Idle() )
{
java.lang.Thread.yield();
}
// change back to 16 bits
tSPI.writeConfig_BusBitWidth(16);
// clear the data to load
tSPI.writeDataToLoad(0x0);
// clear received data
tSPI.strobeClearReceivedData();
// strobe in the data
tSPI.strobeLoad();
// wait for completion
//while( !tSPI.readStatus_Idle() )
while( tSPI.readReceivedElements() == 0 )
{
java.lang.Thread.yield();
}
// strobe in the received data
tSPI.strobeReadReceivedData();
// read the data
long rawData = tSPI.readReceivedData();
// deselect the chip
module.setDIO(chipSelectPin, true);
AS5030Result result = new AS5030Result();
long rawAngle = rawData & 0xFF;
int agc = (int)((rawData >> 8) & 0x3F);
result.angle = (double)rawAngle * 360.0 / 256.0;
result.agc = agc;
return result;
}
}
Code:
/*
* To change this template, choose Tools | Templates
* and open the template in the editor.
*/
package edu.wpi.first.wpilibj;
import com.sun.squawk.util.MathUtils;
/**
*
* @author charris
*/
public class AS5030DualAnalog extends SensorBase implements PIDSource {
private static final double biasVoltage = 2.25;
private AnalogChannel sinChannel;
private AnalogChannel cosChannel;
public AS5030DualAnalog( int slotParam, int sinChannelParam, int cosChannelParam)
{
sinChannel = new AnalogChannel( slotParam, sinChannelParam );
cosChannel = new AnalogChannel( slotParam, cosChannelParam );
}
protected double getCos()
{
return cosChannel.getVoltage() - biasVoltage;
}
protected double getSin()
{
return sinChannel.getVoltage() - biasVoltage;
}
public double getAngle()
{
// calculate the angle
double theta = MathUtils.atan2( getSin(), getCos() );
// convert to degrees
return Math.toDegrees(theta) + 180.0;
}
/**
* Get the angle of the encoder for use with PIDControllers
* @return the current angle according to the encoder
*/
public double pidGet() {
return getAngle();
}
}
|
|
#4
|
|||
|
|||
|
Re: Magnetic Encoder Programming Question\Consult
Thanks for the help on this. In looking at your code it appears that there are some other functions out there that may work for me as well.
I noticed that this code is in Java but i hope that the functions are names are similar (i remember reading that somewhere). If i get something to work today i will post the code later tonight...! JE |
|
#5
|
|||
|
|||
|
Ok, so i wanted to get the PWM working without modifing the chip any more (we already burnt one up). so i played with the code and was able to get code working to sample the PWM on a digital input port of the digital sidecar. i have attached the example below in c++.
Code:
void OperatorControl(void)
{
GetWatchdog().SetEnabled(false);
timeStart = 0.0;
timeEnd = 0.0;
avgPulseTime = 0.0;
pulseCounter = 0;
positionDegree = 0;
const UINT32 slot = 4;
char *c = NULL;
DigitalModule *dm = DigitalModule::GetInstance(slot);// (slot);
DriverStationLCD *dsLCD = DriverStationLCD::GetInstance();
dm->AllocateDIO(1,true);
//dsLCD->UpdateLCD();
while (IsOperatorControl())
{
if(dm->GetDIO(1) == 1)
{
//start the timer and get the time
tim1.Start();
timeStart=tim1.Get();
while(dm->GetDIO(1) == 1) //repeat until there is a falling edge
{
Wait(.000001); //Pause for 1usec
}
timeEnd=tim1.Get();
tim1.Stop(); //stop the timer
if(0 < (timeEnd - timeStart) < .000578) //filter out noise
{
avgPulseTime += (timeEnd-timeStart); //sum up all of the pulses
pulseCounter++;
}
}
//looking to average 10 pulses together
if (pulseCounter == 10)
{
avgPulseTime /= pulseCounter;
avgPulseTime *= 1000000;
positionDegree = avgPulseTime * 360 / 578;
pulseCounter = 0;
//display on the screen
sprintf(c,"%03d",positionDegree);
dsLCD->Printf(dsLCD->kUser_Line4,1,c);
dsLCD->UpdateLCD();
tim1.Reset();
avgPulseTime = 0.0;
*c = NULL;
}
Wait(.0000005);
}
}
I hope that this can help somone else who is thinking of doing the same thing... John K. Erdelyan Lead Mentor & Programming Mentor Team 2910 |
![]() |
| Thread Tools | |
| Display Modes | Rate This Thread |
|
|
Similar Threads
|
||||
| Thread | Thread Starter | Forum | Replies | Last Post |
| Help Programming Transmissive Optical Encoder Module from usdigital.com | programmr | Programming | 6 | 14-11-2008 19:20 |
| Help Programming a Quadrature Encoder | programmr | Programming | 17 | 20-06-2008 10:40 |
| Programming a Devantech Magnetic Compass - CMPS03 | kE7JLM | Programming | 7 | 28-09-2007 08:23 |
| Non Contact Magnetic Encoder with PWM Output | Tom Bottiglieri | Programming | 3 | 09-10-2005 01:19 |
| PID control loop/Encoder question | Zee | Programming | 18 | 30-01-2004 23:14 |