Ros-Industrial Error when connecting with Motoman Controller ERROR: Failed to convert SimpleMessage

614 views
Skip to first unread message

Ali Al-yacoub

unread,
Aug 13, 2015, 10:23:42 AM8/13/15
to swri-ros-pkg-dev
Hi,
I am trying to communicate with DX100 controller,
Robot: SDA10D
system: DS4.04.00A(US/DE)-14,  Parameter: 4.02 and model: SDA010D-Y1.

and I've got this error:
 
[ERROR] [1439475125.904528813]: Failed to parse position data from JointFeedbackMessage[ERROR] [1439475125.904542303]: Failed to convert SimpleMessage[ERROR] [1439475125.904567587]: Message callback for message type: 17, not executed[ERROR] [1439475125.929023464]: Failed to copy JointData.  Len (16) out of range (0 to 10)

It seems that the parameter names we got from the controller are not aligned with the PC side?

Shaun Edwards

unread,
Aug 13, 2015, 6:32:37 PM8/13/15
to swri-ros-pkg-dev
The hydro/indigo versions of the controller and ROS software are not compatible. That error typically occurs when the versions don't match. What versions are you using?
--
You received this message because you are subscribed to the Google Groups "swri-ros-pkg-dev" group.
To unsubscribe from this group and stop receiving emails from it, send an email to swri-ros-pkg-d...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Ali Al-yacoub

unread,
Aug 17, 2015, 10:54:34 AM8/17/15
to swri-ros-pkg-dev
Thank you Shaun,
Those errors disappeared when I launch ROS motoman with version0="false". But still I have this error:

"[ERROR] [1439475125.904567587]: Message callback for message type: 17,"


Shaun Edwards

unread,
Aug 18, 2015, 10:59:55 AM8/18/15
to swri-ros-pkg-dev
Is that the whole error message?  I don't recognize it.

Can you let me know what version ROS and motoman software (from source or debian? Indigo or Hydro?) you are using?  Maybe I can try to recreate the error here.

Zoss, Jeremy K.

unread,
Aug 18, 2015, 2:11:18 PM8/18/15
to swri-ros...@googlegroups.com

It looks to me like you’re still mixing software versions between the MotoPlus software installed on the controller and the ROS software you’re running.

 

The error message you’re seeing is generated by the MessageManager object when it receives an incoming message that has no corresponding MessageHandler defined for it (see here).  On 5/30/2014, v1.2.0 of the MotoPlus driver added the use of message type 17 to transfer current joint-state data from the robot to ROS, but no corresponding ROS message handlers were created.  On 8/22/2014, v1.2.4 of the MotoPlus driver moved this functionality to message type 2017, and the corresponding message-type support was added to the ROS driver.

 

Try using a current version of the ROS driver (> 8/22/2014) for both the MotoPlus and ROS sides, to make sure the message-type definitions are compatible with both sides of the communications interface.

 

Hope this helps,

  Jeremy Zoss

  Southwest Research Institute

Ali Al-yacoub

unread,
Aug 21, 2015, 1:14:38 PM8/21/15
to swri-ros-pkg-dev
Hi all,

Thank you for your help,

Now I'm using the updated version of MotoPlus and ROS(hydro);

I've modified the launch file:
_________________________________________________________________________________________________________________________
<launch>   
  
    <arg name="robot_ip" />
    <arg name="use_bswap" default="false" />
    <arg name="version0" default="false" />

    <!--rosparam command="load" file="$(find motoman_config)/?" /-->

    <rosparam command="load" file="$(find motoman_sda10f_support)/config/joint_names_sda10f.yaml"/>
    <rosparam command="load" file="$(find motoman_sda10f_support)/config/sda10f_motion_interface.yaml"/>
    <rosparam command="load" file="$(find motoman_sda10f_support)/config/sda10f_state_interface.yaml"/>



    <include file="$(find motoman_driver)/launch/robot_interface_streaming.launch">
        <arg name="robot_ip"   value="$(arg robot_ip)" />
        <arg name="use_bswap"  value="$(arg use_bswap)" />
        <arg name="version0"  value="$(arg version0)" />
    </include>
</launch>
_________________________________________________________________________________________________________________________

[FATAL] [1440175666.331378695]: ASSERTION FAILED
    file = /home/aliyacoub/ROS_tutorial/src/motoman-hydro-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp
    line = 320
    cond = all_joint_state.positions.size() == all_joint_names.size()

