View unanswered posts | View active topics It is currently Wed Jul 30, 2014 5:16 pm






Reply to topic  [ 22 posts ]  Go to page 1, 2  Next
Performance (line following vs. robot speed)? 
Author Message
Rookie

Joined: Sun Apr 15, 2007 8:33 am
Posts: 40
Location: USA
Post Performance (line following vs. robot speed)?
Hi,

I have a question about how fast a NXT bot that is using at least 3 LEGO light sensors could go?

In fact I try to optimize my bot for speed but it seems that the sensor response time is too long or that the bot is too fast....

Anyone any ideas?.

PS: I saw some line following bot competitions and their bot are so fast but do they used standard LEGO light sensor????

jm.

_________________
SuntzuMaster- a French gentlemen in USA.


Sun Apr 29, 2007 2:31 pm
Profile
Novice

Joined: Sun Feb 04, 2007 12:48 am
Posts: 69
Location: Australia
Post 
The issue you are raising is the Holy Grail of a lot of robotics competitions. How do I go faster but not lose the line. This is one area where things get more interesting, trickier and frustrating the further you go. Atleast that has been the experience of myself and the students I mentor.

My understanding is, the standard lego light sensors can take a reading every 3ms. ie about 333 times/sec. This is incredibly fast and is probably not the issue that is preventing you from having success in making your line follower go faster without losing the line. You can check it out yourself using the datalog function in RobotC or Robolab 2.9 if you are familiar or interested in experimenting with these parts of the program.

The problem you are likely to be experiencing is that the robot (either through physical design or the programming logic) is unable to respond in time and winds up on the wrong side of the line because it is not agile or responsive enough. Hence the logic of the program is telling it the line is on the left when it is on the right because it couldn't turn quick enough. The smaller the turning circle the better.

The issues you are grappling with is likely how do I make the steering more responsive and start to predict where the line is. Most line following robots aren't so much following the line as oscillating back and forth over the line. What you are trying to reduce the intensity (amount of turn) of each oscillation so that you spend more time moving in a forward direction than turning left or right.

It is a frustrating pursuit when you see videos of people with robots flying along at great speed that appear to be following the line intuitively. I suspect these robots are just so responsive and their oscillations are so small that they appear to drive straight. (To anyone with greater knowledge or expertise; please feel free to correct any misconceptions I may have if I'm wrong.)

My understanding is that at the top of the heirarchy are line following programs that use a PID algorithm. I don't quite understand this except that I believe it is using predictive logic to predict the curve of the line and adjusts the approach of the robot accordingly.

I'd love it if someone would stand on my shoulders and shed some light on the mysteries of a PID algorithm for line following. Perhaps even a sample 8) to decode


Sun Apr 29, 2007 11:57 pm
Profile
Moderator
Moderator
User avatar

Joined: Wed Jan 31, 2007 3:39 am
Posts: 299
Location: San Diego, California. USA
Post 
I think that was a great explanation James!

One thing that i want to add is for the best performance of the light sensor, your need to mount it as close as possible to the ground, that way you get strong readings.

I just learned what the PID control does yesterday so ill give ya the readers digest version:

if the PID is off then.....
motor[motorA]=50
means set the motor power output to 50%

If the PID is on then.....
motor[motorA]=50
really means set the motor speed to 50% of full speed and adjust the power output to maintain that speed

This comes in really handy if your trying to move a motor but it stalls before it gets to where it needs to go, with PID on when it starts to stall the NXT gives the motor more juice to maintain the speed.

There is a nice tutorial movies to watch that talks about motors and sensors, the link is also on the RobotC.net main page and three pictures over

http://www-education.rec.ri.cmu.edu/rob ... ement.html

Hope this Helps and good luck!
Scott

_________________
Mmmm Legos B-)

My Robot Projects:
http://www.freewebs.com/robotprojects/


Mon Apr 30, 2007 6:42 pm
Profile WWW
Moderator
Moderator
User avatar

