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

Revision history [back]

click to hide/show revision 1
initial version

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 the 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. 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

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 the 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. 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)

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 the 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. 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)

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 the 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)