Kinovarobotics / kinova-ros

ROS packages for Jaco2 and Mico robotic arms
BSD 3-Clause "New" or "Revised" License
363 stars 318 forks source link

How to bringup two kinova arms using ethernet connection? #437

Closed aodongdong closed 5 months ago

aodongdong commented 5 months ago

Hello,

I use two kinova arms in ROS. One is left arm with the ip 192.168.5.10, the other is right arm with the ip 192.168.1.31. They are in the different local area network. We can bringup both arms as long as we can ping them.

However, using two USB-to-Ethernet ports to connect to the upper computer is usually unstable (one usually is not connected) when the robotic arm is powered on. Hence, i use the Network switch to make two arms in the same local area network. (The ip was changed to 192.168.1.29 for left arm).

My local machine ip is 192.168.1.30. Then i use the following launch file to bringup:

<launch>
  <arg name="kinova_robotType" default="j2s6s300" />
  <arg name="left_robotName" default="left_arm"/>
  <arg name="right_robotName" default="right_arm"/>
        <arg name="kinova_robotSerial" default="not_set" />
        <arg name="use_jaco_v1_fingers" default="false" />
        <arg name="feedback_publish_rate" default="0.1" />

  <!-- If the node handles multiple robots uncomment this and configure /config/multiple_robots.yaml" -->
    <rosparam file="$(find kinova_bringup)/launch/config/multiple_robots.yaml" command="load" />

  <node name="$(arg left_robotName)_driver" pkg="kinova_driver" type="kinova_arm_driver" output="screen" cwd="node" args="$(arg kinova_robotType)" respawn="true">
    <rosparam file="$(find kinova_bringup)/launch/config/left_robot_parameters.yaml" command="load" />
    <param name="serial_number" value="PJ00900006521429L" />
    <param name="robot_name" value="$(arg left_robotName)" />
    <param name="robot_type" value="$(arg kinova_robotType)" />
    <param name="use_jaco_v1_fingers" value="$(arg use_jaco_v1_fingers)" />
    <param name="status_interval_seconds" value="$(arg feedback_publish_rate)" />
    <remap from="/left_arm_driver/out/joint_state" to="/joint_states" />
  </node>

  <node name="$(arg right_robotName)_driver" pkg="kinova_driver" type="kinova_arm_driver" output="screen" cwd="node" args="$(arg kinova_robotType)" respawn="true">
    <rosparam file="$(find kinova_bringup)/launch/config/right_robot_parameters.yaml" command="load" />
    <param name="serial_number" value="PJ00900006521429R" />
    <param name="robot_name" value="$(arg right_robotName)" />
    <param name="robot_type" value="$(arg kinova_robotType)" />
    <param name="use_jaco_v1_fingers" value="$(arg use_jaco_v1_fingers)" />
    <param name="status_interval_seconds" value="$(arg feedback_publish_rate)" />
    <remap from="/right_arm_driver/out/joint_state" to="/joint_states" />
  </node>

</launch>

left_robot_parameters.yaml is:

# Set this parameter to use a specific arm on your system    --> 
serial_number: PJ00900006521429L

# Joint speed limit for joints 1, 2, 3
jointSpeedLimitParameter1: 30

# Joint speed limit for joints 4, 5, 6
jointSpeedLimitParameter2: 30

# payload: [COM COMx COMy COMz]
# payload: [0.09, 0.03, 0.03, -0.14]

# gravityvector: [x y z]
gravityvector: [0, 9.81, 0]

#connection_type: USB #ethernet
connection_type: Ethernet

# Ethernet connection parameters
ethernet: {
  local_machine_IP: 192.168.1.30,
  subnet_mask: 255.255.255.0,
  local_cmd_port: 25000,
  local_broadcast_port: 25025
}

torque_parameters: {
      publish_torque_with_gravity_compensation: true,
      use_estimated_COM_parameters: false,
    # if torque min/max sepecified, all min/max values need to be specified
    #  torque_min: [80, 80, 80, 80, 80, 80, 80],
    #  torque_max: [90, 90, 90, 90, 90, 90, 90],
    # Decides velocity threshold at which robot switches torque to position control (between 0 and 1)
    # safety_factor: 1,
    # COM parameters
    # order [m1,m2,...,m7,x1,x2,...,x7,y1,y2,...y7,z1,z2,...z7]
    # com_parameters: [0,0,0,0,0,0,0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0]
}

right_robot_parameters.yaml is:

# Set this parameter to use a specific arm on your system    --> 
serial_number: PJ00900006521429R

# Joint speed limit for joints 1, 2, 3
jointSpeedLimitParameter1: 30

# Joint speed limit for joints 4, 5, 6
jointSpeedLimitParameter2: 30