process[joint_trajectory_action-4]: started with pid [10133]
[joint_state-2] process has died [pid 10063, exit code -5, cmd /home/aliyacoub/ROS_tutorial/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/aliyacoub/.ros/log/594e79ae-4824-11e5-89dd-00e04c68796e/joint_state-2.log].
log file: /home/aliyacoub/.ros/log/594e79ae-4824-11e5-89dd-00e04c68796e/joint_state-2*.log


_____________________________________________________________________________________________________________________

I am not sure but it seems that there is a name conflict?

Topic list I've got seems to be all right however I non of them published anything

Topiclist:
____________________
/dynamic_feedback_states
/feedback_states
/joint_path_command
/joint_states
/joint_trajectory_action/cancel
/joint_trajectory_action/feedback
/joint_trajectory_action/goal
/joint_trajectory_action/result
/joint_trajectory_action/status
/robot_status
/rosout
/rosout_agg
/sda10f/sda10f_b1_controller/feedback_states
/sda10f/sda10f_b1_controller/joint_path_command
/sda10f/sda10f_b1_controller/joint_states
/sda10f/sda10f_b1_controller/joint_trajectory_action/cancel
/sda10f/sda10f_b1_controller/joint_trajectory_action/feedback
/sda10f/sda10f_b1_controller/joint_trajectory_action/goal
/sda10f/sda10f_b1_controller/joint_trajectory_action/result
/sda10f/sda10f_b1_controller/joint_trajectory_action/status
/sda10f/sda10f_b2_controller/feedback_states
/sda10f/sda10f_b2_controller/joint_path_command
/sda10f/sda10f_b2_controller/joint_states
/sda10f/sda10f_b2_controller/joint_trajectory_action/cancel
/sda10f/sda10f_b2_controller/joint_trajectory_action/feedback
/sda10f/sda10f_b2_controller/joint_trajectory_action/goal
/sda10f/sda10f_b2_controller/joint_trajectory_action/result
/sda10f/sda10f_b2_controller/joint_trajectory_action/status
/sda10f/sda10f_r1_controller/feedback_states
/sda10f/sda10f_r1_controller/joint_path_command
/sda10f/sda10f_r1_controller/joint_states
/sda10f/sda10f_r1_controller/joint_trajectory_action/cancel
/sda10f/sda10f_r1_controller/joint_trajectory_action/feedback
/sda10f/sda10f_r1_controller/joint_trajectory_action/goal
/sda10f/sda10f_r1_controller/joint_trajectory_action/result
/sda10f/sda10f_r1_controller/joint_trajectory_action/status
/sda10f/sda10f_r2_controller/feedback_states
/sda10f/sda10f_r2_controller/joint_path_command
/sda10f/sda10f_r2_controller/joint_states
/sda10f/sda10f_r2_controller/joint_trajectory_action/cancel
/sda10f/sda10f_r2_controller/joint_trajectory_action/feedback
/sda10f/sda10f_r2_controller/joint_trajectory_action/goal
/sda10f/sda10f_r2_controller/joint_trajectory_action/result
/sda10f/sda10f_r2_controller/joint_trajectory_action/status

___________________


Could you please advice me about this problem?

Best Regards
Ali


But when I run this l;aunch file I have the following errors

Shaun Edwards

unread,
Aug 21, 2015, 5:32:59 PM8/21/15
to swri-ros-pkg-dev
The joint names don't seem to match.  There could be an issue with your yaml config files.  Is it possible for you to share your motoman_sda10f_support package or at least your yaml files?

-Shaun

Ali Al-yacoub

unread,
Aug 24, 2015, 3:30:35 AM8/24/15
to swri-ros-pkg-dev

Hi Shaun,
please find the attached files
joint_names_sda10f.yaml
sda10f_motion_interface.yaml
sda10f_state_interface.yaml

Shaun Edwards

unread,
Aug 24, 2015, 9:42:49 AM8/24/15
to swri-ros-pkg-dev
Ali,

Are you working with the SDA10F or SDA10D?  Your prior emails indicated that is was the SDA10D, but these files are for the SDA10F, which is supported here: https://github.com/ros-industrial/motoman/tree/hydro-devel/motoman_sda10f_support

It also appears that your joint_names_sda10f.yaml file is missing "torso_joint_b2"...see the sda10a https://github.com/ros-industrial/motoman/blob/hydro-devel/motoman_sda10f_support/config/joint_names_sda10f.yaml

-Shaun
Message has been deleted

Ali Al-yacoub

