Chief Delphi

Chief Delphi (http://www.chiefdelphi.com/forums/index.php)
-   Programming (http://www.chiefdelphi.com/forums/forumdisplay.php?f=51)
-   -   Motion Profiling (http://www.chiefdelphi.com/forums/showthread.php?t=98358)

theNerd 20-11-2011 17:45

Motion Profiling
 
I've been starting to research into some more advanced techniques for robot controlling and I stumbled upon what's called motion profiling. I looked a little more on this on the internet and I found out a little about the trapezoidal and s-curve profiles. However all I know is the kinematic relationships (velocity, acceleration...) and I'm confused about how to take this to the useful level. Could the awesome robotics community out there help me in learning the basics of motion profiling and how to implement it into a robot design - especially a drive system?

AustinSchuh 28-11-2011 20:04

Re: Motion Profiling
 
FYI, 254's code uses trapezoidal motion profiles for all drivetrain moves. If you are willing to dredge through the code, you can see how a team used them last year.

I like to conceptually visualize motion profiles as a filter (even though it is not LTI, so this is an abuse of terminology to me). You tell the filter that you want to go to position "10", and it tells you what to do for the next time step to get closer to "10" while only moving with a maximum acceleration and velocity that you configure the filter with. This is essentially how we implemented it.

I would start by writing code on your local machine to generate motion profiles and debug it by plotting the output to see if it works or not. It is quite hard to debug this type of stuff on a running robot.

Jared Russell 29-11-2011 08:11

Re: Motion Profiling
 
To echo what Austin said: This is a great example of something you can develop and test without a running robot. Write the code to generate a trapezoidal motion profile using J2SE or on a desktop using C++, debug using Excel, Matlab, or Gnu plots, and you will be able to port it to your robot code with ease.

Of course, once you are generating your trapezoidal motion profiles, you will need a controller that makes sure the bot actually follows it! Here are a few ideas on how you could do this:

1. Use a PID loop on your drive motors (in distance mode). Use the speed output of your motion profile to limit the maximum command that PID is allowed to send to your motors.

2. Use a PID loop on your drive motors (in speed mode). As long as your speed loop has an integral term (the I gain is nonzero), this should get you where you are going.

3. Use both (1) and (2) to control both speed and distance; there is also a specialized "PIV" controller used in industrial servos that mixes both speed and distance to command the motors.

4. Just use the speed command you generated to drive the motors directly (open loop), but switch to a PID controller when you get close to the goal to go the last few inches.

5. Make a full-state controller using control theory and simulation; if you go this route you are either insane or 254 :)

AustinSchuh 03-12-2011 02:46

Re: Motion Profiling
 
Good point Jared. Once you have a profile, you need to follow it.

My favorite controller for following trajectories is as follows (I think this is a modification of 3). I used it before I got tired of hand-tuning the PD for the drivetrain and switched to state feedback.

pwm = P * error + D * ((error - prev_error) / dt - goal_velocity) + Kv * goal_velocity + Ka * goal_acceleration

This is close to a PD controller, but with some feed forward terms. The idea behind feed forwards is that if you have a pretty good idea about how much power it will take to do something, go ahead and add it in. The control loop will take up the slop from there when you are wrong, or someone bumped the bot.

The D term is special in that you subtract off the goal velocity. This falls out from the state feedback controllers. Think about it this way. If you are at the goal, and moving at the right speed, you don't want to apply corrective power to decelerate the robot (This is what D would do if you weren't trying to move but were moving and at the goal.)

The Kv and Ka feed forwards terms make a lot of sense. It takes power to move at a velocity, so add that power on... Same for acceleration. It takes power to accelerate, so just add the power right on. You can get the goal velocity and acceleration from your profile.

A properly tuned controller with motion profiles will produce some very nice and smooth motion.

winchymatt 19-12-2012 12:44

Re: Motion Profiling
 
Quote:

Originally Posted by AustinSchuh (Post 1088309)
Good point Jared. Once you have a profile, you need to follow it.

My favorite controller for following trajectories is as follows (I think this is a modification of 3). I used it before I got tired of hand-tuning the PD for the drivetrain and switched to state feedback.

pwm = P * error + D * ((error - prev_error) / dt - goal_velocity) + Kv * goal_velocity + Ka * goal_acceleration

Hi,

Realise this is an old thread, but hopefully you will pick this up..

I have been working with PID controllers for a while now, but have never looked at adding feed forward terms. This looks really interesting for a hydraulic system I'm currently working on.

I have a few questions with regards to your controller above:

1) What is your (dt) term within the D part of your controller.