Joined: Wed Jan 31, 2007 3:39 am
Posts: 299
Location: San Diego, California. USA
Post 
Ohh i misread, PID algorithm! Sorry James lol........ that would be interesting to see :D

I just thought of one more thing, Robots that use 2 light sensors that iv seen are able to move allot faster than just using one sensor by itself

If your using just one sensor, you have to hover back and forth over the line to stay with it and it takes allot of time. If you use two sensors, you can watch out for the line on the sides of your robot.

Its very much a speed vs performance challenge.

Good luck!
Scott

_________________
Mmmm Legos B-)

My Robot Projects:
http://www.freewebs.com/robotprojects/


Mon Apr 30, 2007 6:44 pm
Profile WWW
Rookie

Joined: Sun Apr 15, 2007 8:33 am
Posts: 40
Location: USA
Post 
Hello.

Thanks for your inputs. I was able to collect enough information on the internet to understand the PID process applied to a line following algorithm. For instance I know now that only the "PI" and not the "D" must be used to adjust the bot trajectory. I know also that when using two light sensors that the difference between light sensor values can be used as error variable. I know also that if the error == 0 then the bot is just centered on the line if the error < 0 then the bot is sliding on the left of the line and if error > 0 then the bot is sliding on the right of the line... now the "PI" formula should give an output value that can be used to fix the bot trajectory, the output value is applied to one motor in order to increase or decrease the speed that ultimately put the bot back to line.

I shall now test my program and if you are interested I could share my code with you. let me know and have a good day.

JM.

PS: I am french and my English is not always very good :>).

_________________
SuntzuMaster- a French gentlemen in USA.


Tue May 01, 2007 8:41 am
Profile
Rookie

Joined: Sun Apr 15, 2007 8:33 am
Posts: 40
Location: USA
Post 
Success I got the PID for line following robot working !!!!!!!!!!!!!!!!!!!!!!

_________________
SuntzuMaster- a French gentlemen in USA.


Tue May 01, 2007 6:25 pm
Profile
Creator
Creator

Joined: Fri Feb 09, 2007 9:21 am
Posts: 614
Post 
Previous discussions on PID algorithm are not quite accurate. PID stands for Proportional, Integration and Derivative control.

In this case, we'll simplyify and assume a perfect light sensor where 50 is the mid-point when the light sensor is exactly on the line. 0 is fully dark and and 100 is fully bright.

The PID "error factor" will be the differeence of the light sensor value from the desired value of 50.

Suppose we had two light sensor readings of 60 and 100. At 60, we are very close to the target value so we should probably apply only a small correcting value but at 100 we are way off and want to apply a large correction value.

Furthur suppose we want the two motors to average a power level of 50. So for the light sensor value of 60 we may want to set the power level of the two motors to 40 and 60. At light sensor value of 100 we may want to sent them to 0 and 100. This is the proportional control (P) of a PID loop.

Calculation of the P-adjustment is simple. You take the error value and multiply it by a constant. This becomes the adjustment value. In the above case, the P-constant was 1. We then used the P-Adjustment to increase or decrease the speed of each motor.

Use of a 'P" (Proportional) calculation is far better than the "brute" force line-following technique that looks at the light sensor value and makes a binary decision to turn one motor one and the other motor off. Only one motor is turned on a time. With "P" both motors are on but at different speed levels based on how far from the line we are on -- end result is you should be following the line with a faster moving robot!

Sometimes you only need to have a P-factor and the I-constant and D-constant are both set to zero. You don't always have to have an adjustment for each of the P, I and D values.

The D value is the derivative of the error. Continuing with the above example, suppose on three iterations through the loop we got sensor values of 50, 60 and 65. The three P-values (i.e. the error value) are 0, 10 and 15. The D-value is the difference between two successive values -- or 10 and 5 in this case.

With a simple 'P' only calcuation, and using a P-constant of 1. We get the three motor values as described above of
1. 50, 50
2. 40, 60
3. 35, 65
If the robot was trying to follow a straight line, then it appears that the P-constant value of 1.0 is not working -- the error is getting worse instead of smaller. But it might be that the line was a straight line and has now curved to one side.