unread,
Aug 24, 2015, 10:15:01 AM8/24/15
to swri-ros-pkg-dev

Shaun,

I am using SDA10D. I thought that the onley diiference between SDA10D and SDA10F is in the controller side  (big ends). So, the configuration files  will be the same. I am not sure if this is right. Also, I could not find any configration files for SDA10D.

Thanks
Ali

Shaun Edwards

unread,
Aug 24, 2015, 11:17:22 AM8/24/15
to swri-ros-pkg-dev
Ali...you are probably right. I remember this coming up in some previous discussions of the motoman naming convention.  Did my comment about the joint names yaml file fix your problem?

Ali Al-yacoub

unread,
Aug 24, 2015, 3:27:42 PM8/24/15
to swri-ros-pkg-dev
Shaun,
Not really. I still have the same problems.

Thanks
Ali

Ali Al-yacoub

unread,
Aug 25, 2015, 2:42:16 AM8/25/15
to swri-ros-pkg-dev
This is the message I've got:
[FATAL] [1440425180.706752176]: ASSERTION FAILED

    file = /home/aliyacoub/ROS_tutorial/src/motoman-hydro-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp
    line = 320
    cond = all_joint_state.positions.size() == all_joint_names.size()

[joint_state-2] process has died [pid 6286, exit code -5, cmd /home/aliyacoub/ROS_tutorial/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/aliyacoub/.ros/log/4a5801d0-4a69-11e5-aba4-00e04c68796e/joint_state-2.log].
log file: /home/aliyacoub/.ros/log/4a5801d0-4a69-11e5-aba4-00e04c68796e/joint_state-2*.log

Jonathan Meyer

unread,
Aug 28, 2015, 11:22:44 AM8/28/15
to swri-ros-pkg-dev
Hi Ali,

My name is Jonathan and I work with/for Shaun at SwRI. I'd like to attack this problem as systematically as I can, so please bear with me, even if you've done a particular step before.

So:
  1. Ensure that the robot controller is running the Indigo version of the native MotoPlus code and the Inform layer. See instructions: http://wiki.ros.org/motoman_driver/Tutorials/indigo/InstallServer
  2. Ensure you're in a catkin workspace and have cloned the latest version of the motoman driver from Github (https://github.com/ros-industrial/motoman).
  3. Checkout the indigo-devel branch.
  4. catkin-make your workspace.
  5. Navigate to the motoman_driver package.
  6. Open the motoman_driver/launch/robot_state_dx100.launch file.
  7. Set the version0 arg's value to false and save the file.
  8. Execute the robot state visualizer for your robot: roslaunch motoman_sda10f_support robot_state_visualize_sda10f.launch controller:=dx100 robot_ip:=xxx.xxx.xxx.xxx

A visualization of your robot should pop up. If it doesn't what errors do you see (in the terminal or in rviz)?

Thanks,
Jon

Ali Al-yacoub

unread,
Aug 28, 2015, 12:21:23 PM8/28/15
to swri-ros-pkg-dev
Hi Jonathan,

Thank you for your help
by the way I am using ROS-Hydro. I've applied the steps you mention earlier. But still, got the same error and the robot shown in the visualizer is not   correct.


_______________________________________________________________________
ERROR:
_____________________________________________________________________-_
aliyacoub@Yacoub:~/ROS_tutorial$ roslaunch motoman_sda10f_support robot_state_visualize_sda10f.launch controller:=dx100 robot_ip:=192.168.255.1
... logging to /home/aliyacoub/.ros/log/3d577712-4d9e-11e5-8989-00e04c68796e/roslaunch-Yacoub-30258.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
WARNING: disk usage in log directory [/home/aliyacoub/.ros/log] is over 1GB.
It's recommended that you use the 'rosclean' command.

started roslaunch server http://Yacoub:43445/

SUMMARY
========

PARAMETERS
 * /controller_joint_names
 * /robot_description
 * /robot_ip_address
 * /rosdistro
 * /rosversion
 * /version0

NODES
  /
    joint_state (motoman_driver/robot_state)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    rviz (rviz/rviz)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[joint_state-1]: started with pid [30279]
process[robot_state_publisher-2]: started with pid [30310]

_______________________________________________________________________
ERROR:
_____________________________________________________________________-_
[FATAL] [1440778278.596798035]: ASSERTION FAILED

    file = /home/aliyacoub/ROS_tutorial/src/motoman-hydro-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp
    line = 320
    cond = all_joint_state.positions.size() == all_joint_names.size()