# payload: [COM COMx COMy COMz]
#payload: [0, 0, 0, 0]

# gravityvector: [x y z]
gravityvector: [0, 9.81, 0]

#connection_type: USB #ethernet 
connection_type: Ethernet #ethernet

# Ethernet connection parameters
ethernet: {
  local_machine_IP: 192.168.1.30,
  subnet_mask: 255.255.255.0,
  local_cmd_port: 25015,
  local_broadcast_port: 25025
}
#Torque control parameters
#Do not change these parameters unless you want to change torque control behavior
torque_parameters: {
      publish_torque_with_gravity_compensation: true,
      use_estimated_COM_parameters: false,
    # if torque min/max sepecified, all min/max values need to be specified
    #  torque_min: [80, 80, 80, 80, 80, 80, 80],
    #  torque_max: [90, 90, 90, 90, 90, 90, 90],
    # Decides velocity threshold at which robot switches torque to position control (between 0 and 1)
    # safety_factor: 1,
    # COM parameters
    # order [m1,m2,...,m7,x1,x2,...,x7,y1,y2,...y7,z1,z2,...z7]
    # com_parameters: [0,0,0,0,0,0,0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0, 0,0,0,0,0,0,0]
}

multiple_robots.yaml is:

kinova_number_of_robots: 2
kinova_robots:
  - serial: PJ00900006521429L
    type: j2s6s300
    name: left_arm
  - serial: PJ00900006521429R
    type: j2s6s300
    name: right_arm

However, when two arms are in the same local area network, the error occurs:

[right_arm_driver-2] process has died [pid 12382, exit code -11, cmd /home/bulldog/catkin_ws/devel/lib/kinova_driver/kinova_arm_driver j2s6s300 /right_arm_driver/out/joint_state:=/joint_states __name:=right_arm_driver __log:=/home/bulldog/.ros/log/c2a4361e-f0c7-11ee-b8d6-49f53fd20961/right_arm_driver-2.log].

log file: /home/bulldog/.ros/log/c2a4361e-f0c7-11ee-b8d6-49f53fd20961/right_arm_driver-2*.log

[right_arm_driver-2] restarting process

process[right_arm_driver-2]: started with pid [12389]

[ INFO] [1712048695.797221591]: kinova_robotType is j2s6s300.

[ INFO] [1712048695.797916412]: kinova_robotName is right_arm.

[ INFO] [1712048695.799406094]: Initializing Kinova Ethernet API (header version: 50300, library version: 5.2.0)

[ERROR] [1712048695.799499033]: KinovaCommException: Could not initialize Kinova API (return code: 1010)

It seems that two arms can not be bringup in the same time in the same local area network.

Are there any suggestions to solve it?

smoya23 commented 5 months ago

Hi @aodongdong ,

By default, the Kinova Ethernet API assumes the default IP address for the robot as 192.168.100.11 https://github.com/Kinovarobotics/kinova-ros/blob/noetic-devel/kinova_driver/src/kinova_comm.cpp#L88. Seeing as you modified the addresses of your robots, this is probably why the Kinova API is unable to initialize. One easy way to get around this with your current setup would be to add an additional parameter to each one of your (left/right)_robot_parameters.yaml files such as :

ethernet: {
  local_machine_IP: 192.168.1.30,
  subnet_mask: 255.255.255.0,
  local_cmd_port: 25000,
  local_broadcast_port: 25025,
  robot_IP: <your_robot_ip>
}

and then fetch it in the kinova_comm.cpp file :

    //Set ethernet parameters
    EthernetCommConfig ethernet_settings;
    std::string local_IP,subnet_mask,robot_IP;
    int local_cmd_port,local_bcast_port;
    node_handle.getParam("ethernet/local_machine_IP", local_IP);
    node_handle.getParam("ethernet/robot_IP", robot_IP);
    node_handle.getParam("ethernet/subnet_mask", subnet_mask);
    node_handle.getParam("ethernet/local_cmd_port", local_cmd_port);
    node_handle.getParam("ethernet/local_broadcast_port", local_bcast_port);
    ethernet_settings.localCmdport = local_cmd_port;
    ethernet_settings.localBcastPort = local_bcast_port;
    ethernet_settings.localIpAddress = inet_addr(local_IP.c_str());
    ethernet_settings.subnetMask = inet_addr(subnet_mask.c_str());
    ethernet_settings.rxTimeOutInMs = 1000;
    ethernet_settings.robotIpAddress = inet_addr(robot_IP.c_str());
    ethernet_settings.robotPort = 55000;

