Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Multirobot ABB driver setup #3

Open
SteveMacenski opened this issue Sep 18, 2016 · 13 comments
Open

Multirobot ABB driver setup #3

SteveMacenski opened this issue Sep 18, 2016 · 13 comments

Comments

@SteveMacenski
Copy link

Hi,
I have the abb_drivers running a single ABB IRB 120 and I'm trying to get both of them online. There is a footnote in the installServer tutorial saying "For multi-robot controllers, specify the desired robot (e.g. rob1) for each task" but that doesn't make new rostopics for the different robots to communicate through. How do I make multiple robots work with this driver? I don't see a clear place where I can change the topic names in ROS so that the robots can be commanded.

I have tried renaming all the files Rob1/2 at the end and updating the inside, but it kind of blows up on me very quickly and doesn't seem like it will work on the ROS side.

Thanks!

@gavanderhoorn
Copy link
Member

tl;dr: put relevant nodes / launch files in their own namespace. That will allow you to run multiple instances of everything while avoiding name clashes and without having to change anything in the pkg sources.


You'll want to put all the relevant nodes for each robot in their own namespace. That will automatically remap all the topics and prevent name clashes.

One way to conveniently set this up is to create a wrapper launch file that uses groups to start two instances of everything:

<launch>
  <arg name="left_robot_ip" />
  <arg name="left_robot_ip" />

  ...

  <group ns="left">
    <include file="$(find abb_irb120_support)/launch/robot_interface_download_irb120.launch">
      <arg name="robot_ip" value="$(arg left_robot_ip)" />
      ...
    </include>
  </group>

  ...

  <group ns="right">
    <include file="$(find abb_irb120_support)/launch/robot_interface_download_irb120.launch">
      <arg name="robot_ip" value="$(arg right_robot_ip)" />
      ...
    </include>
  </group>

  ...

</launch>

Topics created by nodes in any of the namespaces will automatically be prefixed with the namespace (ie: /left/joint_states etc).

The above launch file example assumes you have two separate controllers (with two IPs). If you have a dual motion-group setup, then the IP would be the same, but the port nrs should be changed. Unfortunately the robot_interface_download_.. launch files do not allow you to override those, so you'll have to basically copy/paste the contents of abb_driver/robot_interface.launch into each of the two namespaces and set the private port parameter on all of the involved nodes.

I've recently done this myself, so if you need any more info, just ask.

@gavanderhoorn
Copy link
Member

gavanderhoorn commented Sep 19, 2016

O, note btw that if you have a single-controller-multi-group setup, you'll still need to "specify the desired robot (e.g. rob1) for each task" on the controller/RAPID side. For multi-controller setups that is obviously not needed.

And of course change the ports that the RAPID programs listen on. I just added 1000 to them, so state server on 12002 and motion server on 12000 for the second group.

@SteveMacenski
Copy link
Author

SteveMacenski commented Sep 19, 2016

Hi!

I super appreciate you getting back to me. Using namespaces was initially my route but couldn't find a way to reconcile it, so thanks for helping! I'll plan on writing up a ros wiki tutorial about this content to make it easier for future folks.

