Project XI-AR1
The Xanadu Industrial Aēchos Rover 1 is a lightweight tracked robot. Designed for outdoor use the AR1 combines a modern low profile mobile platform with extended run time.
Features
Propeller Project Board http://parallax.com/product/32810
Dual 12v 150rpm motors with quadrature encoders http://www.pololu.com/product/2284
Dual VNH2SP30 Motor Driver - http://www.pololu.com/product/708 (in place of Roboclaw at the moment)
2” Tracks (x2) http://www.lynxmotion.com/p-511-track-2-wide-x-21-links-23-single.aspx
ePVC Chassis http://www.usplastic.com/catalog/item.aspx?itemid=33732&catid=733
I've attached the comparison chart below. You should be able to extrapolate the arrogated data from the graph -
Features
Propeller Project Board http://parallax.com/product/32810
Dual 12v 150rpm motors with quadrature encoders http://www.pololu.com/product/2284
Dual VNH2SP30 Motor Driver - http://www.pololu.com/product/708 (in place of Roboclaw at the moment)
2” Tracks (x2) http://www.lynxmotion.com/p-511-track-2-wide-x-21-links-23-single.aspx
ePVC Chassis http://www.usplastic.com/catalog/item.aspx?itemid=33732&catid=733
I've attached the comparison chart below. You should be able to extrapolate the arrogated data from the graph -

