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

Position Controlled Motion with Velocity Constraint on Fanuc Robot

asked 2018-08-02 08:42:16 -0500

jbeck28 gravatar image

updated 2018-08-09 10:06:18 -0500

I'm currently trying implement path planning and execution of dense cartesian trajectories on fanuc arms. I've had reasonable success planning the path provided that I ignore the specified velocities on the points I'm planning to. I have read some threads which said to modify the duration_from_previous in a robot_trajectory::RobotTrajectory object to achieve different traversal speeds between points in a trajectory. Although this approach works perfectly well in simulation, upon moving the actual arm, I find that the arm only moves at constant velocity. Is there currently any way to adjust movement speed of a real, hardware fanuc arm? Any input would be greatly appreciated.

edit retag flag offensive close merge delete

Comments

May I suggest a topic change? 'velocity control' is typically understood to mean to control either the joints of a robot, or a Cartesian (eef) frame using pure velocity. That is not what you are asking for. Instead, you'd like your robot to perform a position controlled motion under certain ..

gvdhoorn gravatar image gvdhoorn  ( 2018-08-02 09:26:17 -0500 )edit

.. velocity constraints. The limiting factor here is the driver that doesn't seem to support that. Perhaps adding that to your question title would be a good thing.

gvdhoorn gravatar image gvdhoorn  ( 2018-08-02 09:27:21 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-08-02 09:16:55 -0500

gvdhoorn gravatar image

updated 2018-08-02 09:24:54 -0500

Unfortunately, the only way that you can approximate this is when generating TP programs in the traditional, off-line manner that CAM tools do this. Fanuc robots don't have the motion interfaces that would allow an on-line, closed loop implementation. This is not really a ROS limitation, it's just the way Fanuc controllers work.

The Insititute Maupertuis has made a package available that implements a basic 'post processor' for Fanuc TP (ie: .ls programs): InstitutMaupertuis/fanuc_post_processor.

You could use that to generate programs and then upload them to the controller.

Note: I wrote 'approximate this' as even with this the robot will still not always do exactly as you'd like it to do (due to interpolation/rounding/blending/etc), but at least the limitation is now on the robot controller side, not on the ROS side.

Note2: one of the major drawbacks of off-line program generation and upload is the inherent limitation of the length of the programs that can be used this way and the overhead experienced by the controller when it's parsing the new program. It's quite easy to quickly run into the limitations wrt maximum trajectory length and program size. An on-line, externally controlled, approach avoids these limitations (but of course is also not perfect).

edit flag offensive delete link more

Comments

Finally: there is some movement in this context: Fanuc has an option called DPM and I know of a (few) group(s) that are trying to use that to implement a better driver for Fanuc robots.

In addition, a new option was released only very recently (about a month ago) that will allow external control ..

gvdhoorn gravatar image gvdhoorn  ( 2018-08-02 09:20:43 -0500 )edit

.. of Fanuc robots in a decent way. A driver for that is not yet available though, and the availability of the option is also very limited (both in terms of supported controllers and robots as well as in distribution).

gvdhoorn gravatar image gvdhoorn  ( 2018-08-02 09:21:30 -0500 )edit

hey @gvdhoorn, me and jbeck28 work together, i was wondering if a, this is a good idea, and b, what CPP files would i need to edit so that i can essentially tack on the velocity to the packet sent to the controller, and just modify the karel script so that instead of having a hard coded 20% velocity

nquattro gravatar image nquattro  ( 2018-08-02 16:08:19 -0500 )edit

it deciphers it from the packet and puts it into the R[]% where it then moves through at that velocity?

nquattro gravatar image nquattro  ( 2018-08-02 16:10:07 -0500 )edit

There is no point in "editing CPP files": the way the controller works and the driver is setup (on the controller side) it's never going to be able to reach the velocities specified. And the velocity (and duration) are already both sent across by fanuc_driver. It's the karel side that ..

gvdhoorn gravatar image gvdhoorn  ( 2018-08-03 01:47:45 -0500 )edit

.. for fanuc_driver overrides the velocity. With fanuc_driver_exp velocity is not overridden, but it doesn't matter too much, as the controller will not be able to reach the specified velocities (because of look-ahead and other factors).

gvdhoorn gravatar image gvdhoorn  ( 2018-08-03 01:48:46 -0500 )edit

See these lines for where the velocity (as a percentage) is being communicated to the TP program by ros_traj.

If you aren't using fanuc_driver_exp, then I would ..

gvdhoorn gravatar image gvdhoorn  ( 2018-08-03 01:50:19 -0500 )edit

.. recommend you start doing that, as it's at least better than fanuc_driver (although it doesn't solve the velocity problem).

gvdhoorn gravatar image gvdhoorn  ( 2018-08-03 01:50:45 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-08-02 08:42:16 -0500

Seen: 1,030 times

Last updated: Aug 09 '18