The "D" calculation adds (or subtracts) an extra adjustment to the error calcuation. Let's suppose the D-constant is also 1. Then the calculated motor value become.
Code:
         Sensor        P         D      Motors
1.          50          0        0      50, 50
2.          60         10       10      30, 70
3.          65         15        5      30, 70


What a "D" adjustment value tends to do is: (1) keep the movement from "overshooting" the target value, (2) temporarily apply an extra adjustment if the derivative value -- or rate of change of the error -- is non-zero.

With the line following example, when the sensor is not at 50 we use the P-adjustment to provide a error correction to try to get the sensor value back to 50. It will get the robot turning in the right direction. Depending on the choice of P-constant and the mechanical parameters of the robot, the robot may actually cross over the line and move to the other direction. The D-adjustment tends to smooth this out and have the error factor asymptotically approach the target value without adjustment.

Of course, in all of the above, you have to pick the right constant values for P, I and D. There's some theoretical work that will calculate these for you -- but you have to characterise the roboc in terms of motor behavior, friction, etc so I've never got this to work. Instead, set D-constant and I-constant to zero and try to find with trial and error a P-constant that will get the line follower to work. Once you've achieved this, play with D-constant settings to try to minimize the overshoot.

A few other things to think about.

RobotC execution speed is so fast that you're probably getting multiple cycles through the loop per millisecond. You want to put a delay in your loop so that you get one cycle every 5 to 15 milliseconds. Otherwise, the D calculation will be useless -- it will only apply for a fraction of a millisecond before it becomes zero! [As well, there's no need to cycle through the loop faster than 3-msec anyway because the light sensor is only scanned every 3-msec].

Depending on your choice of constants, you may find the calculated motor value is less than zero -- i.e. in a reverse direction. You may want to put a check in your program to coerce the minimum value to zero (stopped). Or you may decide that reverse movement is a good thing -- it will probably let you follow very sharp "angles".\

Hope above helps in understanding. Eventually should have a PID controlled line follower added to the RobotC sample files. Unless someone wants to contribute one and post here first.


Fri May 04, 2007 9:32 am
Profile
Rookie

Joined: Sun Apr 15, 2007 8:33 am
Posts: 40
Location: USA
Post 
Hello,

I wrote the following RobotC program and I have imbedded a PID controller. It works just fine with my robot. However, the PID gains must be tuned based on the robot physical configuration. Robot Speed must also be taken as main factor that influence the PID tuning.

My next step is to make it faster and better but in order to do that I have to use a better way to achieve a very very very good PID setup...

I wrote a C# program to help with PID tuning. I can use it to analyze how the PID controller behave based on the input that is the Error that I need to fix...

I would like to thanks Tim Wescott who wrote "PID Without a PhD"
he gaves me some hints on what a PID controller is...
http://www.embedded.com/2000/0010/0010feat3.htm


You can find my robot movie on google VIDEO.
Look for "LEGO based Robot using a PID controller to follow a line"
I just published today (Sunday) theh I expect to have it available Monday...

and NOW the RobotC program............................................ Enjoy!



//********************************************************
//********************************************************
//*!!Sensor, S1, LightLeft, sensorLightActive, , !!*//
//*!!Sensor, S3, LightRight, sensorLightActive, , !!*//
//*!!Motor, motorB, motorB, tmotorNxtEncoderClosedLoop, !!*//
//*!!Motor, motorC, motorC, tmotorNxtEncoderClosedLoop, !!*//
//*!! !!*//
//*!!Start automatically generated configuration code. !!*//
const tSensors LightLeft = (tSensors) S1; //sensorLightActive //*!!!!*//
const tSensors LightRight = (tSensors) S3; //sensorLightActive //*!!!!*//
const tMotor motorB = (tMotor) motorB; //tmotorNxtEncoderClosedLoop //*!!!!*//
const tMotor motorC = (tMotor) motorC; //tmotorNxtEncoderClosedLoop //*!!!!*//
//*!!CLICK to edit 'wizard' created sensor & motor configuration. !!*//