You will need to rebuild the ROS workspace after doing these changes. Also, make sure that all of the ip addresses are under the same subnet mask. I have not tested this yet since I do not currently have access to an arm but it shouldn't break anything. Let me know if this works for you, don't hesitate if you get any other errors!

Best, Santiago

aodongdong commented 5 months ago

Hello, @smoya23

Thank you for your suggestion! Unfortunately, it doesn't work after i modified these parameters&codes according to your suggestion.

Specifically, I have tried two approaches.

  1. I set left arm ip to 192.168.100.44, and right arm to 192.168.100.45. My local machine ip is 192.168.100.30. I checked for the connection by ping, then i use the launch file to bringup, with .yaml files modified. It doesn't work with the same error as described above.
  2. According to your suggestion, i added robot_ip and modified kinova_comm.cpp file. Now, the .yaml is
    ethernet: {
    local_machine_IP: 192.168.100.30,
    subnet_mask: 255.255.255.0,
    local_cmd_port: 25015,
    local_broadcast_port: 25025,
    robot_IP: 192.168.100.44
    }

    for left arm, and

    ethernet: {
    local_machine_IP: 192.168.100.30,
    subnet_mask: 255.255.255.0,
    local_cmd_port: 25015,
    local_broadcast_port: 25025,
    robot_IP: 192.168.100.45
    }

    for right arm. see the settings as follows: 1 2

Additionally, i changed launch file to

<launch>
  <arg name="kinova_robotType" default="j2s6s300" />
  <arg name="left_robotName" default="left_arm"/>
  <arg name="right_robotName" default="right_arm"/>
  <arg name="kinova_robotSerial" default="not_set" />
  <arg name="use_jaco_v1_fingers" default="false" />
  <arg name="feedback_publish_rate" default="0.01" />

  <!-- If the node handles multiple robots uncomment this and configure /config/multiple_robots.yaml" -->
    <rosparam file="$(find kinova_bringup)/launch/config/multiple_robots_test.yaml" command="load" />

  <node name="$(arg right_robotName)_driver" pkg="kinova_driver" type="kinova_arm_driver" output="screen" cwd="node" args="$(arg kinova_robotType)" respawn="true">
    <rosparam file="$(find kinova_bringup)/launch/config/right_kinova.yaml" command="load" />
    <param name="serial_number" value="PJ00900006521429R" />   
    <param name="robot_name" value="$(arg right_robotName)" />   
    <param name="robot_type" value="$(arg kinova_robotType)" />   
    <param name="use_jaco_v1_fingers" value="$(arg use_jaco_v1_fingers)" />   
    <param name="status_interval_seconds" value="$(arg feedback_publish_rate)" />
    <remap from="/right_arm_driver/out/joint_state" to="/joint_states" />
  </node>

  <node name="$(arg left_robotName)_driver" pkg="kinova_driver" type="kinova_arm_driver" output="screen" cwd="node" args="$(arg kinova_robotType)" respawn="true">
    <rosparam file="$(find kinova_bringup)/launch/config/left_kinova.yaml" command="load" />
    <param name="serial_number" value="PJ00900006521429L" />   
    <param name="robot_name" value="$(arg left_robotName)" />   
    <param name="robot_type" value="$(arg kinova_robotType)" />   
    <param name="use_jaco_v1_fingers" value="$(arg use_jaco_v1_fingers)" />   
    <param name="status_interval_seconds" value="$(arg feedback_publish_rate)" />
    <remap from="/left_arm_driver/out/joint_state" to="/joint_states" />
  </node>

</launch>

(which will launch right arm node first) the error comes: image

Note that we can bringup either of the two through ethernet. When one of them is brought up, we can find 2 devices was found by the upper computer. Subnet mask is set to 255.255.255.0 for both arms.

smoya23 commented 5 months ago

Hi @aodongdong,

Sorry to hear it did not work! One thing I did not mention but should be done also, is to change the port numbers for each arm driver. So in either one of your left or right arm .yaml file, change the values for local_cmd_port and local_broadcast_port so that they differ from the other arm's config. Also, from your screenshots, I see that the left arm's driver is unable to launch, are you having the same issue with the right arm or is the right arm driver launching correctly ?

aodongdong commented 5 months ago

Thanks for your kind suggestion @smoya23. The problem has been solved after setting different port numbers for each arm driver. Both arms can be launched at the same time through ethernet.

Specifically, I changed local_cmd_port and local_broadcast_port, and i have added robotport param in .yaml so that it can be fetched in the kinova_comm.cpp.

(PS: The screenshots showcase two arms can not be launched concurrently.)

smoya23 commented 5 months ago

@aodongdong Awesome, great to hear that you were able to solve the problem! Don't hesitate to open a new issue if you encounter any other problems.