process[rviz-3]: started with pid [30329]
[joint_state-1] process has died [pid 30279, exit code -5, cmd /home/aliyacoub/ROS_tutorial/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/aliyacoub/.ros/log/3d577712-4d9e-11e5-8989-00e04c68796e/joint_state-1.log].
log file: /home/aliyacoub/.ros/log/3d577712-4d9e-11e5-8989-00e04c68796e/joint_state-1*.log


_______________________________________________________________________
_____________________________________________________________________-_


Again Thank you for your help
Ali

Jonathan Meyer

unread,
Aug 28, 2015, 2:41:00 PM8/28/15
to swri-ros-pkg-dev
I sent you a private message, but I'm not sure that it got through. I'm bad with this interface atm.

If there is nothing proprietary in it, would you please zip up your workspace and send it to me privately at one of the following addresses: jmeye...@gmail.com or jonatha...@swri.org.

We'll get to the bottom of this.

Thanks,
Jon

Frantisek Durovsky

unread,
Aug 28, 2015, 2:59:42 PM8/28/15
to swri-ros-pkg-dev
Hi guys

Year ago I also spent quite a long time trying to get communication with Motoman dual arm robot running, in my case it was SDA10F with FS100 controller also with ROS Hydro. It took a while, required several steps but now it works quite well even with Indigo.

I ve noticed that you have problem to run motoman_sda10f_support launch files. But what happens if you try just basic motoman driver as in chap.3 of motoman tutorial?
http://wiki.ros.org/motoman_driver/Tutorials/Usage/#Usage

Do you also get this error? If not can you rostopic /joint_states? How many values do you see?
This information could help us a lot

Frantisek

Zoss, Jeremy K.

unread,
Sep 1, 2015, 8:06:48 PM9/1/15
to swri-ros...@googlegroups.com

Ali,

 

I’m sorry to jump in the middle, but I’ve been out on travel for a few weeks, and missed the discussion over the past few weeks.

 

I’m not very familiar with the dual-arm motoman driver, but a few things seem suspicious in looking through your code/config/errors:

 

  1) The list of parameters given at the start of the roslaunch console output includes “/controller_joint_names”, “/version0”, and “/robot_description”, but not “/topic_list” or “/topics_list” (from the sda10f_*_interface.yaml files you posted earlier).

                a) Are you sure that your updated launch file is actually getting called?

                b) Try echoing the value of “rosparam get /version0” to see if it has the expected value

 

  2) The error message you’ve given shows an issue in JointRelayHandler.  However, the MotoPlus driver typically sends JointFeedback messages, which should trigger the JointFeedbackRelayHandler.  The only ways I can see for this JointRelayHandler method to be called are:

                a) “version0” is actually set TRUE instead of FALSE (see here)

                b) something is wrong in the method overloading of JointFeedbackRelayHandler, causing it to call the base-class method instead

 

  3) As Shaun mentioned, I think you need to add an extra joint (‘torso_joint_b2’) to the end of your joint_names_sda10f.yaml file.  I don’t think this should affect operation when connected to a “live robot”, but it might be relevant when using the industrial_robot_simulator.

 

Please check the values on the parameter server once you’ve started your launch file, to make sure /topics_list is set to match your YAML file and /version0 is set to FALSE.

 

Hope this helps,

  Jeremy Zoss

  Robotics and Automation Engineering

  Southwest Research Institute

 

From: swri-ros...@googlegroups.com On Behalf Of Ali Al-yacoub
Sent: Friday, August 28, 2015 11:21 AM
To: swri-ros...@googlegroups.com
Subject: Re: [ROS-Industrial] Ros-Industrial Error when connecting with Motoman Controller ERROR: Failed to convert SimpleMessage

 

Hi Jonathan,

Message has been deleted

Ali Al-yacoub

unread,
Sep 24, 2015, 7:28:43 AM9/24/15
to swri-ros-pkg-dev
Dear All,
Thank you for you help. Due to a submission deadline I could not work on the robot for the last three weeks. Now, I am totally free for the robot.
As Jon suggested I've done the following
First, I know you're on Hydro (Ubuntu 12.04), but you can (I believe)
still compile/run indigo software. For this exercise, please:

1. Navigate to your workspace/src directory

2. git clone https://github.com/ros-industrial/industrial_core.git

3. cd industrial_core

4. git checkout indigo-devel

5. Now attached to this email is a modified version of the motoman
repo. Copy it into your workspace (changes are outlined below).

6. Cd to the top of your workspace and catkin_make

7.  roslaunch motoman_sda10f_support
robot_state_visualize_sda10f.
launch controller:=dx100
robot_ip:=xxx.xxx.xxx.xxx


I changed the launch files to default to version0 = false
and I added a load parameter for


<rosparam command="load" file="$(find
motoman_sda10f_support)/
config/sda10f_state_interface.yaml" />

to the robot_state_visualize launch file.

But still I have the same proble. The attached pic shows the error msg I've got

Please let me know if you have any suggestions

Regards
Ali
trial1.png

Frantisek Durovsky

unread,
Sep 24, 2015, 8:23:53 AM9/24/15
to swri-ros-pkg-dev


Ali I just did some tests on SDA10F and I confirm that even if everything else work fine when trying to run robot_state_visualize_sda10f.launch I get the same errors as you.

So what I did

First I tried robot_interface_streaming_sda10f.launch with arguments adopted to my setup only to check if driver works:

<?xml version="1.0"?>
<launch>
  <arg name="robot_ip" value="192.168.0.2"/>
  <arg name="version0" value="false"/>

  <!-- controller: Controller name (fs100 or dx100) -->
  <arg name="controller" value="fs100"/>

  <rosparam command="load" file="$(find motoman_sda10f_support)/config/sda10f_state_interface.yaml" />

  <include file="$(find motoman_driver)/launch/robot_interface_streaming_$(arg controller).launch">

    <arg name="robot_ip"   value="$(arg robot_ip)" />
    <arg name="version0"   value="$(arg version0)" />
  </include>
</launch>

Launch was without any errors and I was able to rostopic echo /joint_states where I got values for each planning group published separately

header:
  seq: 1034
  stamp:
    secs: 1443095444
    nsecs: 136978611
  frame_id: ''
name: ['arm_right_joint_1_s', 'arm_right_joint_2_l', 'arm_right_joint_3_e', 'arm_right_joint_4_u', 'arm_right_joint_5_r', 'arm_right_joint_6_b', 'arm_right_joint_7_t']
position: [-1.4530037641525269, -0.7121250629425049, 1.534162998199463, -1.8999186754226685, -0.7440110445022583, -1.3038532733917236, 1.3277356624603271]
velocity: []
effort: []
---
header:
  seq: 1035
  stamp:
    secs: 1443095444
    nsecs: 137106920
  frame_id: ''
name: ['arm_left_joint_1_s', 'arm_left_joint_2_l', 'arm_left_joint_3_e', 'arm_left_joint_4_u', 'arm_left_joint_5_r', 'arm_left_joint_6_b', 'arm_left_joint_7_t']
position: [-1.5699782371520996, 1.8100463151931763, 1.4399067163467407, -1.8099150657653809, 0.24991735816001892, -1.3199676275253296, -3.0078057534410618e-05]
velocity: []
effort: []
---
header:
  seq: 1036
  stamp:
    secs: 1443095444
    nsecs: 161986798
  frame_id: ''
name: ['torso_joint_b2']
position: [-6.817693065386266e-05]
velocity: []
effort: []
---
header:
  seq: 1037
  stamp:
    secs: 1443095444
    nsecs: 162110751
  frame_id: ''
name: ['torso_joint_b1']
position: [-6.817693065386266e-05]
velocity: []
effort: []

If you are able to get actual joint_states in such a format you are almost there because your interface works properly

Then in robot_state_visualize_sda10f.launch I replaced line 17 and 19 by working directives from robot_interface_streaming_sda10f.launch like this

<?xml version="1.0"?>

<launch>
  <arg name="robot_ip" value="192.168.0.2"/>
  <arg name="version0" value="false" />
  <arg name="controller" value="fs100" />

<!--   <rosparam command="load" file="$(find motoman_sda10f_support)/config/joint_names_sda10f.yaml" /> -->

  <rosparam command="load" file="$(find motoman_sda10f_support)/config/sda10f_state_interface.yaml" />

  <include file="$(find motoman_driver)/launch/robot_interface_streaming_$(arg controller).launch">

    <arg name="robot_ip"   value="$(arg robot_ip)" />
    <arg name="version0"   value="$(arg version0)" />
  </include>

  <node
        name="robot_state_publisher" 
        pkg="robot_state_publisher" 
        type="robot_state_publisher" />

  <include file="$(find motoman_sda10f_support)/launch/load_sda10f.launch" />

  <node 
    name="rviz"
    pkg="rviz" 
    type="rviz"
    args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" 
    required="true" />
   
</launch>

And finally I was able to visualize robot state

Try those steps with your setup and let us now what you get

Frantisek


screen_small.jpg

Ali Al-yacoub

unread,
Sep 24, 2015, 12:15:04 PM9/24/15
to swri-ros-pkg-dev

Frantisek Thank you for the tips. However, I still have exactly the same error.

I've installed the MotoPlus application in the controller side again and I've debug the code INIT_ROS, ROS_R! and ROS_R2.  I've noticed one thing  in the pic you attached, the parameter initialization list contains Robot_description but I do not have that  in my case.
 Shull I use URDF files to initialize robot description and where  ?



Screenshot from 2015-09-24 17:09:40.png

Frantisek Durovsky

unread,
Sep 24, 2015, 1:58:57 PM9/24/15
to swri-ros-pkg-dev

Yes exactly, controller_joint_names loaded on rosparam server in combination with robot_state_$(arg controller).launch were causing error you describe. When I replaced
line 17 in robot_state_visualize_sda10f.launch:

------------------------------------------------------------------------------------------------------------------------------------------------------------------

<rosparam command="load" file="$(find motoman_sda10f_support)/config/joint_names_sda10f.yaml" />
by

<rosparam command="load" file="$(find motoman_sda10f_support)/config/sda10f_state_interface.yaml" />
------------------------------------------------------------------------------------------------------------------------------------------------------------------

and

line 19-21
-----------------------------------------------------------------------------------------------------------------------------------------------------------------
<include file="$(find motoman_driver)/launch/robot_state_$(arg controller).launch">

        <arg name="robot_ip"   value="$(arg robot_ip)" />
</include>

by


<include file="$(find motoman_driver)/launch/robot_interface_streaming_$(arg controller).launch">
    <arg name="robot_ip"   value="$(arg robot_ip)" />
    <arg name="version0"   value="$(arg version0)" />
</include>

---------------------------------------------------------------------------------------------------------------------------------------------------------------
robot description was loaded on rosparam server instead of controller_joint_names and in combination with robot_interface_streaming_fs100.launch there was no error anymore.

If you tried my launch files and you still get error I suggest to contact Ted Miller from Yaskawa to discuss if your ds100 controller hardware and firmware version meets criteria for communication with ROS-Industrial drivers. In my case fs100 firmware update was necessary in order to get interface working.

Frantisek




Ali Al-yacoub

unread,
Sep 25, 2015, 11:44:33 AM9/25/15
to swri-ros-pkg-dev
Now the parameter initialized correctly. But still same error.

 **********************************************************************
***********************************************************************

aliyacoub@Yacoub:~/Moto_ros2$ roslaunch motoman_sda10f_support robot_state_visualize_sda10f.launch controller:=dx100 robot_ip:=192.168.255.1 version0:=false
... logging to /home/aliyacoub/.ros/log/645700c2-639b-11e5-a0c4-00e04c68796e/roslaunch-Yacoub-25790.log

Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
WARNING: disk usage in log directory [/home/aliyacoub/.ros/log] is over 1GB.
It's recommended that you use the 'rosclean' command.

started roslaunch server http://Yacoub:48187/

SUMMARY
========

PARAMETERS

 * /robot_description
 * /robot_ip_address
 * /rosdistro
 * /rosversion
 * /topics_list

 * /version0

NODES
  /
    joint_state (motoman_driver/robot_state)
    joint_trajectory_action (motoman_driver/motoman_driver_joint_trajectory_action)
    motion_streaming_interface (motoman_driver/motion_streaming_interface)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    rviz (rviz/rviz)

auto-starting new master
process[master]: started with pid [25807]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 645700c2-639b-11e5-a0c4-00e04c68796e
process[rosout-1]: started with pid [25820]
started core service [/rosout]
process[joint_state-2]: started with pid [25832]
process[motion_streaming_interface-3]: started with pid [25863]
[FATAL] [1443195476.651676339]: ASSERTION FAILED
    file = /home/aliyacoub/Moto_ros2/src/motoman-hydro-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp

    line = 320
    cond = all_joint_state.positions.size() == all_joint_names.size()