Comments
Here are PDF plans for the Lynxmotion 2" tracks and 6 Link Sprockets. There are no measurements on the plans because they are not accurate enough for production work. You can print the PDF (make sure you sprint actual size) and use it as a template to cut ePVC with no problems. Do not cut your ePVC until you have all of your track parts in hand. The best way to cut ePVC is with a nice new sharp blade with a decent size handle to grip.
Untitled5.pdf
Here is the most recent photo, using the plans above.
Black: 2200mah 3 cell lipo
Yellow: Mini-Box PSU
Green: Propeller Project Board cut in half (pending custom propeller board
Grey: RC Receiver
Blue: Motor Driver
Purple: +5v and Gnd x10 .1" headers on perfboard
Today I will be seeing if there are any differences between the two motors and doing some run testing. Once that is done I can start planning the main power bus and battery. I usually build my robots around the power source. This time I'm really not approaching from a particular direction because I do not have all of the parts on hand.
First test is the quadrature encoders. To do this I use a bench top power supply and my DSO only. WARNINGING Do not use bench PSU with regenerative MCUs. :The encoders should be both producing the same signal at the same RPM, and the RPM difference between the two motors shouldn't be too much. I will probably do some load testing overnight. The main object of this is to identify any hardware issues, as well as collect my own data on power consumption.
So how many transitions per second are you seeing?
Is this project going to be done in Spin/PASM or are you going to use C?
Thanks for the update. I'm watching with much interest.
Thanks this is the same one you're using. Glad I went with it, seems like an all-purpose small to medium size solution with plenty of torque for tracks.
According to the datasheet at 150 RPM it should be just over 10k transitions per second. I should use my counter to check that out too. Right now they're both running full power whilst I measure their temperature.
For the programming I rely on a lot of objects so probably SPIN/PASM, although I will be evaluating that next. I would like to start using C on the Propeller. The Roboclaw controller has a dead channel and the tracks and chassis don't arrive until Friday so I have some time to decide.
Initially I will be using the motor controller to handle the encoders. That is why I had picked the Roboclaw. I think I will go back to Roboteq. I would love to put the new 2 channel Sabertooth on it but it doesn't have encoder inputs. I need to get it rolling quickly. I have to have a working proof of concept asap. Not the robot itself but pictures of wildlife taken from it.
That is well within the Prop's capabilities correct?
This Object http://obex.parallax.com/object/213 says it can do "The sample period is about 4us. This allows a conservative 125,000 - (8us apart) encoder ticks per second per channel."
I'm going to ditch the idea of using the motor controller for encoders as of now. I've been looking at the encoder Objects and it's a lot easier than I thought. Just want to make sure of the above because this would be the first time using encoders with the Propeller.
I'm pretty sure the Prop can handle this fine. I wrote my own encoder object since I needed four channels. My object (it's been posted to the forum but it's probably well hidden) keeps a running average of the speed of the motors.
I've been thinking about the need of slow movement. 4331 ticks per rotation may be enough to use ticks per unit time for speed measurements but there's also the possibility of measuring the time between transitions. By timing the transitions you should be able to improve the accuracy of the speed calculations.
I've worked a little on timing transitions for my Rover 5 robots since they only have 333.3 transitions per revolution. You probably don't need to worry about this with the Pololu motors. I just thought I'd let you know of the different methods of computing speed.
It would be interesting to see just how slowly these motors could be made to rotate. Could you get it to turn one rev per hour? What would it sound like moving that slow?
Speaking of sound, I went through and tested a bunch of my motors and servos. The only motors I found quieter than the Pololu motors were motors with much less power. Within my limited collection, I think the Pololu motors offer the best trade off between sound and power.
I've been playing with reading the encoders with the Propeller. Since I have no motor controller large enough I'm using my adjustable power supply. I couldn't use the encoders to control its speed but I did test out the lowest speeds I could get it to.
At .37v @ .12ma the encoder wheel is hardly spinning so the output shaft of the motor is super slow. As slow as it looked it was actually about a minute and a half per revolution. The sound at that speed isn't measurable. Background noise of a quiet office is louder.
I agree about the sound and power. Roomba motors are pretty quiet too.
There's no ETA on the return of the motor controller. The tech said if one channel didn't work the board needs to be fixed it was pretty painless phone call. He said that I was overloading the BEC. The BEC says 150ma max. I had a Spektrum rx [20ma] and two [10ma] encoders, so 40ma. How that exceeds 150ma is beyond me but I'm not going to argue with an exchange and the place is 40 minutes from here so it should be quick. I looked at controllers again and there needs to be a smaller HB-25! Pololu offered me a discount on a different controller. Encoder inputs aside, for the amp range I need it's really the best deal. I guess I'll go with it and wait. The reality of not being able to rush into this and have it up and running in a couple days is setting in...
A large sheet of it bends easy but a smaller piece is very rigid. 0.2" should be a good thickness to begin the chassis prototyping. The only hold up is that the tracks are advertised as ~21". Need to know the exact size. The track's nylon rollers will be adjustable to get the right track tension, but not by much. There will be five rollers on each side, one powered hub and one free spinning.
I would like to do what I did below with Vex tracks. That was my first scratch built BS2 based robot.
I'd like to do a flat track this time. Keep the chassis lower profile, doesn't need that kind of ground clearance. We want to sneak up on things. It will also be fun to drive FPV with the camera that low to the ground. You could get lost in your own backyard lol.
To be continued.
I modified this Object http://obex.parallax.com/object/213 to display the raw encoder values on the PST.
{{ ┌─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ │ Quadrature Encoder Engine │ │ │ │ Author: Kwabena W. Agyeman │ │ Updated: 2/28/2010 │ │ Designed For: P8X32A - No Port B. │ │ │ │ Copyright (c) 2010 Kwabena W. Agyeman │ │ See end of file for terms of use. │ │ │ │ Driver Info: │ │ │ │ The driver is only guaranteed and tested to work at an 80Mhz system clock or higher. │ │ Also this driver uses constants defined below to setup pin input and output ports. │ │ │ │ Additionally the driver spin function library is designed to be acessed by only one spin interpreter at a time. │ │ To acess the driver with multiple spin interpreters at a time use hub locks to assure reliability. │ │ │ │ Finally the driver is designed to be included only once in the object tree. │ │ Multiple copies of this object require multiple copies of the source code. │ │ │ │ Nyamekye, │ └─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ This code has been modified from its original version. }} CON '' Encoder_A_Pin_A = 4 '' ─ Quadrature encoder A channel A active high input. '' Encoder_A_Pin_B = 5 '' ─ Quadrature encoder A channel B active high input. '' Encoder_B_Pin_A = 6 '' ─ Quadrature encoder B channel A active high input. '' Encoder_B_Pin_B = 7 '' ─ Quadrature encoder B channel B active high input. Encoder_Frequency = 100_000 ' Maximum ticks per second. Adjusting this value does nothing. It is here for reference. _clkmode = xtal1 + pll16x _xinfreq = 5_000_000 VAR long channelADeltaTicks long channelBDeltaTicks long channelATickFrequency long channelBTickFrequency OBJ pst : "Parallax Serial Terminal" PUB Main pst.Start(115_200) QEDEngine repeat pst.str (string("Motor 1 ")) getSpeedA pst.dec(channelATickFrequency) pst.str (string(" ")) pst.str(string("Motor 2 ")) getSpeedB pst.dec(channelBTickFrequency) pst.newline waitcnt (clkfreq * 1 + cnt) PUB getDeltaA '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the currently accumulated position delta since the last call. │ '' │ │ '' │ Ticks relate to the number of "ticks" on the wheel of the encoder disk. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return channelADeltaTicks~ PUB getSpeedA '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the current tick speed per second. This value updates per tick encoder tick. Takes a while to see zero speed. │ '' │ │ '' │ This value is recalculated each encoder tick. So it takes a second literally to see when the speed drops to zero. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return (clkfreq / channelATickFrequency) PUB getDeltaB '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the currently accumulated position delta since the last call. │ '' │ │ '' │ Ticks relate to the number of "ticks" on the wheel of the encoder disk. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return channelBDeltaTicks~ PUB getSpeedB '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the current tick speed per second. This value updates per tick encoder tick. Takes a while to see zero speed. │ '' │ │ '' │ This value is recalculated each encoder tick. So it takes a second literally to see when the speed drops to zero. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return (clkfreq / channelBTickFrequency) PUB QEDEngine '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Initializes the quadrature encoder driver to run on a new cog. │ '' │ │ '' │ Returns the new cog's ID on sucess or -1 on failure. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ CHADTAddress := @channelADeltaTicks CHATFAddress := @channelATickFrequency CHBDTAddress := @channelBDeltaTicks CHBTFAddress := @channelBTickFrequency return cognew(@initialization, 0) DAT ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ' Quadrature Encoder Driver ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// initialization mov ctra, channelASetup ' Setup counters. mov ctrb, channelBSetup ' mov frqa, #1 ' mov frqb, #1 ' ' //////////////////////Channel A////////////////////////////////////////////////////////////////////////////////////////////// loop cmp channelADelta, phsa wz ' Check for edge and accumulate. if_nz test channelADirection, ina wc ' mov channelADelta, phsa ' Update delta. if_nz rdlong buffer, CHADTAddress ' Add in delta direction. if_nz sumc buffer, #1 ' if_nz wrlong buffer, CHADTAddress ' if_nz_and_c movi speedAFlip, #1001_001 ' Flip mov to neg if direction is negative. if_nz_and_nc movi speedAFlip, #1000_001 ' if_nz mov lockA, #0 ' Lock down final value to prevent false overflow triggering. tjnz lockA, #skip ' mov buffer, cnt ' Get time difference. sub buffer, outa ' if_nz mov outa, cnt ' Reset time difference on tick. rdlong counter, #0 ' Check if difference greater than clock freqeuncy. cmp buffer, counter wc ' if_nc neg lockA, #1 ' Set false trigger lock. speedAFlip if_nz_or_nc mov buffer, buffer ' Update final value. if_nz_or_nc wrlong buffer, CHATFAddress ' ' //////////////////////Channel B////////////////////////////////////////////////////////////////////////////////////////////// skip cmp channelBDelta, phsb wz ' Check for edge and accumulate. if_nz test channelBDirection, ina wc ' mov channelBDelta, phsb ' Update delta. if_nz rdlong buffer, CHBDTAddress ' Add in delta direction. if_nz sumc buffer, #1 ' if_nz wrlong buffer, CHBDTAddress ' if_nz_and_c movi speedBFlip, #1001_001 ' Flip mov to neg if direction is negative. if_nz_and_nc movi speedBFlip, #1000_001 ' if_nz mov lockB, #0 ' Lock down final value to prevent false overflow triggering. tjnz lockB, #loop ' mov buffer, cnt ' Get time difference. sub buffer, outb ' if_nz mov outb, cnt ' Reset time difference on tick. rdlong counter, #0 ' Check if difference greater than clock freqeuncy. cmp buffer, counter wc ' if_nc neg lockB, #1 ' Set false trigger lock. speedBFlip if_nz_or_nc mov buffer, buffer ' Update final value. if_nz_or_nc wrlong buffer, CHBTFAddress ' jmp #loop ' Loop. ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ' Data ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// channelADelta long 0 channelBDelta long 0 ' //////////////////////Configuration////////////////////////////////////////////////////////////////////////////////////////// channelASetup long ((010 << 26) + ((Encoder_A_Pin_A <# 31) #> 0)) ' Counter edge detection setup. channelBSetup long ((010 << 26) + ((Encoder_B_Pin_A <# 31) #> 0)) ' Counter edge detection setup. ' //////////////////////Pins/////////////////////////////////////////////////////////////////////////////////////////////////// ChannelADirection long (|<((Encoder_A_Pin_B <# 31) #> 0)) ' Pin to sample to determine direction. ChannelBDirection long (|<((Encoder_B_Pin_B <# 31) #> 0)) ' Pin to sample to determine direction. ' //////////////////////Addresses////////////////////////////////////////////////////////////////////////////////////////////// CHADTAddress long 0 CHATFAddress long 0 CHBDTAddress long 0 CHBTFAddress long 0 ' //////////////////////Run Time Variables///////////////////////////////////////////////////////////////////////////////////// buffer res 1 counter res 1 lockA res 1 lockB res 1 {{ ┌─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ │ TERMS OF USE: MIT License │ ├─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┤ │Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation │ │files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, │ │modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the │ │Software is furnished to do so, subject to the following conditions: │ │ │ │The above copyright notice and this permission notice shall be included in all copies or substantial portions of the │ │Software. │ │ │ │THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE │ │WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR │ │COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, │ │ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. │ └─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ }}
This is what I get for the output:
Motor 1 -722072 Motor 2 -459400 Motor 1 -359464 Motor 2 -486888 Motor 1 -364392 Motor 2 -476504 Motor 1 -360344 Motor 2 -488296 Motor 1 -717448 Motor 2 -467880 Motor 1 -357656 Motor 2 -476008 Motor 1 -355944 Motor 2 -469992 Motor 1 -358936 Motor 2 -454856 Motor 1 -360648 Motor 2 -898088 Motor 1 -357832 Motor 2 -474040 Motor 1 -732760 Motor 2 -436024 Motor 1 -358232 Motor 2 -436024 Motor 1 -361576 Motor 2 -426696 Motor 1 -358232 Motor 2 -428104 Motor 1 -358184 Motor 2 -440456 Motor 1 -362280 Motor 2 -431272 Motor 1 -364392 Motor 2 -419128 Motor 1 -351544 Motor 2 -415608 Motor 1 -711160 Motor 2 -407160 Motor 1 -360344 Motor 2 -412264 Motor 1 -357704 Motor 2 -425288 Motor 1 -361048 Motor 2 -438840 Motor 1 -364040 Motor 2 -440248 Motor 1 -357704 Motor 2 -427752 Motor 1 -361576 Motor 2 -430040 Motor 1 -362104 Motor 2 -442184 Motor 1 -367208 Motor 2 -423000 Motor 1 -362104 Motor 2 -433208 Motor 1 -366152 Motor 2 -430392 Motor 1 -362936 Motor 2 -443800 Motor 1 -364040 Motor 2 -434088 Motor 1 -361528 Motor 2 -421800 Motor 1 -365448 Motor 2 -409832 Motor 1 -364392 Motor 2 -410504 Motor 1 -363288 Motor 2 -796680 Motor 1 -371960 Motor 2 -397304 Motor 1 -371256 Motor 2 -401704 Motor 1 -368088 Motor 2 -390616 Motor 1 -366856 Motor 2 -387128 Motor 1 -364392 Motor 2 -377592 Motor 1 -360168 Motor 2 -393608 Motor 1 -363864 Motor 2 -391672 Motor 1 -359992 Motor 2 -394488 Motor 1 -362456 Motor 2 -382136 Motor 1 -354664 Motor 2 -388360 Motor 1 -362456 Motor 2 -389912 Motor 1 -358536 Motor 2 -399096
There are a couple of things I'm wondering.
Why is the number negative? It goes up as the motor speeds up, but why would it start so low?
The other thing I'm wondering is what resistors I should use between the Propeller and the encoder outputs?
The sign on speed or distance is arbitrary. If you switch the encoder pin assignments (change 4, 5, 6, 7 to 5, 4, 7, 6) the sign of the speed should be positive.
I think the values displayed are supposed to be the number of encoder ticks per second but I'm not so sure about that. The numbers sure are bigger than what I'd expect. I looked through the code some but Kye is often too clever for me to follow, which is the case here.
You might want to try manually inputting encoder ticks with a pair of push buttons or switches in order to get what you're seeing to make sense.
This depends on how you're powering the encoders. Some encoders will work with 3.3V. The Pololu encoders say they should work at 3.6V but I've been using 5V on mine with 10K ohm resistors. The encoders should be able to work with the motor's 12V supply in which case you'd want the resistors to be 24K or higher. The Prop's input pins can handle voltages higher than 3.3V but the current has to be kept below 500uA. It would be interesting to see if he encoders would work powered with 3.3V.
The numbers are a lot larger than I thought as well, I'm not sure what it means about returning three longs either.
I'm using 10k resistors and 5v power on the encoders. I tried 3.3v with these encoders and it seems to work okay.
You're right, I need to break this down a little further and use push buttons instead of the encoder to play with the variables.
Instead of:
pst.str (string("Motor 1 ")) getSpeedA pst.dec(channelATickFrequency) pst.str (string(" ")) pst.str(string("Motor 2 ")) getSpeedB pst.dec(channelBTickFrequency) pst.newline
Try:
pst.str (string("Motor 1 ")) pst.dec(getSpeedA) pst.str (string(" ")) pst.str(string("Motor 2 ")) pst.dec(getSpeedB) pst.newline
The methods getSpeedX return the speed value. I don't think they change the value of "channelXTickFrequency".
I'm not sure what you mean by "returning three longs". Kye likes to list the amount of stack space his methods require. I don't know how he calculates these values they're aren't associated with the return value of the method. A method can only return a single long. This long can be a pointer to other data but in this case "getSpeed" returns the speed for that particular channel.
Let's say you add these variables:
VAR long channelADeltaTicks long channelBDeltaTicks long channelATickFrequency long channelBTickFrequency [COLOR=#ff0000] long speed1, speed2[/COLOR]
Then you could use these to store the speed values returned from "GetSpeed".
pst.str (string("Motor 1 ")) speed1 := getSpeedA pst.dec(speed1) pst.str (string(" ")) pst.str(string("Motor 2 ")) speed2 := getSpeedB pst.dec(speed2) pst.newline
If you're using these speeds in a PID algorithm, you'll want to make sure it doesn't take a full second to update to the current speed. I don't know Kye's driver well enough how you'd use it with a PID algorithm.
Motor 1 227 Motor 2 111 Motor 1 232 Motor 2 217 Motor 1 232 Motor 2 215 Motor 1 233 Motor 2 215 Motor 1 234 Motor 2 215 Motor 1 230 Motor 2 216 Motor 1 230 Motor 2 214 Motor 1 233 Motor 2 220 Motor 1 231 Motor 2 217 Motor 1 228 Motor 2 218 Motor 1 226 Motor 2 216 Motor 1 224 Motor 2 218 Motor 1 224 Motor 2 223 Motor 1 224 Motor 2 220 Motor 1 224 Motor 2 226 Motor 1 222 Motor 2 218 Motor 1 224 Motor 2 213 Motor 1 224 Motor 2 215 Motor 1 226 Motor 2 224 Motor 1 229 Motor 2 227 Motor 1 227 Motor 2 220 Motor 1 224 Motor 2 219 Motor 1 223 Motor 2 215 Motor 1 226 Motor 2 216 Motor 1 226 Motor 2 218
I thought I had tried that before and it was the same number. Must be getting late...
This number is much lower, and is positive while maintaining an increase with an increase in RPM, so this is huge, thank you. I think I really need to pickup the Prop Ed book and review a few things.
Thanks for the explanation on three longs. I had thought that it was returning a number too large to fit into one long.
Using PID I will update much faster this is just to make the PST easy to read.
If the encoder is measuring ticks per second on a quadrature encoder since there are two detectors would that be two pulses per "tick"?
I think I also need to factor in 3441 ticks per R, and then the number above seems small.
This is how I have it broken down:
repeat rpm1 := GetSpeedA 'ticks per second rpm2 := rpm1/4331 'number of ticks per revolution rpm3 := rpm2*60 'number of revolutions in one minute pst.dec (rpm3) 'output
I've tried a lot of the above. My motor is spinning fixed around 13 rpm. I haven't come anywhere near close to that value
repeat pst.str (string("Motor 1 ")) rpm1 := GetSpeedA 'number of ticks per second rpm2 := rpm1/4331 'raw ticks divided by ticks per revolution rpm3 := rpm2*60 'convert to RPM ' pst.dec (rpm3) pst.str (string(" "))
If the encoder travels 1444 ticks that is about 1/3 of a revolution of the output shaft. If I'm converting ticks per second into revolutions per second I'd have to divide the ticks by the total number of ticks 1444/4431 which equals .33 revolutions per second or 19 rpm.
So I guess I need to work around that next.
repeat pst.str (string("Motor 1: ")) rpm1 := GetSpeedA*100 'number of ticks per second add two zeros rpm2 := rpm1/4331 'raw ticks divided by ticks per revolution rpm3 := rpm2*60 'convert to RPM rpm4 := rpm3/100 'remove two zeros (should be RPM) pst.dec (rpm1) pst.str (string(" ")) pst.dec (rpm2) pst.str (string(" ")) pst.dec (rpm3) pst.str (string(" ")) pst.dec (rpm4) pst.newline waitcnt (clkfreq * 1 + cnt)
I get this:
Motor 1: 26200 6 360 3 Motor 1: 26200 6 360 3 Motor 1: 26200 6 360 3 Motor 1: 26500 6 360 3 Motor 1: 25900 5 300 3 Motor 1: 26000 6 360 3 Motor 1: 26000 6 360 3 Motor 1: 25900 5 300 3 Motor 1: 26300 6 360 3 Motor 1: 25800 5 300 3 Motor 1: 25800 5 300 3
This number is easy enough to work with, but it is not accurate. It's off by around 9 RPM.
Thanks for the help Duane. I'm going to start building the chassis on Monday
Try:
rpm1 := GetSpeedA * 10000
You can use this method to display this sort of scaled integer.
PUB DecPoint(value, denominator) if value < 0 Pst.Char("-") -value if value => denominator result := value / denominator Pst.Dec(result) value //= denominator else Pst.Char("0") Pst.Char(".") repeat while denominator > 1 denominator /= 10 if value => denominator result := value / denominator Pst.Dec(result) value //= denominator else Pst.Char("0")
In this example you'd use 1000 as the denominator parameter.
repeat pst.str (string("Motor 1: ")) rpm1 := GetSpeedA*10000 'number of ticks per second add four zeros rpm2 := rpm1/4331 'raw ticks divided by ticks per revolution rpm3 := rpm2*60 'convert to RPM 'rpm4 := rpm3/100 'remove two zeros (should be RPM) pst.dec(rpm1) pst.str(string(" ")) pst.dec(rpm2) pst.str(string(" ")) DecPoint(rpm3, 10000)
You just need to be careful your scaled value don't exceed 32-bits. In this case you're okay with adding four zeros but five would be too many.
I don't what Kye's object considers a tick.
{{ ┌─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ │ Quadrature Encoder Engine │ │ │ │ Author: Kwabena W. Agyeman │ │ Updated: 2/28/2010 │ │ Designed For: P8X32A - No Port B. │ │ │ │ Copyright (c) 2010 Kwabena W. Agyeman │ │ See end of file for terms of use. │ │ │ │ Driver Info: │ │ │ │ The driver is only guaranteed and tested to work at an 80Mhz system clock or higher. │ │ Also this driver uses constants defined below to setup pin input and output ports. │ │ │ │ Additionally the driver spin function library is designed to be acessed by only one spin interpreter at a time. │ │ To acess the driver with multiple spin interpreters at a time use hub locks to assure reliability. │ │ │ │ Finally the driver is designed to be included only once in the object tree. │ │ Multiple copies of this object require multiple copies of the source code. │ │ │ │ Nyamekye, │ └─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ This code has been modified from its original version. }} CON '' Encoder_A_Pin_A = 4 '' ─ Quadrature encoder A channel A active high input. '' Encoder_A_Pin_B = 5 '' ─ Quadrature encoder A channel B active high input. '' Encoder_B_Pin_A = 6 '' ─ Quadrature encoder B channel A active high input. '' Encoder_B_Pin_B = 7 '' ─ Quadrature encoder B channel B active high input. Encoder_Frequency = 100_000 ' Maximum ticks per second. Adjusting this value does nothing. It is here for reference. _clkmode = xtal1 + pll16x _xinfreq = 5_000_000 VAR long channelADeltaTicks long channelBDeltaTicks long channelATickFrequency long channelBTickFrequency long rpm1 long rpm2 long rpm3 long rpm4 long rpm1b long rpm2b long rpm3b long rpm4b OBJ pst : "Parallax Serial Terminal" PUB Main pst.Start(115_200) 'enable Parallax Serial Terminal waitcnt (clkfreq * 1 + cnt) 'wait a second for PST enable pst.str (string("resart")) 'restart warning pst.newline 'leave this line blank QEDEngine 'start the encoder driver repeat 'main loop pst.str (string("Motor 1: ")) 'print to PST rpm1 := GetSpeedA*1000 'number of ticks per second add three zeros rpm2 := rpm1/4331 'full revolution = 4331, divided by ticks per sec = revs per sec rpm3 := rpm2*60 'convert revs per sec to RPM rpm4 := rpm3/100 'remove two zeros (leave one for better speed resolution) pst.dec (rpm4) 'show the motor speed on PST pst.str (string(" ")) 'put some space between the numbers pst.str (string("Motor 2: ")) 'print to PST rpm1b := GetSpeedB*1000 'number of ticks per second add three zeros rpm2b := rpm1b/4331 'full revolution = 4331, divided by ticks per sec = revs per sec rpm3b := rpm2b*60 'convert revs per sec to RPM rpm4b := rpm3b/100 'remove two zeros (leave one for better speed resolution) pst.dec (rpm4b) 'show the motor speed on PST pst.str (string(" ")) 'put some space between the numbers pst.newline 'leave this line blank waitcnt (clkfreq / 50 + cnt) 'slow refresh rate a bit PUB getDeltaA '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the currently accumulated position delta since the last call. │ '' │ │ '' │ Ticks relate to the number of "ticks" on the wheel of the encoder disk. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return channelADeltaTicks~ PUB getSpeedA '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the current tick speed per second. This value updates per tick encoder tick. Takes a while to see zero speed. │ '' │ │ '' │ This value is recalculated each encoder tick. So it takes a second literally to see when the speed drops to zero. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return (clkfreq / channelATickFrequency) PUB getDeltaB '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the currently accumulated position delta since the last call. │ '' │ │ '' │ Ticks relate to the number of "ticks" on the wheel of the encoder disk. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return channelBDeltaTicks~ PUB getSpeedB '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Returns the current tick speed per second. This value updates per tick encoder tick. Takes a while to see zero speed. │ '' │ │ '' │ This value is recalculated each encoder tick. So it takes a second literally to see when the speed drops to zero. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ return (clkfreq / channelBTickFrequency) PUB QEDEngine '' 3 Stack Longs '' ┌──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ '' │ Initializes the quadrature encoder driver to run on a new cog. │ '' │ │ '' │ Returns the new cog's ID on sucess or -1 on failure. │ '' └──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ CHADTAddress := @channelADeltaTicks CHATFAddress := @channelATickFrequency CHBDTAddress := @channelBDeltaTicks CHBTFAddress := @channelBTickFrequency return cognew(@initialization, 0) DAT ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ' Quadrature Encoder Driver ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// initialization mov ctra, channelASetup ' Setup counters. mov ctrb, channelBSetup ' mov frqa, #1 ' mov frqb, #1 ' ' //////////////////////Channel A////////////////////////////////////////////////////////////////////////////////////////////// loop cmp channelADelta, phsa wz ' Check for edge and accumulate. if_nz test channelADirection, ina wc ' mov channelADelta, phsa ' Update delta. if_nz rdlong buffer, CHADTAddress ' Add in delta direction. if_nz sumc buffer, #1 ' if_nz wrlong buffer, CHADTAddress ' if_nz_and_c movi speedAFlip, #%101001_001 ' Flip mov to neg if direction is negative. if_nz_and_nc movi speedAFlip, #%101000_001 ' if_nz mov lockA, #0 ' Lock down final value to prevent false overflow triggering. tjnz lockA, #skip ' mov buffer, cnt ' Get time difference. sub buffer, outa ' if_nz mov outa, cnt ' Reset time difference on tick. rdlong counter, #0 ' Check if difference greater than clock freqeuncy. cmp buffer, counter wc ' if_nc neg lockA, #1 ' Set false trigger lock. speedAFlip if_nz_or_nc mov buffer, buffer ' Update final value. if_nz_or_nc wrlong buffer, CHATFAddress ' ' //////////////////////Channel B////////////////////////////////////////////////////////////////////////////////////////////// skip cmp channelBDelta, phsb wz ' Check for edge and accumulate. if_nz test channelBDirection, ina wc ' mov channelBDelta, phsb ' Update delta. if_nz rdlong buffer, CHBDTAddress ' Add in delta direction. if_nz sumc buffer, #1 ' if_nz wrlong buffer, CHBDTAddress ' if_nz_and_c movi speedBFlip, #%101001_001 ' Flip mov to neg if direction is negative. if_nz_and_nc movi speedBFlip, #%101000_001 ' if_nz mov lockB, #0 ' Lock down final value to prevent false overflow triggering. tjnz lockB, #loop ' mov buffer, cnt ' Get time difference. sub buffer, outb ' if_nz mov outb, cnt ' Reset time difference on tick. rdlong counter, #0 ' Check if difference greater than clock freqeuncy. cmp buffer, counter wc ' if_nc neg lockB, #1 ' Set false trigger lock. speedBFlip if_nz_or_nc mov buffer, buffer ' Update final value. if_nz_or_nc wrlong buffer, CHBTFAddress ' jmp #loop ' Loop. ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ' Data ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// channelADelta long 0 channelBDelta long 0 ' //////////////////////Configuration////////////////////////////////////////////////////////////////////////////////////////// channelASetup long ((%01010 << 26) + ((Encoder_A_Pin_A <# 31) #> 0)) ' Counter edge detection setup. channelBSetup long ((%01010 << 26) + ((Encoder_B_Pin_A <# 31) #> 0)) ' Counter edge detection setup. ' //////////////////////Pins/////////////////////////////////////////////////////////////////////////////////////////////////// ChannelADirection long (|<((Encoder_A_Pin_B <# 31) #> 0)) ' Pin to sample to determine direction. ChannelBDirection long (|<((Encoder_B_Pin_B <# 31) #> 0)) ' Pin to sample to determine direction. ' //////////////////////Addresses////////////////////////////////////////////////////////////////////////////////////////////// CHADTAddress long 0 CHATFAddress long 0 CHBDTAddress long 0 CHBTFAddress long 0 ' //////////////////////Run Time Variables///////////////////////////////////////////////////////////////////////////////////// buffer res 1 counter res 1 lockA res 1 lockB res 1 {{ ┌─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ │ TERMS OF USE: MIT License │ ├─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┤ │Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation │ │files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, │ │modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the │ │Software is furnished to do so, subject to the following conditions: │ │ │ │The above copyright notice and this permission notice shall be included in all copies or substantial portions of the │ │Software. │ │ │ │THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE │ │WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR │ │COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, │ │ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. │ └─────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ }}
Should give you an output that looks like this -
Motor 1: 70 Motor 2: 65 Motor 1: 72 Motor 2: 64 Motor 1: 72 Motor 2: 66 Motor 1: 71 Motor 2: 66 Motor 1: 70 Motor 2: 66 Motor 1: 72 Motor 2: 66 Motor 1: 72 Motor 2: 66 Motor 1: 71 Motor 2: 66 Motor 1: 70 Motor 2: 67 Motor 1: 23 Motor 2: 67 Motor 1: 72 Motor 2: 66 Motor 1: 71 Motor 2: 66 Motor 1: 70 Motor 2: 67 Motor 1: 72 Motor 2: 66 Motor 1: 72 Motor 2: 33 Motor 1: 71 Motor 2: 67 Motor 1: 70 Motor 2: 66 Motor 1: 72 Motor 2: 66 Motor 1: 72 Motor 2: 67 Motor 1: 71 Motor 2: 66 Motor 1: 70 Motor 2: 65 Motor 1: 72 Motor 2: 64 Motor 1: 72 Motor 2: 66 Motor 1: 71 Motor 2: 65 Motor 1: 70 Motor 2: 66 Motor 1: 72 Motor 2: 66 Motor 1: 72 Motor 2: 65
The above output was at a very slow motor speed. If you stop your motor you will see 0. At 12v I am seeing about 300, that gives me 300 different speeds to play with. Next I'll try to add some pulse outputs to control a servo to maintain a constant speed. The servo will simulate the motor controller I do not have at the moment.
[video=youtube_share;Y9DJjQ7jaLc]
{{ ┌───────────────────────────────────────────────── ────────────────────────────────────────────────── ──────────────────────────┐ │ Quadrature Encoder Engine │ │ │ │ Author: Kwabena W. Agyeman │ │ Updated: 2/28/2010 │ │ Designed For: P8X32A - No Port B. │ │ │ │ Copyright (c) 2010 Kwabena W. Agyeman │ │ See end of file for terms of use. │ │ │ │ Driver Info: │ │ │ │ The driver is only guaranteed and tested to work at an 80Mhz system clock or higher. │ │ Also this driver uses constants defined below to setup pin input and output ports. │ │ │ │ Additionally the driver spin function library is designed to be acessed by only one spin interpreter at a time. │ │ To acess the driver with multiple spin interpreters at a time use hub locks to assure reliability. │ │ │ │ Finally the driver is designed to be included only once in the object tree. │ │ Multiple copies of this object require multiple copies of the source code. │ │ │ │ Nyamekye, │ └───────────────────────────────────────────────── ────────────────────────────────────────────────── ──────────────────────────┘ This code has been modified from its original version. }} CON ServoPin = 1 '' Servo signal to this I/O pin-change if needed '' Encoder_A_Pin_A = 4 '' ─ Quadrature encoder A channel A active high input. '' Encoder_A_Pin_B = 5 '' ─ Quadrature encoder A channel B active high input. '' Encoder_B_Pin_A = 6 '' ─ Quadrature encoder B channel A active high input. '' Encoder_B_Pin_B = 7 '' ─ Quadrature encoder B channel B active high input. Encoder_Frequency = 100_000 '' Maximum ticks per second. Adjusting this value does nothing. It is here for reference. _clkmode = xtal1 + pll16x _xinfreq = 5_000_000 VAR long channelADeltaTicks long channelBDeltaTicks long channelATickFrequency long channelBTickFrequency long rpm1 long rpm2 long rpm3 long rpm4 long rpm1b long rpm2b long rpm3b long rpm4b long pulsewidth[60] long servostack[30] long altstack[30] long debugstack[30] long txstack[30] long rxinput long epos long speed OBJ pst : "Parallax Serial Terminal" PUB Main pst.Start(115_200) 'enable Parallax Serial Terminal waitcnt (clkfreq * 1 + cnt) 'wait a second for PST enable pst.str (string("resart")) 'restart warning pst.newline 'leave this line blank speed := 1500 ' init the speed var QEDEngine 'start the encoder driver cognew(servoc,@servostack) 'enable PWM to motor controller repeat 'main loop pst.str (string("Motor: ")) 'print to PST rpm1 := GetSpeedA*1000 'number of ticks per second add three zeros rpm2 := rpm1/4331 'full revolution = 4331, divided by ticks per sec = revs per sec rpm3 := rpm2*60 'convert revs per sec to RPM rpm4 := rpm3/100 'remove two zeros (leave one for better speed resolution) epos := rpm4 + speed 'sync the servo with the encoder waitcnt (clkfreq / 50 + cnt) 'slow refresh rate a bit PUB Servoc | tInc, tc, tHa, t ctra[30..26] := 100 ' Configure Counter A to NCO ctra[8..0] := servoPin frqa := 1 dira[servoPin]~~ ' Set up cycle and high times tInc := clkfreq/1_000_000 tC := tInc * 21_500 tHa := tInc * 1500 t := cnt ' Mark counter time repeat ' Repeat PWM signal tHa := tInc *epos ' Sync servo position/encoder phsa := -tHa ' Set up the pulse + Gain t += tC ' Calculate next cycle repeat waitcnt(t) ' Wait for next cycle PUB getDeltaA '' 3 Stack Longs '' ┌───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┐ '' │ Returns the currently accumulated position delta since the last call. │ '' │ │ '' │ Ticks relate to the number of "ticks" on the wheel of the encoder disk. │ '' └───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┘ return channelADeltaTicks~ PUB getSpeedA '' 3 Stack Longs '' ┌───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┐ '' │ Returns the current tick speed per second. This value updates per tick encoder tick. Takes a while to see zero speed. │ '' │ │ '' │ This value is recalculated each encoder tick. So it takes a second literally to see when the speed drops to zero. │ '' └───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┘ return (clkfreq / channelATickFrequency) PUB getDeltaB '' 3 Stack Longs '' ┌───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┐ '' │ Returns the currently accumulated position delta since the last call. │ '' │ │ '' │ Ticks relate to the number of "ticks" on the wheel of the encoder disk. │ '' └───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┘ return channelBDeltaTicks~ PUB getSpeedB '' 3 Stack Longs '' ┌───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┐ '' │ Returns the current tick speed per second. This value updates per tick encoder tick. Takes a while to see zero speed. │ '' │ │ '' │ This value is recalculated each encoder tick. So it takes a second literally to see when the speed drops to zero. │ '' └───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┘ return (clkfreq / channelBTickFrequency) PUB QEDEngine '' 3 Stack Longs '' ┌───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┐ '' │ Initializes the quadrature encoder driver to run on a new cog. │ '' │ │ '' │ Returns the new cog's ID on sucess or -1 on failure. │ '' └───────────────────────────────────────────────── ────────────────────────────────────────────────── ───────────────────────┘ CHADTAddress := @channelADeltaTicks CHATFAddress := @channelATickFrequency CHBDTAddress := @channelBDeltaTicks CHBTFAddress := @channelBTickFrequency return cognew(@initialization, 0) DAT ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ' Quadrature Encoder Driver ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// initialization mov ctra, channelASetup ' Setup counters. mov ctrb, channelBSetup ' mov frqa, #1 ' mov frqb, #1 ' ' //////////////////////Channel A////////////////////////////////////////////////////////////////////////////////////////////// loop cmp channelADelta, phsa wz ' Check for edge and accumulate. if_nz test channelADirection, ina wc ' mov channelADelta, phsa ' Update delta. if_nz rdlong buffer, CHADTAddress ' Add in delta direction. if_nz sumc buffer, #1 ' if_nz wrlong buffer, CHADTAddress ' if_nz_and_c movi speedAFlip, #1001_001 ' Flip mov to neg if direction is negative. if_nz_and_nc movi speedAFlip, #1000_001 ' if_nz mov lockA, #0 ' Lock down final value to prevent false overflow triggering. tjnz lockA, #skip ' mov buffer, cnt ' Get time difference. sub buffer, outa ' if_nz mov outa, cnt ' Reset time difference on tick. rdlong counter, #0 ' Check if difference greater than clock freqeuncy. cmp buffer, counter wc ' if_nc neg lockA, #1 ' Set false trigger lock. speedAFlip if_nz_or_nc mov buffer, buffer ' Update final value. if_nz_or_nc wrlong buffer, CHATFAddress ' ' //////////////////////Channel B////////////////////////////////////////////////////////////////////////////////////////////// skip cmp channelBDelta, phsb wz ' Check for edge and accumulate. if_nz test channelBDirection, ina wc ' mov channelBDelta, phsb ' Update delta. if_nz rdlong buffer, CHBDTAddress ' Add in delta direction. if_nz sumc buffer, #1 ' if_nz wrlong buffer, CHBDTAddress ' if_nz_and_c movi speedBFlip, #1001_001 ' Flip mov to neg if direction is negative. if_nz_and_nc movi speedBFlip, #1000_001 ' if_nz mov lockB, #0 ' Lock down final value to prevent false overflow triggering. tjnz lockB, #loop ' mov buffer, cnt ' Get time difference. sub buffer, outb ' if_nz mov outb, cnt ' Reset time difference on tick. rdlong counter, #0 ' Check if difference greater than clock freqeuncy. cmp buffer, counter wc ' if_nc neg lockB, #1 ' Set false trigger lock. speedBFlip if_nz_or_nc mov buffer, buffer ' Update final value. if_nz_or_nc wrlong buffer, CHBTFAddress ' jmp #loop ' Loop. ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ' Data ' ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// channelADelta long 0 channelBDelta long 0 ' //////////////////////Configuration////////////////////////////////////////////////////////////////////////////////////////// channelASetup long ((010 << 26) + ((Encoder_A_Pin_A <# 31) #> 0)) ' Counter edge detection setup. channelBSetup long ((010 << 26) + ((Encoder_B_Pin_A <# 31) #> 0)) ' Counter edge detection setup. ' //////////////////////Pins/////////////////////////////////////////////////////////////////////////////////////////////////// ChannelADirection long (|<((Encoder_A_Pin_B <# 31) #> 0)) ' Pin to sample to determine direction. ChannelBDirection long (|<((Encoder_B_Pin_B <# 31) #> 0)) ' Pin to sample to determine direction. ' //////////////////////Addresses////////////////////////////////////////////////////////////////////////////////////////////// CHADTAddress long 0 CHATFAddress long 0 CHBDTAddress long 0 CHBTFAddress long 0 ' //////////////////////Run Time Variables///////////////////////////////////////////////////////////////////////////////////// buffer res 1 counter res 1 lockA res 1 lockB res 1 {{ ┌───────────────────────────────────────────────── ────────────────────────────────────────────────── ──────────────────────────┐ │ TERMS OF USE: MIT License │ ├───────────────────────────────────────────────── ────────────────────────────────────────────────── ──────────────────────────┤ │Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation │ │files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, │ │modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the │ │Software is furnished to do so, subject to the following conditions: │ │ │ │The above copyright notice and this permission notice shall be included in all copies or substantial portions of the │ │Software. │ │ │ │THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE │ │WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR │ │COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, │ │ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. │ └───────────────────────────────────────────────── ────────────────────────────────────────────────── ──────────────────────────┘ }}
I must have been trying that as you were writing it. I actually remembered this from a older forum thread by someone else. Something about if you need decimal your code isn't right. Anyway now I know what they were talking about.
Thanks again for breaking it down in an easy to understand fashion. I greatly appreciate the help. I feel like redoing all of that code from yesterday. I'm really starting to like motor encoders
Houston, we have tracks!
"Some" assembly required. Mkay....
I don't know what to think about these tracks right now. I had a bunch of stuff to say but I'll hold off until I get to know them a little better. The tracks themselves are great the hardware raises some concerns. I may not be able to use the ePVC the way I intended. To be cont.
I'm very curious about these treads myself. I'm looking forward to reading your opinion about them.
I'll be interested to know how you think they compare with the less expensive Vex treads.
Vex tracks are lighter, less expensive and probably the best option for indoor use. They may slip a little more which is bad for odometery, however a little slip reduced a lot of loading on the hubs and chassis. ePVC and Vex seem to compliment each other. Vex tracks sprockets ride in the center of the track which is skinnier than the Lynx tracks. Vex tracks were a little easier to setup because they come as a kit with less guessing what you need to do a complete robot. The Vex idler assemblies were far easier to work with. The Vex idlers also had slotted holes for adjustment which meant a simple hole on the chassis side.
Lynxmotion tracks are heavier, but the rubber surface provides mega traction. They slip less, but cause a lot more loading on the hubs. I suppose odometery would be better due to less slip. Using ePVC with these tracks seems a little unfair to the ePVC. Aluminum or rigid plastic would be a better choice for the Lynx tracks. The Lynx tracks do not ride on the center, the sprockets are closer to the chassis side. Not sure why this is but it doesn't seem to cause any issues other than aesthetics.
Overall, they're both great choices. Both have individual links you can size to your project which is great. I think a good cut off weight would be around 2-3lbs. If you're going to build something more than a few pounds the Lynx are very suitable. Anything less than a few pounds the Vex will probably do just as well, if not better due to weight and nice idler assemblies.
^^That isn't lined up because of the way the axle mates with the bearing.
[video=youtube_share;rUkSEJ077JY]
I was looking around at the Lynxmotion site and I don't think this assessment is correct.
It looks like the treads could be driven from one edge but I don't think they're meant to be used like that. I think you're supposed to have the drive sprockets centered in the treads. This will require careful placement of the motor so it fits inside the treads a bit. I don't think you'll be able to mount the motor the way it is currently mounted and get the motor far enough inside the tread to position the drive sprocket where it needs to be.
I think you'll need to use the motor mounts and build a platform to position the motor correctly.
I had to do something similar when using these motors with the Vex treads.
You can see the motor and mount attached to the drive sprocket in this picture. If I stick the motor out like that, the track hits the mount no matter where you mount it. This is where a smaller motor, or larger drive sprocket would solve a lot of problems. I would most likely go with larger drive sprockets.
The idler issue. In the pic below you will see one idler sprocket and also one nylon idler. Neither of them is wide enough to be centered without building some kind of fancy frame around the outside. The idle sprocket can be put together a few different ways. In the picture below I put it together as specified in their Tri-trak kit. It works for that kit because the frame is smaller than the tracks and the tracks ride along the outside.
So I searched the web for other people using these tracks and I see most people are just using them off center. That is why I was blaming the track for the issue and not my chassis. It seems these are really just spare parts for the Tri-Trak kit, and other than the tracks them selves you need to fabricate idlers and hubs.
I'm going to order some larger drive sprockets, at least that way the motor can ride in the center. That buys me a lot of time to figure out what to do with the idlers.
There is tons of hardware out there that I can use to do this right. I just need to stay away from the Tri-Track kit stuff because my chassis design is nothing like that. Unfortunately I had just assumed those parts would work on anything like the VEX do.
I understand your choices much better now.
I think the Vex tread would come awfully close to the motors without a triangular design. I think it's interesting how convenient the off center drive shaft is on the Pololu motors. I know it make my treaded robot easier to make.
I think the main disadvantage of having the sprockets off center is it will like increase the twisting torque the track undergoes on uneven ground. I doubt it would cause much trouble but it would reduce the overall strength of the assembly a bit by having the sprockets off center.
Looking back at Amanda's robot, I'm pretty sure she's using the sprockets off center.
I don't suppose Lynxmotion will let you exchange sprockets?
BTW, I switched my encoders over to using the 3.3V logic and they work fine. I'm working on combining my four quadrature encoder object with my four motor control object. I'm hoping there's time in the control loop to both read the encoders and pulse the power pins. I'm pretty sure it should work (if coded correctly).
I did some reconfiguring. I made an assembly that rides inside of the track. It is actually really solid when you do this, like holding a brick. The tracks ride a lot smoother.
In these pics the tracks are upside down, oops.
I was hoping to have the motors inside the chassis. Another reason to run larger sprockets. I'm going to continue with this as is just to get something working and wait for the larger sprockets. I will keep the smaller ones, who knows might need them someday.
I didn't realize you wanted to run the encoders at 3.3v because you were powering them from a pin. What is the benefit of that over giving them constant 5v?
I keep watching for ideas to use on my treaded robot. Thanks for documenting this.
I'm not powering the encoders from an I/O pin; I'm just powering the pin with same supply as the Propeller chip. I'm using a Propeller Project board with my robot. The Project Board doesn't have a 5V source on it. By using 3.3V, I don't need to add a 5V regulator. If I use large enough resistors on the encoder output, I could power the encoder with the motor's supply of 12V. Using 3.3V seems like the safer option.
I see you have a rubber band to limit the movement of the wires. I use a couple of pieces of Gorilla tape to hold the wires against the motor so they don't bend where they meet the encoder PCB. I had to solder a broken wire back in place before I learned to limit the movement of the wires.
Check out how smooth these run, even at full speed. There is a little wobble because the motor is clamped in my vice with some rubber.
[video=youtube_share;kGPcF4ZjMnU]
Wow I still have them upside down in the video...