ros-industrial / motoman

ROS-Industrial Motoman support (http://wiki.ros.org/motoman)

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

ROS Client and Server differ on what messages should be communicated to each other. GP7 launch file

rsrisamang-miso opened this issue · comments

Tried to launch a launch file that defines the topic_list parameter to resolve the missing topic_list error. Launch file:

<!--
  Manipulator specific version of 'robot_interface_streaming.launch'.

  Defaults provided for gp7:
   - 6 joints

  Usage:
    robot_interface_streaming_gp7.launch robot_ip:=<value> controller:=<yrc1000>
-->
<launch>
        <arg name="robot_ip" />

  <!-- controller: Controller name (yrc1000) -->
  <arg name="controller"/>

        <rosparam command="load" file="$(find motoman_gp7_support)/config/joint_names_gp7.yaml" />
        <rosparam command="load" file="$(find motoman_gp7_support)/config/gp7_motion_interface.yaml" />

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

where gp7_motion_interface.yaml is defined as:

topic_list:
    - name: gp7_yrc1000_controller
      ns: gp7
      group: 0
      joints: ['joint_1_s', 'joint_2_l', 'joint_3_u', 'joint_4_r', 'joint_5_b', 'joint_6_t']

Received the error from the ROS Server below:

process[motion_streaming_interface-3]: started with pid [225656]
process[io_relay-4]: started with pid [225679]
[joint_state-2] process has died [pid 225651, exit code -5, cmd /root/workspace/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/root/.ros/log/749845b4-61ef-11ec-b911-0242ac120005/joint_state-2.log].
log file: /root/.ros/log/749845b4-61ef-11ec-b911-0242ac120005/joint_state-2*.log
process[joint_trajectory_action-5]: started with pid [225720]
**[ERROR] [1640044164.085939981 /joint_trajectory_action] [/tmp/binarydeb/ros-kinetic-roscpp-1.12.17/src/libros/publication.cpp:Publication::validateHeader:502]: Client [/motion_streaming_interface] wants topic /joint_path_command to have datatype/md5sum [motoman_msgs/DynamicJointTrajectory/81bfbf2d02070fdef3a528bd72b49257], but our version has [trajectory_msgs/JointTrajectory/65b4f94a94d1ed67169da35a02f33d3f]. Dropping connection.**

Is this a configuration issue or must I make changes in the /motion_streaming_interface node to use trajectory_msgs/JointTrajectory type instead of motoman_msgs/DynamicJointTrajectory?

I checked and I'm running the latest from motoman github, with yrc1000u controller (micro)

Do you actually have a multi-group system?

The ERROR isn't really an error in the case of a single group setup.

For your setup specifically: if you don't have a multi-group system, you don't need the topic_list parameter. The .launch files in the motoman_gp7_support package should work for you.

This seems like it was discussed in #235 and #242, which refer to #113 (which discusses the ERROR which shouldn't be an ERROR).


Edit:

must I make changes in the /motion_streaming_interface node to use trajectory_msgs/JointTrajectory type instead of motoman_msgs/DynamicJointTrajectory?

no. In general, do not assume source-code level changes would be necessary to support a particular setup, unless you've been instructed to make them by a maintainer/developer here.

My GP 7 has an external motor attached to the yrc1000u that we will use to slide the base of the arm along a linear rail.

depending on how this is setup, that could be a multi-group system, yes. And if @ted-miller says it's multi-group, it most likely is.

If you have one, then I would expect both groups to be mentioned in the topic_list configuration you show, but there's only a single group there.

Could you share your complete configuration (ie: including the rail), or perhaps a configuration which is similar to your setup (but not the real packages, if that's sensitive)?

if it is indeed a multi group system follow this: http://wiki.ros.org/motoman_driver/Tutorials/Creating%20a%20Dual-Arm%20System this has the topic list defined. You also will need to do include the correct file in your ROS job that runs on the controller, in your case, I believe it should be: https://github.com/ros-industrial/motoman/tree/kinetic-devel/motoman_driver/Inform/DX200%2C%20FS100%2C%20YRC1000/single_arm_with_base_axis

It is an R1+S1 system. We have discussed the Creating a Dual Arm System link. But, we're investigating another issue first. It seems that the INIT_ROS is not starting with the robot_enable service. I have provided my windows-message-emulator utility to validate that the robot is properly configured (eliminate any variables from the ROS configuration).

I'm not entirely sure MotoROS-related problems can cause the error shown.

It would be good -- in parallel to any diagnostics you are performing -- for @rsrisamang-miso to share the exact files (s)he is using (including any customisations), and the exact sequence of commands.

And just to point out something (perhaps) obvious: ROS Kinetic has been EOL for quite some time now. If that version is being used in order to be able to run the packages in this repository: that would not be necessary.

The current launch file I have is fairly straight forward:

<launch>
    <arg name="robot_ip" default="10.191.0.40" />
    <rosparam command="load" file="$(find motoman_gp7_support)/config/joint_names_gp7.yaml" />
    <rosparam command="load" file="$(find motoman_gp7_support)/config/gp7_motion_interface.yaml" />

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

The gp7_motion_interface.yaml file looks like this:

topic_list:
    - name: gp7_yrc1000u
      ns: gp7
      group: 0
      joints: ['joint_1_s', 'joint_2_l', 'joint_3_u', 'joint_4_r', 'joint_5_b', 'joint_6_t']
    - name: gp7_yrc1000u
      ns: gp7
      group: 1
      joints: ['joint_1_rail']

The joint_names_gp7.yaml file looks like this:

controller_joint_names: ['joint_1_s', 'joint_2_l', 'joint_3_u', 'joint_4_r', 'joint_5_b', 'joint_6_t']

Should I probably add the 'joint_1_rail' joint name at the end of the controller_joint_names list?

I need to run the launch files again in the morning to get the output from using the main launch file described above.

I think you might want to have a different name for your controller for the second one, like this:
image

You see they have a controller called: sda10f_r1_controller for just the arm and another controller for the base axis: sda10f_b1_controller

Thanks Akash. You're right. I updated my topic_list by changing the name. That helped clear up the following error messages I was getting:

[ERROR] [1640192890.751970922 /motion_streaming_interface] [/tmp/binarydeb/ros-kinetic-roscpp-1.12.17/src/libros/service_manager.cpp:ServiceManager::advertiseService:137]: Tried to advertise a service that is already advertised in this node [/gp7/gp7_yrc1000u/stop_motion]
[ERROR] [1640192890.751996204 /motion_streaming_interface] [/tmp/binarydeb/ros-kinetic-roscpp-1.12.17/src/libros/service_manager.cpp:ServiceManager::advertiseService:137]: Tried to advertise a service that is already advertised in this node [/gp7/gp7_yrc1000u/joint_path_command]

I no longer receive the messages above when starting the launch file.

I still get this Error message though:

[ERROR] [1640193800.196059570 /joint_trajectory_action] [/tmp/binarydeb/ros-kinetic-roscpp-1.12.17/src/libros/publication.cpp:Publication::validateHeader:502]: Client [/motion_streaming_interface] wants topic /joint_path_command to have datatype/md5sum [motoman_msgs/DynamicJointTrajectory/81bfbf2d02070fdef3a528bd72b49257], but our version has [trajectory_msgs/JointTrajectory/65b4f94a94d1ed67169da35a02f33d3f]. Dropping connection.

Despite the 'Dropping connection' error, I'm able to still receive valid joint_states frames from the rostopic.

@rsrisamang-miso: could you please post the exact sequence of commands and the output you get (as I asked before)?

Make sure to append --screen to the roslaunch invocation.

Without more information we'll have to keep guessing, like @akashjinandra is doing.


Edit: and could you please use Github code blocks when posting console output? I've edited your previous posts already, please keep it in mind for future comments.

@gavanderhoorn , apologies for not posting this sooner. Thank you for also the tips on how to post code using Github code blocks. Hopefully this is in the correct format:

Filename: miso_yaskawa.launch (motoman_driver/launch)

<launch>
    <arg name="robot_ip" default="10.191.0.40" />
    <rosparam command="load" file="$(find motoman_gp7_support)/config/joint_names_gp7.yaml" />
    <rosparam command="load" file="$(find motoman_gp7_support)/config/gp7_motion_interface.yaml" />

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

Filename : joint_names_gp7.yaml (motoman_gp7_support/config)

controller_joint_names: ['joint_1_s', 'joint_2_l', 'joint_3_u', 'joint_4_r', 'joint_5_b', 'joint_6_t']

Filename : gp7_motion_interface.yaml (motoman_gp7_support/config)

topic_list:
    - name: gp7_yrc1000u
      ns: gp7
      group: 0
      joints: ['joint_1_s', 'joint_2_l', 'joint_3_u', 'joint_4_r', 'joint_5_b', 'joint_6_t']
    - name: gp7_yrc1000u_rail
      ns: gp7
      group: 1
      joints: ['joint_1_rail']

Command sent is:

roslaunch motoman_driver miso_yaskawa.launch
# roslaunch motoman_driver miso_yaskawa.launch 
... logging to /root/.ros/log/282412ee-6361-11ec-8183-0242ac120005/roslaunch-flippy-234719.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://flippy:40685/

SUMMARY
========

PARAMETERS
 * /controller_joint_names: ['joint_1_s', 'jo...
 * /robot_ip_address: 10.191.0.40
 * /rosdistro: kinetic
 * /rosversion: 10.2.0
 * /topic_list: [{'joints': ['joi...

NODES
  /
    io_relay (motoman_driver/io_relay)
    joint_state (motoman_driver/robot_state)
    joint_trajectory_action (industrial_robot_client/joint_trajectory_action)
    motion_streaming_interface (motoman_driver/motion_streaming_interface)

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

setting /run_id to 282412ee-6361-11ec-8183-0242ac120005
process[rosout-1]: started with pid [234799]
started core service [/rosout]
process[joint_state-2]: started with pid [234810]
process[motion_streaming_interface-3]: started with pid [234817]
process[io_relay-4]: started with pid [234842]
process[joint_trajectory_action-5]: started with pid [234897]
[ERROR] [1640202949.338446697 /joint_trajectory_action] [/tmp/binarydeb/ros-kinetic-roscpp-1.12.17/src/libros/publication.cpp:Publication::validateHeader:502]: Client [/motion_streaming_interface] wants topic /joint_path_command to have datatype/md5sum [motoman_msgs/DynamicJointTrajectory/81bfbf2d02070fdef3a528bd72b49257], but our version has [trajectory_msgs/JointTrajectory/65b4f94a94d1ed67169da35a02f33d3f]. Dropping connection.

Please let me know if you'd like any other information. Is there a better way to set the controller_joint_names? We have 7 but in the file I just posted, there's only 6 so I'm sure I have something to fix there. I saw in the other projects the .xacro file was used instead?

I was able to bypass the issues I had earlier by insuring that all the joints on my robot were intialized to Home position. I was missing the 7th joint and therefore the /robot_enable command was not working. It now is returning True for success state when sending the /robot_enable command.

When I send the rosservice list command, I get the following output:

# rosservice list
/gp7/gp7_yrc1000u/joint_path_command
/gp7/gp7_yrc1000u/stop_motion
/gp7/gp7_yrc1000u_rail/joint_path_command
/gp7/gp7_yrc1000u_rail/stop_motion
/io_relay/get_loggers
/io_relay/set_logger_level
/joint_path_command
/joint_state/get_loggers
/joint_state/set_logger_level
/joint_trajectory_action/get_loggers
/joint_trajectory_action/set_logger_level
/motion_streaming_interface/get_loggers
/motion_streaming_interface/set_logger_level
/read_single_io
/robot_disable
/robot_enable
/rosout/get_loggers
/rosout/set_logger_level
/rostopic_235548_1640211125205/get_loggers
/rostopic_235548_1640211125205/set_logger_level
/stop_motion
/write_single_io

I tried sending a rosservice call to /gp7/gp7_yrc1000u/joint_path_command and the output I get is:

# rosservice call /gp7/gp7_yrc1000u/joint_path_command "trajectory:
  header:
    seq: 0
    stamp:
      secs: 0
      nsecs: 0
    frame_id: ''
  joint_names:
  - ''
  points:
  - num_groups: 0
    groups:
    - group_number: 0
      num_joints: 0
      valid_fields: 0
      positions: [0.2, 0, 0, 0, 0, 0]
      velocities: [0.1, 0, 0, 0, 0, 0]
      accelerations: [0]
      effort: [0]
      time_from_start: {secs: 2, nsecs: 0}" 
code: 
  val: 1

Please run the following command instead of what you've shown:

roslaunch --screen motoman_driver miso_yaskawa.launch

I don't believe you did that, as I would expect different output in that case.

And there's no use in trying anything with the driver in this state, as it doesn't initialise correctly.

I'm also unsure why you'd want to use the joint_path_command service. The preference would be to use the FollowJointTrajectoryAction server.

PS: are you running everything as root?

PPS: the rosservice invocation you show would most likely not result in (correct) motion. All list fields for each traj pt should be of equal length, but ignoring that: you've set valid_fields to 0, which means: no fields contain valid information.

But again: please only use the FollowJointTrajectoryAction server for now. If you're just starting out, any other interface will only confuse.

PPPS: I'd recommend to treat motoman_driver as a read-only package, and to not add anything to it, or change anything there. Maintenance will be much easier if you create your own package(s).

Sorry for misunderstanding your --screen option! Here's the output for the following command:

I am running everything as root in my shell. Also, I updated the joint_names_gp7.yaml file to include the additional external motor:

File:

controller_joint_names: ['joint_1_s', 'joint_2_l', 'joint_3_u', 'joint_4_r', 'joint_5_b', 'joint_6_t', 'joint_1_rail']

Command:

roslaunch --screen motoman_driver miso_yaskawa.launch

Output:

roslaunch --screen motoman_driver miso_yaskawa.launch 
... logging to /root/.ros/log/301acf0c-63f1-11ec-a62d-0242ac120005/roslaunch-flippy-237142.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://flippy:40381/

SUMMARY
========

PARAMETERS
 * /controller_joint_names: ['joint_1_s', 'jo...
 * /robot_ip_address: 10.191.0.40
 * /rosdistro: kinetic
 * /rosversion: 10.2.0
 * /topic_list: [{'joints': ['joi...

NODES
  /
    io_relay (motoman_driver/io_relay)
    joint_state (motoman_driver/robot_state)
    joint_trajectory_action (industrial_robot_client/joint_trajectory_action)
    motion_streaming_interface (motoman_driver/motion_streaming_interface)

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

setting /run_id to 301acf0c-63f1-11ec-a62d-0242ac120005
process[rosout-1]: started with pid [237222]
started core service [/rosout]
process[joint_state-2]: started with pid [237233]
[ INFO] [1640264809.819306644 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::add:217]: Added message handler for message type: 0
[ INFO] [1640264809.820033882 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/robot_state_interface.cpp:robot_state_interface::RobotStateInterface::init:78]: Robot state connecting to IP address: '10.191.0.40:50241'
[ INFO] [1640264809.820660901 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:55]: Loading topic list
[ INFO] [1640264809.820674439 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:56]: Found 2 topics
[ INFO] [1640264809.820684861 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:62]: Topic(state_value): [group:0,joints:{joint_1_s,joint_2_l,joint_3_u,joint_4_r,joint_5_b,joint_6_t},name:gp7_yrc1000u,ns:gp7]
[ INFO] [1640264809.820731522 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:62]: Topic(state_value): [group:1,joints:{joint_1_rail},name:gp7_yrc1000u_rail,ns:gp7]
[ INFO] [1640264809.820750063 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:69]: Loading group: [group:0,joints:{joint_1_s,joint_2_l,joint_3_u,joint_4_r,joint_5_b,joint_6_t},name:gp7_yrc1000u,ns:gp7]
[ INFO] [1640264809.820846987 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:69]: Loading group: [group:1,joints:{joint_1_rail},name:gp7_yrc1000u_rail,ns:gp7]
[ INFO] [1640264809.820875982 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:114]: Loaded 2 groups
[ INFO] [1640264809.820911465 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/robot_state_interface.cpp:robot_state_interface::RobotStateInterface::init:108]:  Initializing robot state 2 groups
[ INFO] [1640264809.820925035 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::init:80]: Initializing message manager with default comms fault handler
[ INFO] [1640264809.820932378 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/simple_comms_fault_handler.cpp:simple_comms_fault_handler::SimpleCommsFaultHandler::init:62]: Default communications fault handler successfully initialized
[ INFO] [1640264809.820941157 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::init:102]: Initializing message manager
[ INFO] [1640264809.820950363 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::add:217]: Added message handler for message type: 1
[ INFO] [1640264809.822514275 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::add:217]: Added message handler for message type: 10
[ INFO] [1640264809.822890348 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::add:217]: Added message handler for message type: 15
[ INFO] [1640264809.822907812 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/joint_feedback_ex_relay_handler.cpp:joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::init:54]: Creating joint_feedback_ex_relay_handler with 2 groups
[ INFO] [1640264809.824122822 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::add:217]: Added message handler for message type: 2017
[ INFO] [1640264809.825006116 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/socket/tcp_client.cpp:tcp_client::TcpClient::makeConnect:120]: Connected to server
[ INFO] [1640264809.825018669 /joint_state] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/robot_state_interface.cpp:robot_state_interface::RobotStateInterface::init:150]: Successfully initialized robot state interface
[ INFO] [1640264809.825027235 /joint_state] [/root/workspace/src/industrial_core/simple_message/src/message_manager.cpp:message_manager::MessageManager::spin:186]: Entering message manager spin loop
process[motion_streaming_interface-3]: started with pid [237240]
[ INFO] [1640264809.889509384 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/joint_trajectory_interface.cpp:joint_trajectory_interface::JointTrajectoryInterface::init:78]: Joint Trajectory Interface connecting to IP address: '10.191.0.40:50240'
[ INFO] [1640264809.890080846 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:55]: Loading topic list
[ INFO] [1640264809.890098943 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:56]: Found 2 topics
[ INFO] [1640264809.890112450 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:62]: Topic(state_value): [group:0,joints:{joint_1_s,joint_2_l,joint_3_u,joint_4_r,joint_5_b,joint_6_t},name:gp7_yrc1000u,ns:gp7]
[ INFO] [1640264809.890131560 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:62]: Topic(state_value): [group:1,joints:{joint_1_rail},name:gp7_yrc1000u_rail,ns:gp7]
[ INFO] [1640264809.890142331 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:69]: Loading group: [group:0,joints:{joint_1_s,joint_2_l,joint_3_u,joint_4_r,joint_5_b,joint_6_t},name:gp7_yrc1000u,ns:gp7]
[ INFO] [1640264809.890221489 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:69]: Loading group: [group:1,joints:{joint_1_rail},name:gp7_yrc1000u_rail,ns:gp7]
[ INFO] [1640264809.890236483 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/motoman_utils.cpp:motoman_utils::getJointGroups:114]: Loaded 2 groups
[ INFO] [1640264809.890254975 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/joint_trajectory_streamer.cpp:joint_trajectory_streamer::MotomanJointTrajectoryStreamer::init:74]: MotomanJointTrajectoryStreamer: init
[ INFO] [1640264809.890264772 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/joint_trajectory_streamer.cpp:joint_trajectory_streamer::JointTrajectoryStreamer::init:50]: JointTrajectoryStreamer: init
[ INFO] [1640264809.890759095 /motion_streaming_interface] [/root/workspace/src/industrial_core/simple_message/src/socket/tcp_client.cpp:tcp_client::TcpClient::makeConnect:120]: Connected to server
[ WARN] [1640264809.891161501 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/joint_trajectory_interface.cpp:joint_trajectory_interface::JointTrajectoryInterface::init:145]: Unable to read velocity limits from 'robot_description' param.  Velocity validation disabled.
[ INFO] [1640264809.900662260 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/industrial_robot_client/joint_trajectory_streamer.cpp:joint_trajectory_streamer::JointTrajectoryStreamer::init:59]: Unlocking mutex
[ INFO] [1640264809.900686440 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/joint_trajectory_streamer.cpp:joint_trajectory_streamer::MotomanJointTrajectoryStreamer::streamingThread:405]: Starting Motoman joint trajectory streamer thread
[ INFO] [1640264809.905786408 /motion_streaming_interface] [/root/workspace/src/motoman/motoman_driver/src/joint_trajectory_streamer.cpp:joint_trajectory_streamer::MotomanJointTrajectoryStreamer::streamingThread:413]: Connecting to robot motion server
[ WARN] [1640264809.905799121 /motion_streaming_interface] [/root/workspace/src/industrial_core/simple_message/src/socket/tcp_client.cpp:tcp_client::TcpClient::makeConnect:133]: Tried to connect when socket already in connected state
process[io_relay-4]: started with pid [237265]
[ WARN] [1640264809.955423474 /io_relay] [/root/workspace/src/motoman/motoman_driver/src/io_relay.cpp:io_relay::MotomanIORelay::init:58]: Failed to get '~port' parameter: using default (50242)
[ INFO] [1640264809.956550707 /io_relay] [/root/workspace/src/industrial_core/simple_message/src/socket/tcp_client.cpp:tcp_client::TcpClient::makeConnect:120]: Connected to server
process[joint_trajectory_action-5]: started with pid [237320]
[ INFO] [1640264810.051698717 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getListParam:64]: Adding joint_1_s to list parameter
[ INFO] [1640264810.051728025 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getListParam:64]: Adding joint_2_l to list parameter
[ INFO] [1640264810.051734236 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getListParam:64]: Adding joint_3_u to list parameter
[ INFO] [1640264810.051739625 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getListParam:64]: Adding joint_4_r to list parameter
[ INFO] [1640264810.051744137 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getListParam:64]: Adding joint_5_b to list parameter
[ INFO] [1640264810.051751043 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getListParam:64]: Adding joint_6_t to list parameter
[ INFO] [1640264810.051755732 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getListParam:64]: Adding joint_1_rail to list parameter
[ INFO] [1640264810.051775460 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_utils/src/param_utils.cpp:param::getJointNames:104]: Found user-specified joint names in 'controller_joint_names': [joint_1_s, joint_2_l, joint_3_u, joint_4_r, joint_5_b, joint_6_t, joint_1_rail]
[ INFO] [1640264810.051794896 /joint_trajectory_action] [/root/workspace/src/industrial_core/industrial_robot_client/src/joint_trajectory_action.cpp:joint_trajectory_action::JointTrajectoryAction::JointTrajectoryAction:60]: Filtered joint names to 7 joints
[ERROR] [1640264810.337055576 /joint_trajectory_action] [/tmp/binarydeb/ros-kinetic-roscpp-1.12.17/src/libros/publication.cpp:Publication::validateHeader:502]: Client [/motion_streaming_interface] wants topic /joint_path_command to have datatype/md5sum [motoman_msgs/DynamicJointTrajectory/81bfbf2d02070fdef3a528bd72b49257], but our version has [trajectory_msgs/JointTrajectory/65b4f94a94d1ed67169da35a02f33d3f]. Dropping connection.

Also, I'm not quite sure where I would find the JointTrajectoryAction. Should that be part of the rosservice list of services? When I do a rosservice list, I get the following options:

# rosservice list
/gp7/gp7_yrc1000u/joint_path_command
/gp7/gp7_yrc1000u/stop_motion
/gp7/gp7_yrc1000u_rail/joint_path_command
/gp7/gp7_yrc1000u_rail/stop_motion
/io_relay/get_loggers
/io_relay/set_logger_level
/joint_path_command
/joint_state/get_loggers
/joint_state/set_logger_level
/joint_trajectory_action/get_loggers
/joint_trajectory_action/set_logger_level
/motion_streaming_interface/get_loggers
/motion_streaming_interface/set_logger_level
/read_single_io
/robot_disable
/robot_enable
/rosout/get_loggers
/rosout/set_logger_level
/stop_motion
/write_single_io

I think I found the issue. The version0 value is set to 'true' in the launch file, which assumes older client version. I set it to false and now I don't get the error.

Ok. It seems you're using an incorrect .launch file.

You should be include-ing the $(find motoman_driver)/launch/robot_multigroup_interface_streaming_$(arg controller).launch file.

The non-multigroup file will try to use the regular joint_trajectory_action node, which uses different messages to communicate with the driver.


Edit:

I think I found the issue. The version0 value is set to 'true' in the launch file, which assumes older client version. I set it to false and now I don't get the error.

don't set version0 manually.

Just include the correct .launch file.


Edit 2:

Also, I'm not quite sure where I would find the JointTrajectoryAction.

It's a regular actionlib server.

Should that be part of the rosservice list of services?

No, action servers are not services, so they don't show up in the output of rosservice list.

See the linked wiki page for information on actionlib. Refer to this for an example script which creates a client, populates a short trajectory and then submits it as a goal.

If you're just starting out, I strongly suggest you use the action interface.


Edit 3:

I am running everything as root in my shell.

you may already be aware, but running ROS nodes as root is really not recommended.

ROS 1 has no security and the attack surface is huge.

There are very few situations in which running a ROS node with super-user privileges would be required.

Thank you for your help @gavanderhoorn, and @akashjinandra too! Definitely learned something here. I appreciate your advice and comments on this issue.

As it appears we've diagnosed the cause of the error reported in the OP, I'm going to close this issue.