process[joint_trajectory_action-4]: started with pid [25904]
process[robot_state_publisher-5]: started with pid [25968]
[joint_state-2] process has died [pid 25832, exit code -5, cmd /home/aliyacoub/Moto_ros2/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/aliyacoub/.ros/log/645700c2-639b-11e5-a0c4-00e04c68796e/joint_state-2.log].
log file: /home/aliyacoub/.ros/log/645700c2-639b-11e5-a0c4-00e04c68796e/joint_state-2*.log
process[rviz-6]: started with pid [25986]
**************************************************************************************
**************************************************************************************


I've already contact Ted and I've upgraded the system before.
WP_20150925_001.jpg

Ali Al-yacoub

unread,
Oct 7, 2015, 10:30:25 AM10/7/15
to swri-ros-pkg-dev
Dear All,

I am using SDA10D Dual arm robot ("version0=0") with ROS-Hydro and DX100 controller ("bswap=false").  The controller system is upgraded and output files are installed in the controller.

CASE I:
  •  Run the launch file with version0=true (Single arm robot)
    •  roslaunch motoman_sda10f_support robot_interface_streaming_sda10f.launch robot_ip:=192.168.255.1 controller:=dx100 version0:=true
  • Result:
    • Message callback for message type: 2017
    • rostopic list:
      • /feedback_states
      • /joint_path_command
      • /joint_states
      • /joint_trajectory_action/cancel
      • /joint_trajectory_action/feedback
      • /joint_trajectory_action/goal
      • /joint_trajectory_action/result
      • /joint_trajectory_action/status
      • /robot_status
      • /rosout
      • /rosout_agg
    • rostopic echo /joint_state
      • ---
        header:
          seq: 15878
          stamp:
            secs: 1444225999
            nsecs: 193610019
          frame_id: ''
        name: ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6']
        position: [-2.8140366077423096, 0.0, 0.0, 0.0, 0.0, 0.0]
        velocity: []
        effort: []
        ---
        header:
          seq: 15879
          stamp:
            secs: 1444225999
            nsecs: 219502138
          frame_id: ''
        name: ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6']
        position: [3.0016252994537354, 1.2068167924880981, -1.5357121229171753, -0.22096917033195496, 3.133953094482422, 1.2318168878555298]
        velocity: []
        effort: []
        ---
        header:
          seq: 15880
          stamp:
            secs: 1444225999
            nsecs: 219613894
          frame_id: ''
        name: ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6']
        position: [-2.340684175491333, -0.6677588820457458, 1.5464651584625244, 2.1704916954040527, -1.4063869714736938, 0.4736355245113373]
        velocity: []
        effort: []
  • This means that robot is sending messages and it communicate correctly with ros. But, as expected the data length is not correct for single arm robot.
