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

How to use staubli_val3_driver/ industrial_robot_simulator with industrial_robot_client and Moveit

asked 2021-06-02 05:10:45 -0500

bkaiser gravatar image

updated 2021-06-02 07:13:52 -0500

Hello,

we have a Staubli tx2_40 industrial robot with a CS8 controller and want to control it using ros. I created the xacro/urdf description, a moveit_config and a _gazebo package.

I use ros melodic on ubuntu 18.04.

Using the val3 driver i can connect to the CS8 controller and read the joint positions. Rviz visualizes the robot state. Following this tutorial (https://industrial-training-master.re...) I created the staubli_tx2_40_planning_execution.launch. When launching this file I get the error that the action client is not connected.

... I read about this problems in other questions. However I was not abl eto fix the rpoblem from that. Using gazebo as robot simulation works. In this configuration I am able to use moveit to plan trajectories and move the simulated robot.

The problem occurs when using indusrtial_robot_simulator or the val3 driver with the industrial_robot_client. This is the launch file:

<launch>
  <!-- The planning and execution components of MoveIt! configured to run -->
  <!-- using the ROS-Industrial interface. -->

  <!-- Non-standard joint names:
       - Create a file [robot_moveit_config]/config/joint_names.yaml
           controller_joint_names: [joint_1, joint_2, ... joint_N]
       - Update with joint names for your robot (in order expected by rbt controller)
       - and uncomment the following line: -->
  <rosparam command="load" file="$(find staubli_tx2_40_support)/config/joint_names.yaml"/>

  <!-- the "sim" argument controls whether we connect to a Simulated or Real robot -->
  <!--  - if sim=false, a robot_ip argument is required -->
  <arg name="sim" default="true" />
  <arg name="robot_ip" unless="$(arg sim)" />
  <arg name="use_industrial_robot_simulator" default="false"/>

  <!-- load the robot_description parameter before launching ROS-I nodes -->
  <include file="$(find staubli_tx2_40_moveit_config)/launch/planning_context.launch" >
   <arg name="load_robot_description" value="true" />
  </include>

  <!-- run the robot simulator and action interface nodes -->
  <group if="$(arg sim)">

    <group unless="$(arg use_industrial_robot_simulator)">
      <include file="$(find staubli_tx2_40_gazebo)/launch/staubli_tx2_40.launch" />
      <remap from="/follow_joint_trajectory" to="/arm_controller/follow_joint_trajectory"/>
    </group>

    <group if="$(arg use_industrial_robot_simulator)">
      <include file="$(find industrial_robot_simulator)/launch/robot_interface_simulator.launch" />
      <!-- publish the robot state (tf transforms) -->
      <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
    </group>
  </group>

  <!-- run the "real robot" interface nodes -->
  <!--   - this typically includes: robot_state, motion_interface, and joint_trajectory_action nodes -->
  <!--   - replace these calls with appropriate robot-specific calls or launch files -->
  <group unless="$(arg sim)">
    <remap from="follow_joint_trajectory" to="joint_trajectory_action"/>
    <include file="$(find staubli_val3_driver)/launch/robot_interface_streaming.launch" >
      <arg name="robot_ip" value="$(arg robot_ip)"/>
    </include>
  </group>

  <include file="$(find staubli_tx2_40_moveit_config)/launch/move_group.launch">
    <arg name="publish_monitored_planning_scene" value="true" />
  </include>

 <!-- Run Rviz and load the default config to see the state of the move_group node -->
  <include file="$(find staubli_tx2_40_moveit_config)/launch/moveit_rviz.launch">
    <arg name="rviz_config" value="$(find staubli_tx2_40_moveit_config)/launch/moveit.rviz"/>
  </include>

</launch>

This ist the output produced:

process[rosout-1]: started with pid [7059]
started core service [/rosout]
process[industrial_robot_simulator-2]: started with pid [7067]
process[joint_trajectory_action-3]: started with pid [7068]
process[robot_state_publisher-4]: started with pid [7069]
process[move_group-5]: started ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2021-06-02 05:39:44 -0500

gvdhoorn gravatar image

updated 2021-06-02 07:21:18 -0500

How to get Staubli Val3 Driver to work with industrial_robot_simulator/ industrial_robot_client

at face value, this question doesn't really make sense. The industrial_robot_simulator is a Python ROS node which does not interact with real hw. So it cannot do anything with staubli_val3_driver.

The staubli_val3_driver)/launch/robot_interface_streaming.launch you already found starts all the required parts:

  1. the robot_state node, which publishes JointState messages
  2. the motion_streaming_interface node, which relays JointTrajectorys
  3. the joint_trajectory_action node, which exposes the FollowJointTrajectory action server

The industrial_robot_simulator combines all of those nodes in one single script, and pretends it's a real driver -- with the same ROS API (topics, services, actions).

MoveIt talks to the joint_trajectory_action node; it's essentially a FollowJointTrajectory client, if you configure it as such. That's what currently not working in your setup. Likely because the configuration on MoveIt's side is incorrect.

The ros_controllers.yaml file is a bit of a mess (not your fault). It's really unfortunate it mixes ros_control based controller and hardware interface configuration with "regular" controller interfaces in MoveIt. It makes it really difficult to diagnose these kinds of problems, if you don't already know what's going wrong.

staubli_val3_driver is not a ros_control based driver, so you cannot spawn controllers in it, nor is any of the ros_control or hardware_interface configuration used with it.

Your ros_controllers.yaml file tells MoveIt it should expect the FollowJointTrajectory server on arm_controller/follow_joint_trajectory, but the driver does not start the server there. It starts it on /follow_joint_trajectory. You'll either have to remap from arm_controller/follow_joint_trajectory to /follow_joint_trajectory -- as you already do for the staubli_tx2_40_gazebo)/launch/staubli_tx2_40.launch file -- or update the controller_list entry in your ros_controllers.yaml file to look like this (from fanuc_cr7ia_moveit_config/config/controllers.yaml, which uses the exact same ROS API):

controller_list:
  - name: ""
    action_ns: joint_trajectory_action
    type: FollowJointTrajectory
    joints: [...]

Some additional comments:

  • Staubli joints aren't named joint_aN (with N a natural number), but joint_N (with N a natural number) in robot support packages (look at the .xacros in staubli_tx2_60_support fi)
  • it's uncommon to mix real driver, industrial_robot_simulator and Gazebo usage in a single moveit_planning_execution.launch file
  • it's uncommon to repeat the robot variant name in the name of the moveit_planning_execution.launch file: it's already hosted by a package with the variant name in it, so there's no need to repeat it again (ie: staubli_tx2_40_moveit_config contains moveit_planning_execution.launch)
edit flag offensive delete link more

Comments

Thank you very much for the quick reply. I will try to adopt the addressed changes and implement the nameing conventions. In addition, I will edit the title of the question.

bkaiser gravatar image bkaiser  ( 2021-06-02 06:19:00 -0500 )edit

And a PR (or two) adding the staubli_tx2_40_support and related packages to ros-industrial/staubli_experimental would also be very much appreciated of course :)

gvdhoorn gravatar image gvdhoorn  ( 2021-06-02 06:20:33 -0500 )edit

Once everything is working I will gladly contribute it.

bkaiser gravatar image bkaiser  ( 2021-06-02 07:15:23 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-06-02 05:10:45 -0500

Seen: 503 times

Last updated: Jun 02 '21