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

Fanuc robot slows down at each trajectory point despite CNT is set to 100

asked 2019-03-11 07:38:54 -0600

razerblade gravatar image

updated 2019-10-08 05:21:29 -0600

gvdhoorn gravatar image

I'm using ROS kinetic and fanuc_driver_exp on the Fanuc LR Mate 200iD/4S (R30iB Mate controller). I am using MoveIt! to move the robot, RRTConnect planning library and TRAC_IK inverse kinematics solver. The problem is that the robot slows down at each trajectory point even when I use CNT 100 variable in ROS_TRAJ cfg.

What I have tried:

  • Using different OMPL planners, inverse kinematics planners with changing parameters.
  • Trying industrial trajectory filters (uniform_sample_filter and n_point_filter)
  • Enforcing joint model state space.
  • Using higher acceleration limits.
  • Moving the robot in moveit planning commander, RVIZ Motion Planning plugin and C++ move_group_interface.
  • Trying various CNT values on Fanuc controller.

Problem in more detail:

With the planners tunning I have reached solid trajectory planning success in my opinion (the velocity of the joints tries to follow trapezoidal profile and it changes without jumps in random directions as it was the problem at the beginning). The bottom graphs represent planned positions, accelerations and velocities for the first joint of the robot.

planned position

planned acceleration

planned velocity

But when I connect the ROS to the real robot, robot has a bit of jerky motion (more noticable at higher speeds). When analyzing the plot from joint_states for joint 1 position for the same move as planning it seems that the robot slows down at each planned point. The plot looks like this:

resulting position

I must say that after the tunning I got better performance (shaking occurs at higher velocity than before) but there are still some limits.

Now I wonder if you have any suggestions if there is anything else to try to enhance that motion? Or is this it and the limit to reach the smoothness lies in the controller?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2019-10-08 05:28:37 -0600

gvdhoorn gravatar image

Or is this it and the limit to reach the smoothness lies in the controller?

yes and no: it's a result of the way fanuc_driver and fanuc_driver_exp command motion and how the controller works internally.

I've written about this before, and my understand of how things work has not changed, so if you're interested you may want to search for older Q&As about this, both here on ROS Answers as well as on the ros-industrial/fanuc and gavanderhoorn/fanuc_driver_exp Github issue trackers.

Now I wonder if you have any suggestions if there is anything else to try to enhance that motion?

Unfortunately not with the current implementation of both fanuc_driver and fanuc_driver_exp.

If smoothness is a requirement for you, you may want to look into alternative ways of controlling your Fanuc. Either a full-blown post-processor-with-upload-of-trajectory (like InstitutMaupertuis/fanuc_post_processor) or something else entirely. There is work underway to integrate with Fanuc's new J519 (Stream Motion) option (ros-industrial/fanuc#247), but that has not been released yet.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-03-11 07:38:54 -0600

Seen: 2,425 times

Last updated: Oct 08 '19