PR2 / pr2_controllers

The controllers that run in realtime on the PR2 and supporting packages.
46 stars 34 forks source link

base controller 2 doesn't reach command velocity according to odometry #392

Open ichumuh opened 5 years ago

ichumuh commented 5 years ago

When I send a twist to the pr2 base, it doesn't reach the commanded velocity, according to odometry. pr2_doesnt_reach_cmd_vel This does not happen when we put the pr2 on blocks, so that the wheels are in the air. So I suspect that it is related to friction caused by the pr2's weight. We thought that such a steady state error should be fixable by increasing the I term for the wheels in the base controller 2 config file. But all it did was making the caster wheels behave weirdly. So I looked into the code and I think the pid controller is not used properly. https://github.com/PR2/pr2_controllers/blob/c01cb6fe038d348a4f2890ef43cc9cb0a7a873ef/pr2_mechanism_controllers/src/pr2_base_controller2.cpp#L470-L473 Here the new command for the wheels gets computed. The first term is error, where the velocity needed to help with the steering is put. And for error dot, the velocity difference is put, needed to make the robot drive forward. But that means that P and I only affect the steering and D affects how the pr2 drives forward. That seems very weird to me, is there a reason for this? It makes it impossible to get rid of the steady state error through tuning of the pid controller.

v4hn commented 5 years ago

Did you send translation commands in your experiment too, or was this rotation commands only?

Given the complex kinematic setup of the control via caster wheels, I'm not surprised this does not work perfectly. And in practice the observed behavior seemed to suffice for most experiments up to now.

This does not happen when we put the pr2 on blocks, so that the wheels are in the air. So I suspect that it is related to friction caused by the pr2's weight.

Do you have similar plots for this condition?

But that means that P and I only affect the steering and D affects how the pr2 drives forward. That seems very weird to me, is there a reason for this?

I believe there is nobody left in the field who could answer this question. If error dot is indeed derived from the forward velocity, that does not make a lot of sense. Did you experiment with different input terms? If you find a better alternative, I'm willing to try it out on our PR2 to compare results.

ichumuh commented 5 years ago

Did you send translation commands in your experiment too, or was this rotation commands only?

I can also see an error during translation.

Do you have similar plots for this condition?

I didn't save them, but I can create some if you'd like. It basically matches perfectly, when I command a constant speed. It lags a bit behind during acceleration, but that's to be expected.

Did you experiment with different input terms?

For the PID controller? no, was to afraid to touch that.

If you find a better alternative, I'm willing to try it out on our PR2 to compare results.

I have a temporary hacky solution that seems to work, because we have a deadline coming up. https://github.com/code-iai/pr2_controllers/blob/65febd2a6c652b57af819da0b6cb7a8b259f5985/pr2_mechanism_controllers/src/pr2_base_controller3.cpp#L465-L472

I've noticed that, when driving forward the offset is approx. 0.015 and when yawing its 0.04, which is also approx 0.015 vel of the outer wheel. So I just add that to the linear velocity and seems to work fine until now.

edit: this is how it looks with my solution: Screenshot from 2019-06-25 14-34-08

v4hn commented 5 years ago

I don't think these plots mean a lot unless you send the same controls to compare the different implementations.

Did you send translation commands in your experiment too, or was this rotation commands only?

I can also see an error during translation.

I meant to ask whether the behavior you see could be related to coupling between linear and rotation targets.

Did you experiment with different input terms?

For the PID controller? no, was to afraid to touch that.

Too bad. :)

Of course, your "hacky" solution will not be applied to upstream.