//* ********************************************************** *
//* * PID Global variables and array
//* ********************************************************** *
//* * dState Last position input
//* * iState Integrator state
//* * iMax, iMin Maximum and minimum allowable integrator state
//* * iGain Integral gain
//* * pGain Proportional gain
//* * dGain Derivative gain

float dState[2];
float iState[2];
float iMax[2];
float iMin[2];
float pGain[2];
float iGain[2];
float dGain[2];

//* ********************************************************** *
//* * Global variable used for Light sensor
//* ********************************************************** *
int nLeft;
int nRight;
float fError= 0.0;
float fsError= 0.0;

//* ********************************************************** *
//* * Light Sensor data acquiring (front left and right)
//* ********************************************************** *
task tLightSensors()
{
nSchedulePriority = kDefaultTaskPriority;
SensorMode[LightLeft] = modePercentage;
SensorMode[LightRight] = modePercentage;
while(true)
{
wait1Msec(3);
nLeft = SensorValue(LightLeft);
nRight = SensorValue(LightRight);
fError = (nRight - nLeft);
if (fError > fsError)
fsError = fError;
}
return;
}

//* ********************************************************** *
//* * PID controller
//* ********************************************************** *
float UpdatePID(int x, float error,float position)
{
float pTerm = 0.0, dTerm = 0.0, iTerm = 0.0, result = 0.0;
pTerm = pGain[x] * error;
// calculate the proportional term
// calculate the integral state with appropriate limiting
iState[x] += error;
if (iState[x] > iMax[x])
iState[x] = iMax[x];
else
if (iState[x] < iMin[x])
iState[x] = iMin[x];
iTerm = iGain[x] * iState[x]; // calculate the integral term
dTerm = dGain[x] * (position - dState[x]);
dState[x] = position;
result = pTerm + iTerm - dTerm;
return (result);
}

//* ********************************************************** *
//* * Arbiter nPower is the PID CMD
//* ********************************************************** *
void Arbiter(int nPower)
{
int outputL = 0;
int outputR = 0;

//* * Servo motors initial setup.
bFloatDuringInactiveMotorPWM = false;
nMaxRegulatedSpeed = 2160;
nPidUpdateInterval = 1;
nMotorPIDSpeedCtrl[motorB] = mtrSpeedReg;
nMotorPIDSpeedCtrl[motorC] = mtrSpeedReg;
motor[motorB] = nPower;
motor[motorC] = nPower;

//* ********************************************************** *
//* * PID save area.
//* ********************************************************** *
dState[0] = 0.0;
iState[0] = 0.0;

//* ********************************************************** *
//* * Tune the PID using gains parameters
//* ********************************************************** *
pGain[0] = 2.95;
iGain[0] = 0.0;
dGain[0] = 0.026;
//* ********************************************************** *
//* * Percent of the input cmd (motor power)
//* ********************************************************** *
iMin[0] = (nPower / 100.0) * 25.0;
iMax[0] = (nPower / 100.0) * 75.0;
//* ********************************************************** *
//* *
//* ********************************************************** *
while (true)
{
//* ********************************************************** *
//* * call the PID controller (Left motor-plant)
//* ********************************************************** *
if (fError < 0.0)
{
outputL = nPower - (int) UpdatePID(0,abs(fError),abs(fError));
if (outputL > nPower) outputL = nPower;
if (outputL < 0) outputL = 0;
motor[motorC] = outputL;
wait1Msec(1.0);
continue;
}

//* ********************************************************** *
//* * call the PID controller (Right motor-plant)
//* ********************************************************** *
if (fError > 0.0)
{
outputR = nPower - (int) UpdatePID(0,abs(fError),abs(fError));
if (outputR > nPower) outputR = nPower;
if (outputR < 0) outputR = 0;
motor[motorB] = outputR;
wait1Msec(1.0);
continue;
}

}
motor[motorB] = 0;
motor[motorC] = 0;
while(nMotorRunState[motorB] != runStateIdle);
return;
}

//* ********************************************************** *
//* * Main program
//* ********************************************************** *
task main()
{
nSchedulePriority = kDefaultTaskPriority;
eraseDisplay();
//* ********************************************************** *
//* * Start Light sensors
//* ********************************************************** *
StartTask(tLightSensors);
wait1Msec(1000);
//* ********************************************************** *
//* * Call the Arbiter
//* ********************************************************** *
Arbiter(40);
//* ********************************************************** *
//* * Stop all tasks
//* * Exit
//* ********************************************************** *
StopAllTasks();
return;
}

_________________
SuntzuMaster- a French gentlemen in USA.


Sun May 06, 2007 7:31 pm
Profile
Creator
Creator

Joined: Fri Feb 09, 2007 9:21 am
Posts: 614
Post 
Here's a hint on how to "publish" (i.e. include in a post) your source file with indentation and more readable format. It needs the latest pre-release of RobotC -- posting sometime this week.

RobotC's "EDIT" menu has an advanced sub-menu. There's three useful commands on it.
1. Tabilfy -- this will replace 'blanks' with tab characters when it can.
2. Untabify -- the opposite command. Replace tabs with 'blanks' (or ' ' character).
3. Format selection -- this will run through the current source selection and redo the indenting of your file where indentation is added for each "open" '{' character.

Somewhere in the "preferences" setup there is also a setting as to whether the RobotC editor will use only ' ' or tab characters in your text.

So, to "re-format" your text do the following:
1. Select all the text in your file.
2. Use the "format" command described above.
3. Use the "untabify" command described above.
4. Paste your text in the forum post.
5. Select the current text you've just pasted and click the "Code" button in the forum text editor. This will change the text to use mono-spaced Courier font.
6. Your text will now be easier to read in the post.

I'm not picking on you. :lol: I suspect the forum administrator may pick up on this post and add it as a separate "sticky" topic to the forum. Vu, Tim: Hint! Hint![/list]


Sun May 06, 2007 8:51 pm
Profile
Creator
Creator

Joined: Fri Feb 09, 2007 9:21 am
Posts: 614
Post 
SuntzuMaster:

A wondeful piece of code. From looking at it, I gather it is a line following robot using two light sensors.

My sone did a science fair project a while back on various line following algorithms. One of the conclusions he reached was that he wasn't able to squeeze much better performance out of two light sensors vs a single light sensor -- it was very tough to translate the two light sensors into a nice numeric quantity. Three light sensors was a lot easier to do!

I'm not sure how your robot performs. What I noticed from the science fair was that you could see the robot actually speed up on the straightaways and slow dow on the curve. On the straightaways any PID adjustments were very small and both motors were able to run at near maximum speed whereas on a curve there was lots of adjustments and the inner motor was running much slower than the outer motor. Did you see a similar performance?

You're right the PID factors are very dependent on the motor speed. They're also dependent on how far in front of the axle the sensor is mounted.

I couldn't find the video on Google Video. I guess it's not available yet


Sun May 06, 2007 9:00 pm
Profile
Rookie

Joined: Sun Apr 15, 2007 8:33 am
Posts: 40
Location: USA
Post 
Hello,

Thanks for your inputs about a potential new RobotC release.
I hope that there are more "C" like statments... and also more features...

I am working with Microsoft VS 2005 and I have to say that is really a very nice IDE! Anyway RobotC do just good and yes my code is well formed but when I cut and paste it then all the formating was lost...

My google video link : http://video.google.com/videoplay?docid=-9082535197088137732&hl=en

You will see that there is a spot of sun light on my test pad the robot is able to deal with that spot but it is oscillating a bit.

Could you tell me how large the track were because I have just used some standard electric tape that is not very large the LEGO test pad track is 2 cm and my home made track is >= 1.5 cm... I do believe that with a large track I could use a near max speed without changing my current PID setup...

Two light sensors are good enough with a PID because you just have to do S1-S2 = errorFactor...Then with my rbot If errorFactor < 0 then the Left motor must be fixed else if the errorFactor > 0 then the Right motor must be fixed.

