Joint not found while trying controlling robotiq_2finger_gripper
Hello,
I am new to ROS and trying to control the robotiq2fingergripper which I have attached to a very simple robot arm I made. The robot consists of 2 spherical and one revolute joint with the gripper at the very end. To attach the gripper, I just added the URDF lines of the gripper to the end of my URDF file and attached the last link to the gripperbasejoint. This is my URDF file
<?xml version="1.0"?>
<!-- <xacro:include filename="$(find robot)/urdf/my_robot.gazebo" /> -->
<!-- <xacro:include filename="$(find robot)/urdf/materials.xacro" /> -->
<!-- <robot name="pendulum_robot"> -->
<link name="world">
</link>
<joint name="base_joint" type="fixed">
<parent link="world"/>
<child link="body_link"/>
<axis xyz="0.0 0.0 0.0"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<!-- First Link -->
<link name="body_link">
<visual>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 1.0"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 1.0"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.08417" ixy="0.0" ixz="0.0" iyy="0.08417" iyz="0.0" izz="0.001666667"/>
</inertial>
</link>
<!-- Shoulder Joint -->
<joint name="shoulder_y" type="revolute">
<parent link="body_link"/>
<child link="dummy_link_1"/>
<axis xyz="0 1 0" />
<origin xyz="0.0 0 1.05" rpy="0 0 0"/>
<limit effort="500" velocity="2.0" lower="-3.14" upper="3.14"/>
<!-- <dynamics damping="0.2"/> -->
</joint>
<link name="dummy_link_1">
<inertial>
<mass value="0.025" />
<inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
</inertial>
</link>
<joint name="shoulder_z" type="revolute">
<parent link="dummy_link_1"/>
<child link="dummy_link_2"/>
<axis xyz="0 0 1" />
<!-- <dynamics damping="0.2"/> -->
<limit effort="500" velocity="2.0" lower="-3.14" upper="3.14"/>
</joint>
<link name="dummy_link_2">
<inertial>
<mass value="0.025" />
<inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
</inertial>
</link>
<joint name="shoulder_x" type="revolute">
<parent link="dummy_link_2"/>
<child link="bicep_link"/>
<axis xyz="1 0 0" />
<!-- <dynamics damping="0.2"/> -->
<limit effort="500" velocity="2.0" lower="-3.14" upper="3.14"/>
</joint>
<!-- Bicep Link-->
<link name="bicep_link">
<!-- <pose>0 0 0 0 0 0</pose> -->
<visual>
<origin xyz="0 0 0.275" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.5"/>
</geometry>
</visual>
<!-- <collision>
<origin xyz="0 0 0.275" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.5"/>
</geometry>
</collision> -->
<inertial>
<origin xyz="0 0 0.275" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.010833" ixy="0.0" ixz="0.0" iyy="0.010833" iyz="0.0" izz="0.0008333"/>
</inertial>
</link>
<joint name="elbow" type="revolute">
<parent link="bicep_link"/>
<child link="forearm_link"/>
<axis xyz="1 0 0" />
<origin xyz="0 0 0.55" rpy="0 0 0"/>
<!-- <dynamics damping="0.2"/> -->
<limit effort="500" velocity="2.0" lower="-1.0" upper="3.14"/>
</joint>
<!-- Forearm Link-->
<link name="forearm_link">
<!-- <pose>0 0 0 0 0 0</pose> -->
<visual>
<origin xyz="0 0 0.275" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.5"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.275" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.5"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0.275" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.010833" ixy="0.0" ixz="0.0" iyy="0.010833" iyz="0.0" izz="0.0008333"/>
</inertial>
</link>
<!-- Wrist Joint -->
<joint name="wrist_y" type="revolute">
<parent link="forearm_link"/>
<child link="dummy_link_3"/>
<axis xyz="0 1 0" />
<origin xyz="0.0 0 0.55" rpy="0 0 0"/>
<!-- <dynamics damping="0.2"/> -->
<limit effort="500" velocity="2.0" lower="-3.14" upper="3.14"/>
</joint>
<link name="dummy_link_3">
<inertial>
<mass value="0.025" />
<inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
</inertial>
</link>
<joint name="wrist_x" type="revolute">
<parent link="dummy_link_3"/>
<!-- <child link="hand"/> -->
<child link="dummy_link_4"/>
<axis xyz="1 0 0" />
<!-- <dynamics damping="0.2"/> -->
<limit effort="500" velocity="2.0" lower="-3.14" upper="3.14"/>
</joint>
<link name="dummy_link_4">
<inertial>
<mass value="0.025" />
<inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
</inertial>
</link>
<joint name="wrist_z" type="revolute">
<parent link="dummy_link_4"/>
<child link="hand"/>
<axis xyz="0 0 1" />
<!-- <dynamics damping="0.2"/> -->
<limit effort="500" velocity="2.0" lower="-3.14" upper="3.14"/>
</joint>
<link name="hand">
<visual>
<origin xyz="0 0 0.06" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0.06" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.0008333" ixy="0.0" ixz="0.0" iyy="0.0008333" iyz="0.0" izz="0.0008333"/>
</inertial>
</link>
<gazebo reference="body_link"> <!-- reference to a existing "link" -->
<!-- NOTE: use Gazebo/DepthMap to take color from mesh (.dae only) -->
<material>Gazebo/GreenGlow</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>True</selfCollide>
</gazebo>
<gazebo reference="bicep_link"> <!-- reference to a existing "link" -->
<!-- NOTE: use Gazebo/DepthMap to take color from mesh (.dae only) -->
<material>Gazebo/TurquoiseGlow</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>True</selfCollide>
</gazebo>
<gazebo reference="forearm_link"> <!-- reference to a existing "link" -->
<!-- NOTE: use Gazebo/DepthMap to take color from mesh (.dae only) -->
<material>Gazebo/RedGlow</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>True</selfCollide>
</gazebo>
<gazebo reference="hand"> <!-- reference to a existing "link" -->
<!-- NOTE: use Gazebo/DepthMap to take color from mesh (.dae only) -->
<material>Gazebo/YellowGlow</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>True</selfCollide>
</gazebo>
<joint name="gripper_base_joint" type="fixed">
<parent link="hand"/>
<child link="robotiq_arg2f_base_link"/>
<origin rpy="0.0 0.0 1.57" xyz="0.0 0.0 0.1"/>
</joint>
<link name="robotiq_arg2f_base_link">
<inertial>
<origin rpy="0 0 0" xyz="8.625E-08 -4.6583E-06 0.03145"/>
<mass value="0.22652"/>
<inertia ixx="0.00020005" ixy="-4.2442E-10" ixz="-2.9069E-10" iyy="0.00017832" iyz="-3.4402E-08" izz="0.00013478"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<!-- The DAE file doesn't show well in Gazebo so we're using the STL instead -->
<!-- <mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_base_link.dae" scale="0.001 0.001 0.001"/> -->
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_base_link.stl"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_base_link.stl"/>
</geometry>
</collision>
</link>
<gazebo reference="robotiq_arg2f_base_link">
<material>Gazebo/Black</material>
</gazebo>
<link name="left_outer_knuckle">
<inertial>
<origin rpy="0 0 0" xyz="-0.000200000000003065 0.0199435877845359 0.0292245259211331"/>
<mass value="0.00853198276973456"/>
<inertia ixx="2.89328108496468E-06" ixy="-1.57935047237397E-19" ixz="-1.93980378593255E-19" iyy="1.86719750325683E-06" iyz="-1.21858577871576E-06" izz="1.21905238907251E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_outer_finger">
<inertial>
<origin rpy="0 0 0" xyz="0.00030115855001899 0.0373907951953854 -0.0208027427000385"/>
<mass value="0.022614240507152"/>
<inertia ixx="1.52518312458174E-05" ixy="9.76583423954399E-10" ixz="-5.43838577022588E-10" iyy="6.17694243867776E-06" iyz="6.78636130740228E-06" izz="1.16494917907219E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_inner_finger">
<inertial>
<origin rpy="0 0 0" xyz="0.000299999999999317 0.0160078233491243 -0.0136945669206257"/>
<mass value="0.0104003125914103"/>
<inertia ixx="2.71909453810972E-06" ixy="1.35402465472579E-21" ixz="-7.1817349065269E-22" iyy="7.69100314106116E-07" iyz="6.74715432769696E-07" izz="2.30315190420171E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_inner_finger_pad">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.0 0.0 1"/>
</material>
</collision>
</link>
<link name="left_inner_knuckle">
<inertial>
<origin rpy="0 0 0" xyz="0.000123011831763771 0.0507850843201817 0.00103968640075166"/>
<mass value="0.0271177346495152"/>
<inertia ixx="2.61910379223783E-05" ixy="-2.43616858946494E-07" ixz="-6.37789906117123E-09" iyy="2.8270243746167E-06" iyz="-5.37200748039765E-07" izz="2.83695868220296E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_outer_knuckle">
<inertial>
<origin rpy="0 0 0" xyz="-0.000200000000003065 0.0199435877845359 0.0292245259211331"/>
<mass value="0.00853198276973456"/>
<inertia ixx="2.89328108496468E-06" ixy="-1.57935047237397E-19" ixz="-1.93980378593255E-19" iyy="1.86719750325683E-06" iyz="-1.21858577871576E-06" izz="1.21905238907251E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_outer_finger">
<inertial>
<origin rpy="0 0 0" xyz="0.00030115855001899 0.0373907951953854 -0.0208027427000385"/>
<mass value="0.022614240507152"/>
<inertia ixx="1.52518312458174E-05" ixy="9.76583423954399E-10" ixz="-5.43838577022588E-10" iyy="6.17694243867776E-06" iyz="6.78636130740228E-06" izz="1.16494917907219E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_inner_finger">
<inertial>
<origin rpy="0 0 0" xyz="0.000299999999999317 0.0160078233491243 -0.0136945669206257"/>
<mass value="0.0104003125914103"/>
<inertia ixx="2.71909453810972E-06" ixy="1.35402465472579E-21" ixz="-7.1817349065269E-22" iyy="7.69100314106116E-07" iyz="6.74715432769696E-07" izz="2.30315190420171E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_inner_finger_pad">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.0 0.0 1"/>
</material>
</collision>
</link>
<link name="right_inner_knuckle">
<inertial>
<origin rpy="0 0 0" xyz="0.000123011831763771 0.0507850843201817 0.00103968640075166"/>
<mass value="0.0271177346495152"/>
<inertia ixx="2.61910379223783E-05" ixy="-2.43616858946494E-07" ixz="-6.37789906117123E-09" iyy="2.8270243746167E-06" iyz="-5.37200748039765E-07" izz="2.83695868220296E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pendulum_robot/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="finger_joint" type="fixed">
<origin rpy="0 0 3.141592653589793" xyz="0 -0.0306011 0.054904"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="left_outer_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.8" velocity="2.0"/>
</joint>
<joint name="left_outer_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0315 -0.0041"/>
<parent link="left_outer_knuckle"/>
<child link="left_outer_finger"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="left_inner_knuckle_joint" type="fixed">
<!-- <origin xyz="0 ${reflect * -0.0127} 0.06142" rpy="${pi / 2 + .725} 0 ${(reflect - 1) * pi / 2}" /> -->
<origin rpy="0 0 3.141592653589793" xyz="0 -0.0127 0.06142"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="left_inner_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="1" offset="0"/>
</joint>
<joint name="left_inner_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0061 0.0471"/>
<parent link="left_outer_finger"/>
<child link="left_inner_finger"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="-0.8757" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="-1" offset="0"/>
</joint>
<joint name="left_inner_finger_pad_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0220203446692936 0.03242"/>
<parent link="left_inner_finger"/>
<child link="left_inner_finger_pad"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="right_outer_knuckle_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0306011 0.054904"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="right_outer_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.81" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="1" offset="0"/>
</joint>
<joint name="right_outer_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0315 -0.0041"/>
<parent link="right_outer_knuckle"/>
<child link="right_outer_finger"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="right_inner_knuckle_joint" type="fixed">
<!-- <origin xyz="0 ${reflect * -0.0127} 0.06142" rpy="${pi / 2 + .725} 0 ${(reflect - 1) * pi / 2}" /> -->
<origin rpy="0 0 0.0" xyz="0 0.0127 0.06142"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="right_inner_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="1" offset="0"/>
</joint>
<joint name="right_inner_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0061 0.0471"/>
<parent link="right_outer_finger"/>
<child link="right_inner_finger"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="-0.8757" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="-1" offset="0"/>
</joint>
<joint name="right_inner_finger_pad_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0220203446692936 0.03242"/>
<parent link="right_inner_finger"/>
<child link="right_inner_finger_pad"/>
<axis xyz="0 0 1"/>
</joint>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
</plugin>
</gazebo>
<transmission name="trans_shoulder_y">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_y">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_shoulder_y">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_shoulder_z">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_z">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_shoulder_z">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_shoulder_x">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_x">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_shoulder_x">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_elbow">
<type>transmission_interface/SimpleTransmission</type>
<joint name="elbow">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_elbow">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_wrist_y">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_y">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_wrist_y">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_wrist_x">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_x">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_wrist_x">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_wrist_z">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_z">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_wrist_z">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_finger_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="finger_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_finger_joint">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_right_outer_knuckle_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_outer_knuckle_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_right_outer_knuckle_joint">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_right_inner_knuckle_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_inner_knuckle_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_right_inner_knuckle_joint">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_left_inner_knuckle_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_inner_knuckle_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_left_inner_knuckle_joint">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_left_inner_finger_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_inner_finger_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_left_inner_finger_joint">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<transmission name="trans_right_inner_finger_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_inner_finger_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_right_inner_finger_joint">
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
Visually the gripper is present when I launch gazebo and without the controller lines for the gripper, the arm moves with the gripper attached. When I add the transmission lines and the "fingergroupaction_controller" to my launch file, I get an error
[ INFO] [1685751316.431977667]: gazebo_ros_control plugin is waiting for model URDF in parameter [/pend_bot/robot_description] on the ROS param server.
[ERROR] [1685751316.543147733]: This robot has a joint named "finger_joint" which is not in the gazebo model.
[FATAL] [1685751316.543175133]: Could not initialize robot simulation interface
[INFO] [1685751317.411113, 0.000000]: Calling service /pend_bot/gazebo/set_model_configuration
I know I have taken a few shortcuts like not making any macro files, but is there a way to make this work?
Looking forward to any help. Thank you
Asked by A_J on 2023-06-02 19:48:11 UTC
Comments