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

Problem working with real IRB 1200 robot #156

Closed
rajmohan747 opened this issue Jul 28, 2018 · 17 comments
Closed

Problem working with real IRB 1200 robot #156

rajmohan747 opened this issue Jul 28, 2018 · 17 comments

Comments

@rajmohan747
Copy link

Hi,
I am with IRB 1200 in ROS-Kinetic platform.
Initially I am launching

roslaunch abb_irb1200_support robot_interface_streaming_irb1200_5_90.launch robot_ip:=192.168.125

Since I'm working with real robot, sim parameter was set as True. On launching ,

roslaunch abb_irb1200_5_90_moveit_config moveit_planning_execution.launch sim:=false robot_ip:=192.168.125.1

I am facing an error as robot_interface_streaming_irb1200_5_90.launch is not available.

Also tried replacing robot_interface_streaming_irb1200_5_90.launch with robot_interface_download_irb1200_5_90.launch.

After that on launching the node to move the robot,the teach pendant is showing like:

Sending  24 points to MOTION Task.  Traj START received Traj END received

But the robot is still not moving

Please correct me, if I'm doing something wrong

@gavanderhoorn
Copy link
Member

For both of you: did you follow the installation and setup tutorials?

@rajmohan747
Copy link
Author

@gavanderhoorn : Yes ,I followed the same procedure only.

@gavanderhoorn
Copy link
Member

Please describe exactly how you are starting the programs on the robot, in what mode it is, what you do with the TP after having started the programs, etc.

Also: please verify that you've correctly configured all programs on the controller.

A robot not moving is typically caused by the robot being in Manual mode but you're not holding the enabling device or because the tasks have not been correctly configured.

@rajmohan747
Copy link
Author

rajmohan747 commented Aug 1, 2018

We repeated the entire procedure with an older version of the same package https://github.com/arjunskumar/ABB-IRB-1200 and this worked.

@gavanderhoorn
Copy link
Member

As that is not a fork, it's inconvenient for me to compare the two.

Could I ask you to compare the contents of abb_driver in arjunskumar repository and the one in ros-industrial/abb_driver? Perhaps that will provide a clue.

@gavanderhoorn
Copy link
Member

gavanderhoorn commented Aug 1, 2018

There are not too many changes between those two versions, mainly the addition of the external axes support and a hard-coded IP (192.168.125.5) which I expect you had to change:

18c18
<   <arg name="robot_ip" doc="IP of the controller"/>
---
>   <arg name="robot_ip" />
21c21
<   <arg name="J23_coupled" default="false" doc="If true, compensate for J2-J3 parallel linkage" />
---
>   <arg name="J23_coupled" default="false" />
diff -Nr abb/abb_driver/package.xml ABB-IRB-1200/abb_driver/package.xml
16,17c16,17
<   <author>Shaun Edwards</author>
<   <maintainer email="levi.armstrong@swri.org">Levi Armstrong (Southwest Research Institute)</maintainer>
---
>   <author email="sedwards@swri.org">Shaun Edwards</author>
>   <maintainer email="sedwards@swri.org">Shaun Edwards</maintainer>
diff -Nr abb/abb_driver/rapid/ROS_common.sys ABB-IRB-1200/abb_driver/rapid/ROS_common.sys
33d32
<     extjoint extax_pos;
diff -Nr abb/abb_driver/rapid/ROS_messages.sys ABB-IRB-1200/abb_driver/rapid/ROS_messages.sys
44d43
<     extjoint ext_axes;
53d51
<     extjoint ext_axes;
112,118c110,113
<     UnpackRawBytes raw_message.data, 29, message.ext_axes.eax_a, \Float4;
<     UnpackRawBytes raw_message.data, 33, message.ext_axes.eax_b, \Float4;
<     UnpackRawBytes raw_message.data, 37, message.ext_axes.eax_c, \Float4;
<     UnpackRawBytes raw_message.data, 41, message.ext_axes.eax_d, \Float4;
<     UnpackRawBytes raw_message.data, 45, message.velocity, \Float4;
<     UnpackRawBytes raw_message.data, 49, message.duration, \Float4;
<
---
>     ! Skip bytes 29-44.  UNUSED.  Reserved for Joints 7-10.  TBD: copy to extAx?
>     UnpackRawBytes raw_message.data, 29+(ROS_MSG_MAX_JOINTS-6)*4, message.velocity, \Float4;
>     UnpackRawBytes raw_message.data, 33+(ROS_MSG_MAX_JOINTS-6)*4, message.duration, \Float4;
>
121d115
<     message.ext_axes := m2mm_extjoint(message.ext_axes);
131d124
<     VAR extjoint ROS_ext_axes;
141d133
<     ROS_ext_axes := mm2m_extjoint(message.ext_axes);
151,154c143,145
<     PackRawBytes ROS_ext_axes.eax_a,  raw_message.data, 29, \Float4;
<     PackRawBytes ROS_ext_axes.eax_b,  raw_message.data, 33, \Float4;
<     PackRawBytes ROS_ext_axes.eax_c,  raw_message.data, 37, \Float4;
<     PackRawBytes ROS_ext_axes.eax_d,  raw_message.data, 41, \Float4;
---
>     FOR i FROM 1 TO ROS_MSG_MAX_JOINTS-6 DO   ! Insert placeholders for joints 7-10 (message expects 10 joints)
>         PackRawBytes 0,               raw_message.data, 25+i*4, \Float4;
>     ENDFOR
164,192d154
< ENDFUNC
<
< LOCAL FUNC num connected_eax(num eax)
<     ! The value 9E9 is defined for axes which are not connected
<     IF eax <> 9E9 THEN
<         RETURN eax;
<     ENDIF
<     RETURN 0;
< ENDFUNC
<
< ! Returns only connected external axes in METERS
< LOCAL FUNC extjoint mm2m_extjoint(extjoint all_eax)
<     VAR extjoint eax;
<     eax.eax_a := connected_eax(all_eax.eax_a) / 1000;
<     eax.eax_b := connected_eax(all_eax.eax_b) / 1000;
<     eax.eax_c := connected_eax(all_eax.eax_c) / 1000;
<     eax.eax_d := connected_eax(all_eax.eax_d) / 1000;
<     RETURN eax;
< ENDFUNC
<
< ! Returns external axes in MILLIMETERS
< LOCAL FUNC extjoint m2mm_extjoint(extjoint eax_in_m)
<     VAR extjoint eax_in_mm;
<     eax_in_mm.eax_a := eax_in_m.eax_a * 1000;
<     eax_in_mm.eax_b := eax_in_m.eax_b * 1000;
<     eax_in_mm.eax_c := eax_in_m.eax_c * 1000;
<     eax_in_mm.eax_d := eax_in_m.eax_d * 1000;
<
<     RETURN eax_in_mm;
diff -Nr abb/abb_driver/rapid/ROS_motion.mod ABB-IRB-1200/abb_driver/rapid/ROS_motion.mod
57d56
<                 target.extax := trajectory{current_index}.extax_pos;
59c58
<                 skip_move := (current_index = 1) AND is_near(target, 0.1, 0.1);
---
>                 skip_move := (current_index = 1) AND is_near(target.robax, 0.1);
89c88
< LOCAL FUNC bool is_near(jointtarget target, num deg_tol, num mm_tol)
---
> LOCAL FUNC bool is_near(robjoint target, num tol)
94,103c93,98
<     RETURN ( ABS(curr_jnt.robax.rax_1 - target.robax.rax_1) < deg_tol )
<        AND ( ABS(curr_jnt.robax.rax_2 - target.robax.rax_2) < deg_tol )
<        AND ( ABS(curr_jnt.robax.rax_3 - target.robax.rax_3) < deg_tol )
<        AND ( ABS(curr_jnt.robax.rax_4 - target.robax.rax_4) < deg_tol )
<        AND ( ABS(curr_jnt.robax.rax_5 - target.robax.rax_5) < deg_tol )
<        AND ( ABS(curr_jnt.robax.rax_6 - target.robax.rax_6) < deg_tol )
<        AND ( ABS(curr_jnt.extax.eax_a - target.extax.eax_a) < mm_tol )
<        AND ( ABS(curr_jnt.extax.eax_b - target.extax.eax_b) < mm_tol )
<        AND ( ABS(curr_jnt.extax.eax_c - target.extax.eax_c) < mm_tol )
<        AND ( ABS(curr_jnt.extax.eax_d - target.extax.eax_d) < mm_tol );
---
>     RETURN ( ABS(curr_jnt.robax.rax_1 - target.rax_1) < tol )
>        AND ( ABS(curr_jnt.robax.rax_2 - target.rax_2) < tol )
>        AND ( ABS(curr_jnt.robax.rax_3 - target.rax_3) < tol )
>        AND ( ABS(curr_jnt.robax.rax_4 - target.rax_4) < tol )
>        AND ( ABS(curr_jnt.robax.rax_5 - target.rax_5) < tol )
>        AND ( ABS(curr_jnt.robax.rax_6 - target.rax_6) < tol );
diff -Nr abb/abb_driver/rapid/ROS_motionServer.mod ABB-IRB-1200/abb_driver/rapid/ROS_motionServer.mod
69c69
<     point := [message.joints, message.ext_axes, message.duration];
---
>     point := [message.joints, message.duration];
diff -Nr abb/abb_driver/rapid/ROS_socket.sys ABB-IRB-1200/abb_driver/rapid/ROS_socket.sys
32c32
<     IF (SocketGetStatus(server_socket) = SOCKET_CREATED) SocketBind server_socket, GetSysInfo(\LanIp), port;
---
>     IF (SocketGetStatus(server_socket) = SOCKET_CREATED) SocketBind server_socket, 192.168.125.5, port;
104c104
< ENDMODULE
\ No newline at end of file
---
> ENDMODULE
diff -Nr abb/abb_driver/rapid/ROS_stateServer.mod ABB-IRB-1200/abb_driver/rapid/ROS_stateServer.mod
70d69
<     message.ext_axes := joints.extax;

