ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Motion performance between fanuc_driver/fanuc_driver_exp vs offline trajectory generation

asked 2021-02-05 00:45:23 -0500

dq18 gravatar image

updated 2021-02-05 01:32:56 -0500

gvdhoorn gravatar image

Hi,

We are using a Fanuc robot model for dense cartesian trajectories.

I have read a few topics to understand what would be the best way to interface with ROS to do that (#q299442, #q291577 and gavanderhoorn/fanuc_driver_exp#18), but I need some clarifications on the difference between using fanuc_driver or driver_exp and generating a TP program with an offline post-processor.

From what I understood, motion performance using fanuc_driver or fanuc_driver_exp is lower because they use position streaming, so the robot velocity is fixed by the robot controller and there is no "look-ahead" functionality. Is this the only reason? Generating the TP program offline will still result in keeping the CNT vs accuracy limitation as far as I understand, but could this limitation be removed some other way?

Thanks for the clarification

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-02-05 01:29:13 -0500

gvdhoorn gravatar image

updated 2021-02-05 01:41:03 -0500

First: let me start by saying this answer is based on my personal understanding, which is based on a few years of experience with Fanuc robots and writing external trajectory generation programs (or drivers) for them. I could be completely wrong, or have misunderstood some critical aspect of how they work. Keep that in mind when reading this.

From what I understood, motion performance using fanuc_driver or fanuc_driver_exp is lower because they use position streaming, so the robot velocity is fixed by the robot controller and there is no "look-ahead" functionality.

The 'fixed velocity' is not really a result of position streaming, it's just how fanuc_driver was implemented. fanuc_driver_exp does pass on velocities (or segment durations) to the Fanuc controller.

The biggest problem with the available implementations is the lack of look-ahead (or: both implementations deprive the controller of the possibility to use its look-ahead functionality, as it only ever has a single PR which is also constantly updating).

Is this the only reason? Generating the TP program offline will still result in keeping the CNT vs accuracy limitation as far as I understand

Whatever interface you use, as long as you use TP programs, there will always be the smoothness vs accuracy problem.

You can mitigate it somewhat by using CR termination types instead of CNT, as the former allows you to specify a radius instead of a percentage, but that is not supported by default in either fanuc_driver or fanuc_driver_exp (there is a branch in fanuc_driver_exp which was the result of some testing, see gavanderhoorn/fanuc_driver_exp@linear_support, which uses CR, but there is still no look-ahead (note: you cannot use the regular industrial_robot_client nor fanuc_driver nodes with that branch, as it uses a custom message type)).

could this limitation be removed some other way?

If "this limitation" refers to the smoothness vs accuracy then fundamentally all (industrial) robots suffer from this problem: smooth motions require continuity (up to the Nth derivative) so with sparse trajectories, you must introduce some form of cornering/blending/rounding (the robot cannot change direction instantaneously). Planners which are capable of taking jerk constraints (for instance) or higher into account and produce dense trajectories might get away with very little blending, but it'll probably still be there/necessary.

Off-line generation of TP programs is not inherently any better. It will however allow the controller to fully use look-ahead, which will improve motion smoothness. Dense trajectories will still slow-down the controller.

With newer controllers and the newest software versions, you have some alternatives to full off-line-and-upload approaches:

  • J519 (or Stream Motion): this is a real-time external motion interface which gets you 125 Hz joint and Cartesian position control over a UDP connection. Requires a real-time system and is difficult to buy from Fanuc (except in the US)
  • R912 (or Remote Motion Interface): this is essentially a drip-feed for TP programs. Look-ahead works, but same smoothness-vs-accuracy with CNT termination. Main advantage: unlimited program length and programs can be generated on-the-fly
  • use the spline motions ...
(more)
edit flag offensive delete link more

Comments

Note: there isn't really anything ROS specific here. Any software using any of the available motion interfaces to Fanuc controllers should run into the same limitations/problems/performance issues.

gvdhoorn gravatar image gvdhoorn  ( 2021-02-05 01:50:49 -0500 )edit

Very detailed answer as usual. Thanks for that! I am trying to find which industrial robot brand would give less difficulty to use in our application, so your answer definitely helps.

I am in China, so I am expecting even less support from Fanuc concerning the J519 and R912 interfaces, but will try and see with them.

I am leaving this thread open for a bit longer, in case someone wants to add something or his/her personal opinion

dq18 gravatar image dq18  ( 2021-02-05 05:40:16 -0500 )edit

So what did you end up using/trying?

gvdhoorn gravatar image gvdhoorn  ( 2021-02-28 01:55:42 -0500 )edit

We are just using fanuc_driver for now and testing offline TP generation. I would like to test with J519 as we have the option but I need to do some more research before

dq18 gravatar image dq18  ( 2021-03-01 20:37:27 -0500 )edit

I'm interested in knowing what the results/findings of your tests yielded. Any updates would be appreciated dq18, thank you.

robertdagenais gravatar image robertdagenais  ( 2021-12-14 14:27:55 -0500 )edit

The main finding is that Fanuc is not great for this kind of project :) We could not access J519 so we ended up using offline planning with a post-processor, similar to link text, but repurposed to our needs. That gave the best motion performance when motion is cartesian. To get a kind of "control" loop (i.e. reading stuff from the controller), we were using fanuc_driver_exp mostly for reading robot state and dominh. We eventually switched to ABB after pushing for months, but I left the project before I could see how much better it is.

dq18 gravatar image dq18  ( 2021-12-17 11:18:27 -0500 )edit

Thanks for the update dq18!

robertdagenais gravatar image robertdagenais  ( 2022-01-06 10:04:17 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-02-05 00:45:23 -0500

Seen: 1,359 times

Last updated: Feb 05 '21