I am also working around a robot able to perform a very precize object location using the US... I have already designed some functions to perform a very precize ZTR "zero turn radius" I can position my boot with a 1 degree of accuracy... I have also a nice odometer process for dead reckon navigation... I have also a bluetooth GPS but I need to write the function to interface the robot with the GPS using the NMEA protocol...
few other stuff around I2C for accelero meter, compas and color sensors...

I have also decided that I have to revisit all my calculus... I haven't done any real advanced calculus for the past 27 years!

I haven't yet done a test with a track that is more circular but I think that the robot should do good too. Have a look at my video and tell me what your thoughts are.

Have a great day.

_________________
SuntzuMaster- a French gentlemen in USA.


Mon May 07, 2007 8:05 am
Profile
Novice

Joined: Sun Feb 04, 2007 12:48 am
Posts: 69
Location: Australia
Post 
Wow this has turned into an awesome thread for information on line following. Thanks to Dick Swan for a fabulous conceptual explanation of PID and to SuntzuMaster for his obviously impressive code (I'm still at the conceptual level, working on interpreting SuntzuMaster's code).

One thing I was hoping to get further clarification about was the Integration component of PID. I understand the Proportional and the Derivative but the Integration appears to be missed in Dick's explanation above. It may be in there or implied but I'd love more conceptual detail if possible.