As the robot didn't move for you, I'm suspecting something wrong with bool is_near(robjoint target, num tol).

@gonzalocasas: any ideas?

@gonzalocasas
Copy link
Contributor

@gavanderhoorn I'll check. Afaik, the IRB-1200 has the same controller version, so I would expect this to behave the same, but judging from the diff you posted, I would tend to agree with you in your suspicion.

@rajmohan747 in the meantime, could you please confirm which exact robotware version you have? Also, have you tried the same in simulation, i.e. RobotStudio?

@rajmohan747
Copy link
Author

@gonzalocasas : I am using Roboware version 6.05.00.00

@gonzalocasas
Copy link
Contributor

@rajmohan747 and did you try in simulation as well? Does it behave the same way? Or does the RobotStudio simulation move fine but not the real robot?

@rajmohan747
Copy link
Author

@gonzalocasas I have not tried on RobotStudio simulation.
It was directly experimented with real robot

@gavanderhoorn
Copy link
Member

@gonzalocasas: have you have a chance to test things?

@gonzalocasas
Copy link
Contributor

@gavanderhoorn unfortunately, not yet. I don't have a real IRB-1200 available. I want to test on simulation, but I will only be able to do it in about 2 weeks from now.

@gonzalocasas
Copy link
Contributor

@rajmohan747 would it be possible for you to send me a backup of your controller to reproduce the issue? thx!

@gonzalocasas
Copy link
Contributor

@gavanderhoorn yesterday we tested the driver on an ABB IRB 120 (not 1200!). I realize it is not the exact same robot, but both use the compact IRC5, so perhaps there's some connection beyond the model name.

And we did see an issue indeed, but it was not related to is_near. What we noticed is that the first point in the trajectory has a duration set to 10 seconds. And since the first point is rather close anyway, 10 seconds duration means the robot appears as not moving (even if it is, because we heard the breaks releasing).

Our test was as simple as it gets, MoveIt with all default configurations, abb driver up to date, abb_experimental for the support package of the ABB IRB120 and the following launch file:

<?xml version="1.0" ?>
<launch>
  <arg name="robot_ip" default="192.168.10.10" />

  <include file="$(find abb_irb120_moveit_config)/launch/planning_context.launch">
    <arg name="load_robot_description" value="true" />
  </include>

   <node pkg="tf" type="static_transform_publisher" name="gort" args="0.0 0.0 0.0 0 0 0 1 map base_link 10" />

  <include file="$(find abb_driver)/launch/robot_interface.launch" >
    <arg name="robot_ip" value="$(arg robot_ip)" />
  </include>

  <include file="$(find abb_irb120_moveit_config)/launch/move_group.launch" />

  <include file="$(find abb_irb120_moveit_config)/launch/moveit_rviz.launch">
    <arg name="config" value="true" />
    <arg name="debug" default="false" />
  </include>
</launch>

Could it be this the same problem that @rajmohan747 is seeing? And if so... @gavanderhoorn do you have any hints as to where the problem might be originating? Could it be that at some serialization level, a value that corresponds to some other field is spilling into the duration field and affecting the value that RAPID sees?

/cc @codeJRV

@gavanderhoorn
Copy link
Member

@gonzalocasas: thanks for reporting back.

I'm not entirely sure how reverting to an older version got things to work for @rajmohan747 in this case though.

Related / duplicates of what you report: #142 and ros-industrial/abb#146.

@gavanderhoorn gavanderhoorn transferred this issue from ros-industrial/abb_experimental Nov 16, 2018
@gavanderhoorn
Copy link
Member

Please see whether #155 fixes this.

@gavanderhoorn
Copy link
Member

I'm going to close this as I believe #155 fixes what @rajmohan747 described.

If that is not the case then please re-open and clarify.

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

3 participants