2) Do you determine the goal_velocity and goal_acceleration from the goal position within the controller, or do you send these in from your trajectroy planner?

3) Can you point me to a code example of this controller?

I have a bunch of other questions but figured I would start with this.. :)

Matt.

AustinSchuh 20-12-2012 01:12

Re: Motion Profiling
 
DT is the period of your loop.

Acceleration, velocity and position are from the trajectory planner.

254's 2011 code has this as part of the drive train autonomous code. It should be available in the whitepapers on this site.

Austin

winchymatt 20-12-2012 07:40

Re: Motion Profiling
 
Quote:

Originally Posted by AustinSchuh (Post 1203347)
DT is the period of your loop.

Acceleration, velocity and position are from the trajectory planner.

254's 2011 code has this as part of the drive train autonomous code. It should be available in the whitepapers on this site.

Austin

Great thanks, yes I should have known dt would be discrete time! I checked out the code and the trajectory planner was a great help! Imported the ContinuousAccelFilter class into my borland builder test app, works really well! Thanks for the pointers.

So on a side note, if you were sending just position information to the PID controller, and did not have velocity and acceleration data, could one derive the velocity and acceleration by differentiating the position data with the previous position.. I guess this would not produce a true goal velocity, but may give some feed forward gain??

Matt.

flameout 20-12-2012 21:55

Re: Motion Profiling
 
Quote:

Originally Posted by winchymatt (Post 1203367)
So on a side note, if you were sending just position information to the PID controller, and did not have velocity and acceleration data, could one derive the velocity and acceleration by differentiating the position data with the previous position.. I guess this would not produce a true goal velocity, but may give some feed forward gain??

Matt.

You can, if and only if that signal is twice differentiable. If not, then you'll get bad spikes in your data -- if you have spots that are not twice differentiable, you'll need to differentiate on each side then use each section as a separate input, essentially "cutting out" the bad spots. This is much more useful if the position trajectory is derived via some analytical or numerical process -- you'll likely have a ton of noise if you try to do this with real sensor data.

Also, with full PID, having a feedforward on the velocity target will cause overshoot, just FYI.* If you're doing PID for position control, then having an acceleration feedforward should be fine; a velocity feedforward would be beneficial if you're doing PD.

If anyone disagrees with any of the statements in this post, please correct me -- this is operating at the edge of my knowledge of control theory.

* This statement is incorrect, please see AustinSchuh's post below.

Paul Copioli 20-12-2012 21:59

Re: Motion Profiling
 
Quote:

Originally Posted by winchymatt (Post 1203367)
So on a side note, if you were sending just position information to the PID controller, and did not have velocity and acceleration data, could one derive the velocity and acceleration by differentiating the position data with the previous position.. I guess this would not produce a true goal velocity, but may give some feed forward gain??

Matt.

Matt,

The problem with this method is that discrete differentiation induces noise into the control loop. By using the path planning algorithm you have a pure, non noisy, velocity and acceleration profile.

Paul

AustinSchuh 21-12-2012 01:25

Re: Motion Profiling
 
Quote:

Originally Posted by flameout (Post 1203601)
Also, with full PID, having a feedforward on the velocity target will cause overshoot, just FYI. If you're doing PID for position control, then having an acceleration feedforward should be fine; a velocity feedforward would be beneficial if you're doing PD.

I disagree with this statement. I'll give you a fuzzy explanation now, and try to find time to prove it for real with the math later. I'll probably cheat and give you the continuous time proof...

You can model the velocity feed forward as a disturbance. It adds a power to the motors that the control loop is not expecting. This power is constant (at least at constant velocity), so, since the loop is stable, it will stabilize out and converge. This is very similar from the loop's perspective to changing the goal, and since both of them are happening at the same time, it shouldn't have much effect.

Differentiating the goal signal will also introduce delay into it. This won't have a huge effect on the system since the time constant of a robot is very slow compared to a good loop frequency, but this can become more and more pronounced as your system's time constant gets closer to the period of your loop.

Paul Copioli 21-12-2012 02:01

Re: Motion Profiling
 
I agree with Austin on this one. Velocity feed forward (and acceleration FF, and current FF) all work to stabilize the PID loop. Instead of your proportional gain having to do all the heavy lifting, a small understanding of PWM in value vs actual rotational speed will decrease the proportional gain required. At full voltage the PID is ideally only dealing with disturbances. As the battery dies, the P will have to do a little more work since the FF mapping is no longer valid (but better than 0).

In our FRC auton application it is a huge advantage to use FF gain since you are presumably using a fully charged battery.