Part of my problem may be my bringing legacy concepts over from line edge following and 2 sensor line avoiding line following techniques. (For others: http://www.wrighthobbies.net/guides/linefollower.htm)

If you are using a single sensor line follower with PID, is the grey between the white and black line used as the set-point? Does it matter if you hit the grey on the other side of the black line?
If you are measuring the error/difference between two sensors as per SuntzuMaster's code how does it know the difference between straddling the line (or is the distance b/n the sensors less than the width of the line?) or being on the white sections to either the left or right of the black line. Is it the Integration component that remembers the distance away from the set-point but the algorithm is flexible enough to adjust the set-point if the line is curving left or right.

Sorry if this seems a bit basic to others, but I'm sure there are loads of other newbies who are stuggling with a similar lack of understanding who just need a bit of a step up or alternatively a good shove. :)

Thanks in advance,
James


Wed May 09, 2007 6:12 pm
Profile
Creator
Creator

Joined: Fri Feb 09, 2007 9:21 am
Posts: 614
Post 
Regarding single sensor used for following line-edge -- i.e. mid-point is gray and edge extremes are either white or black.

Knowing which "side" of the line you're on is a problem. Let's assume line is black and background is while. Your sensor starts detecting black so you appropriately adjust motors to move back to the edge. Now if your adjustment does not react fast enough the sensor can "drift" all the way past the line to the "wrong" edge. On this edge you adjustment factos have the opposite effect of what you expect and your robot will no longer follow the line.

There's two ways to compensate -- one is to slow the speed of your robot. The second is to widen the line. Usually only the first is a viable alternative.

Another soluiton is to increase the radius of a turn. This is why many line following contests will specify the width of the line and the minimum turn radius.

Mtulipel sensors can also help. If you can figure out the appropriate "error factor" two or three sensors can "widen" the area where you can make possible adjustments so that above doesn't happen.

Regarding "I" or "Integration Factor
The Integration factor is the sum of the individual errors frpom each cycle through the PID loop. The I factor should compensate for "constant" errors. Here's an example:

Suppose you had a well-tuned edge follower that was working great and doing a good job of tracking the target value of '50'. Suppose you drop you robot and the right wheel now drags against the robot -- has a lot more friction. Now your robot doesn't work so well.

Because of the higher friction your algorithm that was "tuned" to keep the light sensor at '50' no longer works well because right motor has more friction than left motor. If you're lucky, the robot will still continue to follow the line but now perhaps the light sensor seems to average 65.

The I factor will continue to accumulate as it adds the error of 15 (i.e. 65 - 50) each time through the PID loop. This accumulated error will add up and if there is a non-zero weighting factor involved then the "i" will compensate for the higher friction in the right motor.

Here's another example. You may want to drive a robot at a low speed (say 25% of full power). Robot is initially stopped and it takes a big temporary "kick" to get it moving. So you target speed is 25 and actual is 0 -- error factor is -25. Supporse your 'P' constant is 1 -- then the P-factor will try to move the motor at 25 which isn't enough to get it moving. Since the motor speed is not changing, the "D" (derivative) error is zero. You'd be stuck with a robot that won't move. But "I" factot would continue to add up and you might have a "I" constant of 0.1 (i.e. typically much smaller than "P"). The I factor will have little impact initially, but as it adds up the PID power level to use will increase -- after ten cycles the I error will be 250 and the I-factot will be 25 (250 x 0.1) so that power applied to motor will be 50 (remember P was 25). HOpefully motor will move.

So, generally I factor may take several cycles / iterations of PID loop to have an impact. It will also likely take several iterations for the I factor to again become insignificant. Some "modified" PID algorithms do not do a simple linear summation of the "I" factor because of this. They may throttle "I" error to a maximum value. They may also make "I" error calculation a time weighted value - e.g. new "I" = (old "I" x 75%) + (current "error x 25%) -- so that it will more rapidly converge back to zero when current error is smaller values.


Wed May 09, 2007 6:53 pm
Profile
Rookie

Joined: Sun Apr 15, 2007 8:33 am
Posts: 40
Location: USA
Post 
Hello,

it is me again...

I agree with Dick on the fact that with only one sensor you have very few if none possibilities to know if the robot is sliding on the left or on the right of the line.

PID works only if you can feed it with an error range from -x to 0 and from 0 to +x.

I can tell you that I have spend some time... to make it works...
I try to improve the PID gain(s) and I work also on how to improve the mechanical side of my robot...

Now I do believe that it could be very difficult to do with our LEGO what others do with their dedicated line follower robot... they use a sequential array of sensors (most of the time 7) then they arrange their sensors array like a "^" shape from that point they just have to poll the sensors in sequential mode to know where the line is... then they use I guess a preset motor speed... no need PID anymore... I saw some robots so fast that was incredible...

I shall keep you aware of my finding.

One thing that I want to test is to have a line of at least 2 cm... my current line is 1.5 cm... a larger line should make the robot more precize and faster too.

have a great day.

jm.

_________________
SuntzuMaster- a French gentlemen in USA.


Wed May 09, 2007 7:45 pm
Profile
Rookie

Joined: Sun Apr 15, 2007 8:33 am
Posts: 40
Location: USA
Post 
Just want to add that my robot sensors are on both side of the line then when SL-SR=0 then that mean that we are dead on the line. Obviously, if the error is positive then you are on one side and when it is negative on the other side (my sensor are set to give a % of light that is reflected).

The space between sensor is also another important factor...
smaller the space is, smoother the robot goes, but to make it stick to the line when a sharp turn must be negotiated is challenging... The PID must in that case be very very very well tune. You can achieve 100% at very low speed but as soon as the speed increase as soon the robot will be in trouble even with a very smooth turn... you can add space between sensor that could help to increase the robot speed too...

I saw also a large number of video on the internet about line following robot... so far I am quite happy about my result... I have to make it a bit smoother and then I shall be fully satisfied.

Last but not least, we should create a code repository were we could share our finding...

_________________
SuntzuMaster- a French gentlemen in USA.


Wed May 09, 2007 8:10 pm
Profile
Display posts from previous:  Sort by  
Reply to topic   [ 22 posts ]  Go to page 1, 2  Next

Who is online

Users browsing this forum: No registered users and 2 guests


You cannot post new topics in this forum
You cannot reply to topics in this forum
You cannot edit your posts in this forum
You cannot delete your posts in this forum
You cannot post attachments in this forum

Search for:
Jump to:  
cron



Powered by phpBB © 2000, 2002, 2005, 2007 phpBB Group.
Designed by ST Software for PTF.