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

How to simulate and control 2 industrial robots with Moveit ?

asked 2020-10-04 07:14:52 -0500

Vaneltin gravatar image

Hi !

I'm trying to simulate an industrial workcell with 2 industrial robots : Staubli TX2-60L and TX2-90L. I've made a XACRO file with all the elements of the workcell and the two robots. I've made a moveit package with 2 move group : one for each robots.

But when I try to move in the same time the robots with two python script, it doesn't work. Only one is moving.

Do you have an idea ?

Thank you

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-10-04 23:44:48 -0500

fvd gravatar image

updated 2020-10-04 23:47:13 -0500

Currently, you cannot execute two trajectories at the same time with MoveIt. This is a known limitation and related to the way MoveIt does trajectory execution monitoring. Here is a Github issue with more in-depth discussion (and how you could contribute to improving this part of the codebase).

At the moment, the main workarounds are:

  • Combine your two robots into one planning group, e.g. both_arms, and set multiple goals (e.g. one pose goal for each end effector) for your plan. This way, the plan will contain both robots' trajectories and avoid collisions between the robots. This is the safe and sane option.
  • If you need to move the robots asynchronously, you can obtain your two robot trajectories with the plan() function and then send them to the robot controllers to be executed. However, there will be no collision monitoring, and if the two trajectories move the robots are moving into the same area, they will collide. Only do this if are absolutely certain (!) that the two independent robot trajectories will not result in a collision.
  • Alternatively to calling the robot controllers' follow_joint_trajectory action, you can merge the two robot trajectories into a single trajectory containing the joints of both robots and execute it with MoveGroupCommander or move_group_interface. But the risks regarding collision are the same, because the plan for each robot was calculated without considering the other robot's motion.

To reiterate: Do not attempt the two latter options unless there is no risk of collision between the robots, and be aware that this is dangerous and that you can absolutely break your robots if you are not careful.

edit flag offensive delete link more

Comments

Thank you very much for your clear answer!

Vaneltin gravatar image Vaneltin  ( 2020-10-06 02:10:18 -0500 )edit

Hi~

We can not execute two trajectories at the same time, but we can plan them one by one?

cshmilyc gravatar image cshmilyc  ( 2021-09-16 06:17:11 -0500 )edit

You can plan them one by one already, but you can currently only execute one at a time through the MoveGroupInterface's execute() function. We recently submitted this PR which allows the execution of multiple trajectories via the MoveIt interfaces while checking for collision between them. You can test it yourself if you build it from source.

fvd gravatar image fvd  ( 2021-09-16 20:00:00 -0500 )edit

Thanks, @fvd~ I'll follow your research and try

cshmilyc gravatar image cshmilyc  ( 2021-09-17 22:10:45 -0500 )edit

Hi, again~ Shall I pull the repository from cambel:simultaneous-motions and build a specialized version "moveit" and replace the origin one in ROS?

cshmilyc gravatar image cshmilyc  ( 2021-09-17 22:28:19 -0500 )edit

1) Put it in your catkin workspace with the dependencies and build it, then it will be used instead of the binary install
2) Post a new question or look at the tutorial to build moveit if you get stuck more

fvd gravatar image fvd  ( 2021-09-18 07:37:45 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2020-10-04 07:14:52 -0500

Seen: 529 times

Last updated: Oct 04 '20