I have a single controller multi robot set up (2 IRB120's running on an IRC5+1 drive module).

I have it running showing me robot_state, but the commands sent to 1 robot are executed on both, though I don't totally understand how ROS_motion.mod being the same on both robots knows which instance is going to which communications port.

For posterity, I have included the code below I got it working with!

<!-- Launch multiple ABB robots on a irc5 controller with additional drive modules -->

<launch>
  <!-- J23 not coupled for irb120, IP address found manually -->
  <arg name="robot_ip" default="192.168.125.1"/>
  <arg name="J23_coupled" default="false"/> 

  <!-- ports for socket communication in TCP -->
  <arg name="rosey_state_port" value="11002"/>
  <arg name="rosey_motion_port" value="11000"/>
  <arg name="gary_state_port" value="12002"/>
  <arg name="gary_motion_port" value="12000"/> 

  <!-- Robot 1 -->
  <group ns="rosey">
    <param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>

    <param name="J23_coupled" type="bool" value="$(arg J23_coupled)"/>

    <node pkg="abb_driver"
          type="robot_state"
          name="robot_state">
          <param name="port" value="$(arg rosey_state_port)"/>
    </node>

    <node pkg="abb_driver" 
          type="motion_download_interface"
          name="motion_download_interface">
          <param name="port" value="$(arg rosey_motion_port)"/>
    </node>

    <node pkg="industrial_robot_client" 
          type="joint_trajectory_action"
          name="joint_trajectory_action"/>
  </group>

  <!-- Robot 2 -->
  <group ns="gary">
    <param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>

    <param name="J23_coupled" type="bool" value="$(arg J23_coupled)"/>

    <node pkg="abb_driver"
          type="robot_state"
          name="robot_state">
          <param name="port" value="$(arg gary_state_port)"/>
    </node>

    <node pkg="abb_driver"
          type="motion_download_interface"
          name="motion_download_interface">
          <param name="port" value="$(arg gary_motion_port)"/>
    </node>     

    <node pkg="industrial_robot_client"
          type="joint_trajectory_action"
          name="joint_trajectory_action"/>
  </group>
</launch>

@SteveMacenski
Copy link
Author

I spoke too soon. My robot_state node is giving me feedback from both of the robots, but when I command one to move, they both move. Is this something that I needed to edit in the ROS_motion.mod file for the second robot version?

@gavanderhoorn
Copy link
Member

My robot_state node is giving me feedback from both of the robots, but when I command one to move, they both move. Is this something that I needed to edit in the ROS_motion.mod file for the second robot version?

yes. That is what I meant with "note btw that if you have a single-controller-multi-group setup, you'll still need to "specify the desired robot (e.g. rob1) for each task" on the controller/RAPID side".

@SteveMacenski
Copy link
Author

SteveMacenski commented Sep 19, 2016

I made separate tasks on the controller for each robot (motionserver, stateserver, motion) where the motionserver and stateserver included the updated port numbers. Within the RAPID codes for each module, do you have a summary of things that also require differentiation between the two robots? Its not overwhelmingly clear to me what variables would need to be changed in the motionserver/motion modules to have them be separated.

Edit: to be clear, I have the namespaces set up and the correct robot shows up in the joint_states for each (so not mirrors) in the right topic. The ros trajectory topics are only sending to and from 1 of the robots and both are executing, so its on the RAPID side. There are instances of the 3 .mod files for each robot with no edits except in motionServer and stateServer with the 12000 and 12001 port numbers (and changed names). I think there are some variables that are globals found in both motionServer and motion mod files that when 1 receives it, it globals to both. I'm just not sure which variable(s) it/they are. If you know it would be helpful! If not, I can try and play around until I find out what works.

@gavanderhoorn
Copy link
Member

@SteveMacenski: I'll check my notes and get back to you.

From what I remember you'll have to explicitly add which motion server is responsible for which group.

Note that this will get you asynchronous motion control over both groups only.

@SteveMacenski
Copy link
Author

SteveMacenski commented Sep 20, 2016

Hi @gavanderhoorn, I've been playing around a bit last night and found a solution. I'd still be curious as to how you did it to see which is better for use.

I was able to go into ROS_common.mod and make an instance of all of the global variables ROS_trajectory_lock, ROS_trajectory, ROS_trajectory_size, ROS_new_trajectory for each robot (appended a R1, R2 at end). Then went into the ROS_motion.mod and ROS_motionServer.mod files and replaced their versions of those globals with the R1/R2 versions. Reflashed and now I can command both robots through a publishing node at the same time (barring delays in script execution).

The only thing is after ~20 seconds of running the controller comes with a
ABB the system has entered system failure state most of the functionality has been disabled. See the event log for more information and problem cause

error (which is pretty interesting). But only when commanding both robots at once, at a frequency of commands >= 0.1 (works fine at 0.05). I'm sure I can get around this, it seems to be like a socketing problem where I'm sending too much stuff to the controller at one time. Probably solvable by sending one message at a time and watching for a 'I got it!' response before commanding the second robot.

@gavanderhoorn
Copy link
Member

@SteveMacenski: my apologies. I haven't had time yet to find my modified RAPID files.

Have you had any luck figuring this out by yourself in the meantime?

@SteveMacenski
Copy link
Author

@gavanderhoorn No problem, this weird shutdown problem happens occasionally. I think I've narrowed down what it's complaining about: if you send a new command while the robot is trying to get to the old one (so in motion) it happens.

Is there no error handling for changing a trajectory while the robot is still in motion?

@gavanderhoorn
Copy link
Member

gavanderhoorn commented Oct 1, 2016

@SteveMacenski wrote:

Is there no error handling for changing a trajectory while the robot is still in motion?

Well, trajectory replacement is expressly not supported at the moment. See void JointTrajectoryStreamer::jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg) for what should happen (basically: a trajectory stop, and your new trajectory ignored).

[..] commanding both robots at once, at a frequency of commands >= 0.1 (works fine at 0.05) [..]

abb_driver is a downloading driver, so there are some assumptions on the RAPID side that make it less suitable for things like dynamically changing trajectories.

What are you trying to do exactly?

@SteveMacenski
Copy link
Author

Hi!

What's actually happening when the robot is given a new trajectory before finishing the old one is an error on the pendant saying that motionServer has some error, and then it immediately says something about a failure state and disables all actions, requiring a power cycle,
ABB the system has entered system failure state most of the functionality has been disabled. See the event log for more information and problem cause

My goal is to be able to have some feedback control using a set of F/T sensors and visual segmentation with some cameras. We have a predicted trajectory of 2 robots manipulating a flexible plastic rod to a desired shape. However, the shape of the rod is more important than the robot's path, so if the shape deviates, the feedback system will kick on and adjust the trajectory to get back in the right path.

The only way I can see this working now is if we: send the robots some small subset of the trajectory, once it stops, check the shape calculate needed offsets, send another subset, repeat. This is slow and probably introducing a number of issues with the stop-start and synchronizing the motions.

There is the trajectory_action_controller/cancel topic that I imagine if it deviates, we just cancel the trajectory and send it a new one adjusted, but it doesn't look like the abb_driver uses that topic, does it? Also still a 'jerky' change, but that is unavoidable by the basis of the downloading driver.

Thanks for the help @gavanderhoorn

@SteveMacenski
Copy link
Author

After more testing, it appears that when running 1 robot and sending it another trajectory, the error you stated appears. When multiple robots do it, the system disable errors I described come up.
It's odd that they affect each other since they are different files running on a controller that should be powerful enough to handle it. The only thing I can think of is the TCP/IP connection gets "jammed" (in whatever way that makes sense) when sending back both "Empty trajectory received, canceling current trajectory" messages and causes one of the motionServers to fail- resulting in the errors I see.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Development

No branches or pull requests

2 participants