ros-industrial / industrial_core

ROS-Industrial core communication packages (http://wiki.ros.org/industrial_core)
154 stars 181 forks source link

Scalar velocity calculation: is the ratio correctly calculated? #235

Closed gonzalocasas closed 5 years ago

gonzalocasas commented 5 years ago

Disclaimer: I post this as a question/doubt. I have the feeling there's a bug in the code, but I am not totally sure, and it is also possible that I'm misunderstanding something in the pipeline.

I've been trying to move our Staubli robots as fast as they can, and in doing so, I started checking the code of the industrial_robot_client more in depth, and I notice that the calculated scalar velocity is rather low for all my trajectory points.

So, if I understand correctly, the IRC (Industrial Robot Client), takes the list of velocities in the trajectory point, does fabs(v / v_limit) for each joint, where v_limit is the velocity limit for the joint, and from the resulting list of ratios, it selects the maximum, and uses that as velocity. Basically this bit of code.

Now, my question is: isn't there a mismatch between ranges of those two values? I believe the joint velocity is expressed in the range [-lower;+upper], e.g. ([-3.14159265359 rad/s; +3.14159265359 rad/s]), but the joint velocity limit is expressed in the range [0;limit], e.g. [0;7.59218224618 rad/s]). And if that's correct, that means the IRC is incorrectly unable to produce scalar velocities of 1.0 (I guess it maxes at 0.5).

gavanderhoorn commented 5 years ago

I believe the joint velocity is expressed in the range [-lower;+upper], e.g. ([-3.14159265359 rad/s; +3.14159265359 rad/s]),

"the joint velocity": where exactly?

but the joint velocity limit is expressed in the range [0;limit], e.g. [0;7.59218224618 rad/s]).

"the joint velocity limit": again: where exactly?

URDFs have only a positive limit. Trajectories also only list a single velocity.


I may be misunderstanding you, but afaict, the math is correct.

Very few robots -- or at least industrial robots -- have asymetric velocity limits (ie: different negative and positive limits). Typically a single limit is given, exactly as [0; limit]. "negative motion" is just a motion in a different direction, but the same velocity limit applies. You can only specify either a mm/s for a Cartesian translation (or whatever units the OEM prefers) or a % of maximum (typically joint moves).

If I'm not mistaken, this results in checking the given velocity for a traj pt against the range [0; limit] for a given joint. Your suggestion would essentially double the maximum velocity.

And if that's correct, that means the IRC is incorrectly unable to produce scalar velocities of 1.0 (I guess it maxes at 0.5).

are you asking because you encountered trajectories for which this happened, or was this the result of a hypothetical question and an analysis of the code?

Multiple factors can influence the maximum velocity requested, among which MoveIt's time parameterisation. A common problem is the absence of acceleration limits in MoveIt configuration pkgs, leading to MoveIt using 1 rad/s^2 as a default.

gonzalocasas commented 5 years ago

Of course, you're correct, the code is doing the right thing, so I will close this.

For completeness, to answer your questions:

"the joint velocity": where exactly?

In MoveIt's trajectories, i.e. specifically the JointTrajectoryPoint.

"the joint velocity limit": again: where exactly?

In the velocity attribute of the <limit> tag in Joint in URDF

are you asking because you encountered trajectories for which this happened, or was this the result of a hypothetical question and an analysis of the code?

I had issues with trajectories executing very slowly, in principle caused by a time parametrization problem because the actual velocity values in the trajectory output by MoveIt are very low, but during debugging, I bumped into this and I was confused into thinking it was wrong. (And btw, your hint about absence of acceleration limits is interesting, it might be the root cause of my issue, without derailing too much into the "wrong" issue, does that mean that by default, the lack of accel limits also limits velocities in MoveIt time parametrized trajectories to 1 rad/s?).

gavanderhoorn commented 5 years ago

does that mean that by default, the lack of accel limits also limits velocities in MoveIt time parametrized trajectories to 1 rad/s?)

if you have the limits configured properly it shouldn't limit the velocities, but the ramp up to those velocities will be capped at 1 rad/s^2.

See this line, where DEFAULT_VEL_MAX is set to 1.0 (rad/s) here.

And the same for DEFAULT_ACCEL_MAX here.

And that is in the default IterativeParabolicTimeParameterization: you'll probably want to use either the IterativeSplineParameterization or the TimeOptimalTrajectoryGeneration. See also 326511 on ROS Answers.