Put another way, the P gain is a multiplier. The smaller that multiplier is allowed to be, the less oscillation and general "what the heck just happened" sessions will happen.

Tom Line 21-12-2012 03:28

Re: Motion Profiling
 
Quote:

Originally Posted by Jared341 (Post 1087308)
To echo what Austin said: This is a great example of something you can develop and test without a running robot. Write the code to generate a trapezoidal motion profile using J2SE or on a desktop using C++, debug using Excel, Matlab, or Gnu plots, and you will be able to port it to your robot code with ease.

Of course, once you are generating your trapezoidal motion profiles, you will need a controller that makes sure the bot actually follows it! Here are a few ideas on how you could do this:

1. Use a PID loop on your drive motors (in distance mode). Use the speed output of your motion profile to limit the maximum command that PID is allowed to send to your motors.

2. Use a PID loop on your drive motors (in speed mode). As long as your speed loop has an integral term (the I gain is nonzero), this should get you where you are going.

3. Use both (1) and (2) to control both speed and distance; there is also a specialized "PIV" controller used in industrial servos that mixes both speed and distance to command the motors.

4. Just use the speed command you generated to drive the motors directly (open loop), but switch to a PID controller when you get close to the goal to go the last few inches.

5. Make a full-state controller using control theory and simulation; if you go this route you are either insane or 254 :)

I'm a bit lost as to why a trapezoidal profile would be better than a well tuned PID. It seems to me that you want to accelerate as quickly as possible for as long as possible, then decelerate as quickly as possible and stop at your location.

How does a 'profile' do that any better than PID?

Paul Copioli 21-12-2012 03:42

Re: Motion Profiling
 
That profile actually gives you a predictable and repeatable motion path almost regardless of battery voltage (I say almost because a dead battery is a dead battery). The PID should only be used for disturbance correction. All high end industrial robots that need ridiculously good repeatability use the motion planning method. FANUC uses trapezoidal Acceleration profile and triangular acceleration profile (for really short motions) to control motion. The biggest issue fighting repeatability is Jerk (the derivative of Acceleration) and the trapezoidal acceleration profile helps fight this.

Most wafer robots used in the silicon industry use triangular aceeleration, but the loads are a bit higher with a tradeoff of shorter time to target.

In general, it is good practice to do some sort of motion planning to increase reliability. Most of us FRC people are just too lazy to actually do it and use PID to control everything.

flameout 21-12-2012 09:01

Re: Motion Profiling
 
Quote:

Originally Posted by AustinSchuh (Post 1203654)
I disagree with this statement.

I think you're right -- I was making an assumption that I did not state in my post. I was assuming that the velocity feedforward gain (your Kv) is sufficient to cause essentially zero steady-state error without an integral component -- if it is less, than it is possible to have no overshoot. Also, I was not claiming that it would be unstable -- it would overshoot once then return to the setpoint in a perfectly stable manner.

Here's where I'm coming from, assuming Kv is as described above (i.e. would cause approximately 0 steady state error with no integral component):

Say you're moving steadily (tracking a target trajectory) at a velocity of 1 (arbitrary units) -- your P, I, and D terms are all approximately zero, since you are at steady state. The Kv term is the majority of your control signal.

Now suppose the target trajectory changes to a velocity of 2 -- this could happen either smoothly or instantaneously. Due to the system's inertia, it will find itself at less than the desired position. Therefore, the control system will correct, trying to bring the state towards the new setpoint.

During this time, the previously-small I term will be growing as the errors accumulate. However, due to the Kv term, the necessary I term to maintain zero steady state error at the setpoint is approximately zero. Since the I term will not begin decreasing until it has overshot, it is guaranteed to overshoot.

This overshoot may or may not be acceptable. Additionally, if Kv is less than the value I've described, then it would only decrease the Ki value necessary to prevent overshoot, and decrease the rise time of the controller, which may be desirable.

Tom Line 21-12-2012 17:52

Re: Motion Profiling
 
Ok. After reading a bit more online, I understand some of the terms. Jerk is caused by the transition between acceleration / velocity, velocity / deceleration, or acceleration / deceleration. Those are the 'sharp' points on the graph.

To create a motion profile utilizing acceleration and deceleration, don't you have experimentally measure these to accurately determine what your robot is capable of?

From what I understand, motion profiling would seem to get you to your position point more quickly that PID. With PID, you have your drive values taper off as you get closer to your setpoint. With motion profiling, you would stay at your maximum velocity until it's time to go into maximum deceleration.

Is this accurate?


All times are GMT -5. The time now is 06:45.

Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi