Kinovarobotics / ros_kortex

ROS packages for KINOVA® KORTEX™ robotic arms
Other
167 stars 162 forks source link

Trying to install a FT sensor on the GEN3 arm #312

Open MahrukhAzh opened 11 months ago

MahrukhAzh commented 11 months ago

Hello,

As a beginner in ROS, i am trying to implement a FT sensor at the end effector of the GEN 3 ARM. My initial problem is that gazebo does not recognize the 'FT_sensor' joint (error: [FATAL] [1701011286.835621614]: gazebo_ros_ft_sensor plugin error: jointName: FT_sensor does not exist) as it is mounted on fixed joint (see code below). I tried multiple times to see how the 'FT_sensor'fixed joint could be recognized in the .sdf that gazebo is taking it but no chance.

Here is my code below:

(gen3_macro.xacro description file)

<?xml version="1.0"?>

<robot name="gen3_arm" xmlns:xacro="http://ros.org/wiki/xacro">
(...)

    <link name="${prefix}end_effector_link" />
<joint
  name="${prefix}end_effector"
      type="fixed">
      <origin xyz="0 0 -0.0615250000000001" rpy="3.14159265358979 1.09937075168372E-32 0" />
      <parent
        link="${prefix}bracelet_link" />
  <child
    link="${prefix}end_effector_link" />
      <axis
        xyz="0 0 0" />
    </joint>

    <link name="FT_sensor_link"/>
    <joint name="FT_sensor" type="fixed">
      <origin xyz="0 0.05639 -0.00305" rpy="3.14159265358979 3.14159265358979 0" />
      <parent link="${prefix}end_effector_link" />
      <child link="FT_sensor_link"/>
    </joint>

    <gazebo reference='FT_sensor'>
      <disableFixedJointLumping>true</disableFixedJointLumping>
      <preserveFixedJoint>true</preserveFixedJoint>
    </gazebo>

    <gazebo>
      <plugin name="Force_Torque_sensor" filename="libgazebo_ros_ft_sensor.so">
        <updateRate>100.0</updateRate>
        <topicName>ft_sensor_topic</topicName>
        <jointName>FT_sensor</jointName>
      </plugin>
    </gazebo>

    <xacro:if value="${vision}">
  <link name="${prefix}camera_link" />
      <joint name="${prefix}camera_module" type="fixed">
    <origin xyz="0 0.05639 -0.00305" rpy="3.14159265358979 3.14159265358979 0" />
    <parent link="${prefix}end_effector_link" />
        <child  link="${prefix}camera_link" />
      </joint>

      <link name="${prefix}camera_depth_frame" />
  <joint name="${prefix}depth_module" type="fixed">
        <origin xyz="0.0275 0.066 -0.00305" rpy="3.14159265358979 3.14159265358979 0" />
        <parent link="${prefix}end_effector_link" />
    <child  link="${prefix}camera_depth_frame" />
      </joint>

      <link name="${prefix}camera_color_frame" />
  <joint name="${prefix}color_module" type="fixed">
        <origin xyz="0 0.05639 -0.00305" rpy="3.14159265358979 3.14159265358979 0" />
        <parent link="${prefix}end_effector_link" />
    <child  link="${prefix}camera_color_frame" />
      </joint>
    </xacro:if>

  </xacro:macro>
</robot>

Also, i noticed that the end effector joint does not appear also as joint in the gazebo simulation. Is that normal? Or am I missing an information to activate it? Any help would be welcomed. Thank you for your time!

aalmrad commented 4 weeks ago

Hello,

Apologies for the late reply. We are recently trying to actively tackle the github issues on our repositories. Gazebo normally ignores the fixed joints and this explain why you cannot see the end effector joint in simulation and it seems to me that setting the disableFixedJointLumping to true is not doing its job for the FT_sensor joint. Try to change the type of the type of the FT_sensor joint to something else not fixed like revolute and set the upper and lower limits to 0 and see if that solves the problem.

Best, Abed