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

Settings for max velocity and acceleration not effected at real FANUC robot

asked 2021-11-11 08:23:59 -0500

nicob gravatar image

updated 2021-11-11 08:25:28 -0500

I am using the the python commands set_max_acceleration_scaling_factor(x) and set_max_velocity_scaling_factor(y) of the MoveGroupCommander class to control the speed behaviour of a FANUC robot, based on the industrial package.

This works finse in a simulation only environment in RViz accordingly to the joint limits defined in the file joint_limits.yaml. But if I connect ROS to the controller of the real robot, the robot is much more slowly. The robot does not seem to follow the max factors. Are there additional limits defined in the FANUC industrial package?

Thanks in advance!

nico

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-11-11 09:39:54 -0500

gvdhoorn gravatar image

updated 2021-11-11 10:02:31 -0500

If you're using fanuc_driver (you don't state which package you're using, but I assume it's that one), then it overrides the velocity commands. That's a limitation of that driver.

gavanderhoorn/fanuc_driver_exp tries to do better, and it will not override anything, but motion performance will still not be perfect.

There is a lot of existing Q&A and discussion on the issue tracker of both ros-industrial/fanuc and gavanderhoorn/fanuc_driver_exp which I don't want to repeat here. Summarising: except J519, there is no Fanuc motion interface which allows you to execute trajectories exactly as they are planned on the ROS side. That's both in time and in space. Off-line generation of TP programs based on ROS trajectories is possible (and has been done), but of course comes with its own disadvantages (limited length, programs need to be uploaded, delays before execution, etc).

An alternative could be a driver based on R912 (or Remote Motion Interface, RMI). That would essentially be a "drip-feed" of a TP program. I'm not aware of any publicly available implementation based on R912 though.

And note that again except with J519, you can never actually directly control velocity nor acceleration on a Fanuc. You only ever constrain maximum velocity, and can indirectly set the steepness of the acceleration curve.

edit flag offensive delete link more

Comments

See #q371112 for a similar Q&A, and see this page for more Fanuc related ROS questions (some / many of which are on similar topics).

gvdhoorn gravatar image gvdhoorn  ( 2021-11-11 09:47:43 -0500 )edit

Thanks for de detailed answer! This helps me a lot to understand the system better.

nicob gravatar image nicob  ( 2021-11-15 06:26:10 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-11-11 08:23:59 -0500

Seen: 815 times

Last updated: Nov 11 '21