CASE II:
  • Run: roslaunch motoman_sda10f_support robot_interface_streaming_sda10f.launch robot_ip:=192.168.255.1 controller:=dx100 version0:=false
  • Result:
    • [FATAL] [1444226769.212200383]: ASSERTION FAILED
          file = /home/aliyacoub/MotomanROS_Hydro/src/motoman-hydro-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp

    •     line = 320
          cond = all_joint_state.positions.size() == all_joint_names.size()
    • rostopic list:
    • The all_joint_stat.position.size()=0
    • I've  added some debugging lines in the code. I've  noticed that two handlers are called, namelly: joint_feedback_relay_handler and joint_feedback_relay_Ex_handler. and it seems that the position is cleared some where between them
    • Could you please help me to identify the bug?
    • This is the result when I run the launch file with the debugging lines:

      •  * /robot_ip_address
         * /rosdistro
         * /rosversion
         * /topics_list
         * /version0

        NODES
          /
            joint_state (motoman_driver/robot_state)
            joint_trajectory_action (motoman_driver/motoman_driver_joint_trajectory_action)
            motion_streaming_interface (motoman_driver/motion_streaming_interface)

      • auto-starting new master
        process[master]: started with pid [24904]
        ROS_MASTER_URI=http://localhost:11311

        setting /run_id to 8eac64ec-6cfc-11e5-8b60-00e04c68796e
        process[rosout-1]: started with pid [24917]
        started core service [/rosout]
        process[joint_state-2]: started with pid [24929]
        [ERROR] [1444226769.160735476]: Version0= False, line 70
        [ERROR] [1444226769.160767472]: Default_port=50241
        [ERROR] [1444226769.160807129]: RobotStateInterface::init(SmplMsgConnection* connection)-->> Version0==false
        [ERROR] [1444226769.161725972]: RobotStateInterface::init(SmplMsgConnection* connection, robot_groups) Line 182
        [ERROR] [1444226769.165536961]: default_joint_handler_.init(connection_, robot_groups_) triggered
        [ERROR] [1444226769.165931934]: default_joint_feedback_handler_.init(connection_, robot_groups_) triggered
        [ERROR] [1444226769.167502195]: rtn is true
        [ERROR] [1444226769.167552256]: efault_joint_feedback_ex_handler_.init(connection_) triggered
        [ERROR] [1444226769.168065474]: default_robot_status_handler_.init(connection_) triggered
        [ERROR] [1444226769.168086993]: RobotStateInterface::init returns true, line 208
        process[motion_streaming_interface-3]: started with pid [24960]
        [ERROR] [1444226769.205910679]: Creat message function , line 75
        [ERROR] [1444226769.205960965]: message_length=132
        [ERROR] [1444226769.205972561]: Version== 0
        [ERROR] [1444226769.205983061]: Creat message function , line 90
        [ERROR] [1444226769.206007442]: LINE 181 joint_feedback_relay_handler!!!
        [ERROR] [1444226769.206021318]: line 184 joint_feedback_relay_handler value: = 10!!
        [ERROR] [1444226769.206030950]: JointFeedbackRelayHandler::JointDataToVector, Line 169
        [ERROR] [1444226769.206063703]: joint_stat_length=0
        [ERROR] [1444226769.211539984]: Creat message function , line 75
        [ERROR] [1444226769.211625874]: message_length=132
        [ERROR] [1444226769.211640183]: Version== 0
        [ERROR] [1444226769.211651822]: Creat message function , line 90
        [ERROR] [1444226769.211679743]: LINE 181 joint_feedback_relay_handler!!!
        [ERROR] [1444226769.211696211]: line 184 joint_feedback_relay_handler value: = 10!!
        [ERROR] [1444226769.211708934]: JointFeedbackRelayHandler::JointDataToVector, Line 169
        [ERROR] [1444226769.211735033]: joint_stat_length=0
        [ERROR] [1444226769.211816073]: Creat message function , line 75
        [ERROR] [1444226769.211834053]: message_length=132
        [ERROR] [1444226769.211844604]: Version== 0
        [ERROR] [1444226769.211852278]: Creat message function , line 90
        [ERROR] [1444226769.211863712]: LINE 181 joint_feedback_relay_handler!!!
        [ERROR] [1444226769.211873245]: line 184 joint_feedback_relay_handler value: = 10!!
        [ERROR] [1444226769.211880216]: JointFeedbackRelayHandler::JointDataToVector, Line 169
        [ERROR] [1444226769.211891301]: joint_stat_length=0
        [ERROR] [1444226769.211937795]: Creat message function EX, line 89
        [ERROR] [1444226769.212119829]: Creat message function EX, line 117
        [ERROR] [1444226769.212139566]: JointFeedbackExRelayHandler::convert_message, line 168
        [ERROR] [1444226769.212150383]: line 170 value: 0
        [ERROR] [1444226769.212159581]: Message length in byte=132
        [ERROR] [1444226769.212178877]: all_joint_state.position.size()=0
        [ERROR] [1444226769.212188007]: all_joint_names.size()=7
        [FATAL] [1444226769.212200383]: ASSERTION FAILED
            file = /home/aliyacoub/MotomanROS_Hydro/src/motoman-hydro-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp
            line = 321

      •     cond = all_joint_state.positions.size() == all_joint_names.size()

      • [ERROR] [1444226769.218327594]: MotomanMotionCtrl initialized correctly line 55 motion_ctrl
        [ERROR] [1444226769.218349743]: MotomanMotionCtrl initialized correctly line 55 motion_ctrl
        [ERROR] [1444226769.218361523]: MotomanMotionCtrl initialized correctly line 55 motion_ctrl
        [ERROR] [1444226769.218372063]: MotomanMotionCtrl initialized correctly line 55 motion_ctrl
        [ERROR] [1444226769.218381694]: MotomanMotionCtrl initialized correctly line 55 motion_ctrl
        process[joint_trajectory_action-4]: started with pid [24999]
        [joint_state-2] process has died [pid 24929, exit code -5, cmd /home/aliyacoub/MotomanROS_Hydro/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/aliyacoub/.ros/log/8eac64ec-6cfc-11e5-8b60-00e04c68796e/joint_state-2.log].
        log file: /home/aliyacoub/.ros/log/8eac64ec-6cfc-11e5-8b60-00e04c68796e/joint_state-2*.log


    Regards
    Ali
     
    Reply all
    Reply to author
    Forward
    0 new messages