-
-
Save soraxas/03588e631b5f349b4d29402dfee4cb5e to your computer and use it in GitHub Desktop.
urdf file for j2n6s300_standalone.xacro. Created with `rosrun xacro xacro j2n6s300_standalone.xacro > model.urdf`
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<!-- =================================================================================== --> | |
<!-- | This document was autogenerated by xacro from j2n6s300_standalone.xacro | --> | |
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> | |
<!-- =================================================================================== --> | |
<!-- j2n6s300 refers to jaco v2 6DOF non-spherical 3fingers --> | |
<robot name="j2n6s300" xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz" xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint" xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model" xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable" xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xi="http://www.w3.org/2001/XInclude"> | |
<!-- links mesh_no | |
base 0 | |
shoulder 1 | |
arm 2 | |
forearm 3 | |
wrist 4 | |
arm_mico 5 | |
arm_half1 (7dof) 6 | |
arm_half2 (7dof) 7 | |
wrist_spherical_1 8 | |
wrist_spherical_2 9 | |
hand 3 finger 55 | |
hand_2finger 56 | |
finger_proximal 57 | |
finger_distal 58 | |
--> | |
<!-- links mesh_no | |
base 0 | |
shoulder 1 | |
arm 2 | |
forearm 3 | |
wrist 4 | |
arm_mico 5 | |
arm_half1 (7dof) 6 | |
arm_half2 (7dof) 7 | |
wrist_spherical_1 8 | |
wrist_spherical_2 9 | |
hand 3 finger 55 | |
hand_2finger 56 | |
finger_proximal 57 | |
finger_distal 58 | |
--> | |
<link name="root"/> | |
<!-- for gazebo --> | |
<link name="world"/> | |
<joint name="connect_root_and_world" type="fixed"> | |
<child link="root"/> | |
<parent link="world"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
</joint> | |
<!-- ros_control plugin --> | |
<gazebo> | |
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control"> | |
<robotNamespace>j2n6s300</robotNamespace> | |
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> | |
<legacyModeNS>true</legacyModeNS> | |
</plugin> | |
</gazebo> | |
<link name="j2n6s300_link_base"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/base.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/base.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.46784"/> | |
<origin rpy="0 0 0" xyz="0 0 0.1255"/> | |
<inertia ixx="0.000951270861568" ixy="0" ixz="0" iyy="0.000951270861568" iyz="0" izz="0.000374272"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_base" type="fixed"> | |
<parent link="root"/> | |
<child link="j2n6s300_link_base"/> | |
<axis xyz="0 0 0"/> | |
<limit effort="0" lower="0" upper="0" velocity="0"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<link name="j2n6s300_link_1"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/shoulder.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/ring_big.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/shoulder.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.7477"/> | |
<origin xyz="0 -0.002 -0.0605"/> | |
<inertia ixx="0.00152031725204" ixy="0" ixz="0" iyy="0.00152031725204" iyz="0" izz="0.00059816"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_1" type="continuous"> | |
<parent link="j2n6s300_link_base"/> | |
<child link="j2n6s300_link_1"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="40" lower="-6.28318530718" upper="6.28318530718" velocity="0.628318530718"/> | |
<origin rpy="0 3.14159265359 0" xyz="0 0 0.15675"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<transmission name="j2n6s300_joint_1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_1"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_1_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>160</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<!--For torque sensing in simulation--> | |
<gazebo reference="j2n6s300_joint_1"> | |
<provideFeedback>true</provideFeedback> | |
</gazebo> | |
<gazebo> | |
<plugin filename="libgazebo_ros_ft_sensor.so" name="ft_sensor"> | |
<updateRate>30.0</updateRate> | |
<topicName>j2n6s300_joint_1_ft_sensor_topic</topicName> | |
<jointName>j2n6s300_joint_1</jointName> | |
</plugin> | |
</gazebo> | |
<link name="j2n6s300_link_2"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/arm.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/ring_big.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/arm.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.99"/> | |
<origin xyz="0 -0.2065 -0.01"/> | |
<inertia ixx="0.010502207991" ixy="0" ixz="0" iyy="0.000792" iyz="0" izz="0.010502207991"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_2" type="revolute"> | |
<parent link="j2n6s300_link_1"/> | |
<child link="j2n6s300_link_2"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="80" lower="0.820304748437" upper="5.46288055874" velocity="0.628318530718"/> | |
<origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.0016 -0.11875"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<transmission name="j2n6s300_joint_2_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_2"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_2_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>160</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<!--For torque sensing in simulation--> | |
<gazebo reference="j2n6s300_joint_2"> | |
<provideFeedback>true</provideFeedback> | |
</gazebo> | |
<gazebo> | |
<plugin filename="libgazebo_ros_ft_sensor.so" name="ft_sensor"> | |
<updateRate>30.0</updateRate> | |
<topicName>j2n6s300_joint_2_ft_sensor_topic</topicName> | |
<jointName>j2n6s300_joint_2</jointName> | |
</plugin> | |
</gazebo> | |
<link name="j2n6s300_link_3"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/forearm.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/ring_big.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/forearm.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.6763"/> | |
<origin xyz="0 0.081 -0.0086"/> | |
<inertia ixx="0.00142022431908" ixy="0" ixz="0" iyy="0.000304335" iyz="0" izz="0.00142022431908"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_3" type="revolute"> | |
<parent link="j2n6s300_link_2"/> | |
<child link="j2n6s300_link_3"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="40" lower="0.331612557879" upper="5.9515727493" velocity="0.628318530718"/> | |
<origin rpy="0 3.14159265359 0" xyz="0 -0.410 0"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<transmission name="j2n6s300_joint_3_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_3"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_3_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>160</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<!--For torque sensing in simulation--> | |
<gazebo reference="j2n6s300_joint_3"> | |
<provideFeedback>true</provideFeedback> | |
</gazebo> | |
<gazebo> | |
<plugin filename="libgazebo_ros_ft_sensor.so" name="ft_sensor"> | |
<updateRate>30.0</updateRate> | |
<topicName>j2n6s300_joint_3_ft_sensor_topic</topicName> | |
<jointName>j2n6s300_joint_3</jointName> | |
</plugin> | |
</gazebo> | |
<link name="j2n6s300_link_4"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/wrist.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/ring_small.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/wrist.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.426367"/> | |
<origin xyz="0 -0.037 -0.0642"/> | |
<inertia ixx="7.73496906e-05" ixy="0" ixz="0" iyy="7.73496906e-05" iyz="0" izz="0.0001428"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_4" type="continuous"> | |
<parent link="j2n6s300_link_3"/> | |
<child link="j2n6s300_link_4"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="20" lower="-6.28318530718" upper="6.28318530718" velocity="0.837758040957"/> | |
<origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.2073 -0.0114"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<transmission name="j2n6s300_joint_4_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_4"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_4_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>160</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<!--For torque sensing in simulation--> | |
<gazebo reference="j2n6s300_joint_4"> | |
<provideFeedback>true</provideFeedback> | |
</gazebo> | |
<gazebo> | |
<plugin filename="libgazebo_ros_ft_sensor.so" name="ft_sensor"> | |
<updateRate>30.0</updateRate> | |
<topicName>j2n6s300_joint_4_ft_sensor_topic</topicName> | |
<jointName>j2n6s300_joint_4</jointName> | |
</plugin> | |
</gazebo> | |
<link name="j2n6s300_link_5"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/wrist.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/ring_small.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/wrist.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.426367"/> | |
<origin xyz="0 -0.037 -0.0642"/> | |
<inertia ixx="7.73496906e-05" ixy="0" ixz="0" iyy="7.73496906e-05" iyz="0" izz="0.0001428"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_5" type="continuous"> | |
<parent link="j2n6s300_link_4"/> | |
<child link="j2n6s300_link_5"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="20" lower="-6.28318530718" upper="6.28318530718" velocity="0.837758040957"/> | |
<origin rpy="1.0471975512 0 3.14159265359" xyz="0 -0.03703 -0.06414"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<transmission name="j2n6s300_joint_5_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_5"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_5_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>160</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<!--For torque sensing in simulation--> | |
<gazebo reference="j2n6s300_joint_5"> | |
<provideFeedback>true</provideFeedback> | |
</gazebo> | |
<gazebo> | |
<plugin filename="libgazebo_ros_ft_sensor.so" name="ft_sensor"> | |
<updateRate>30.0</updateRate> | |
<topicName>j2n6s300_joint_5_ft_sensor_topic</topicName> | |
<jointName>j2n6s300_joint_5</jointName> | |
</plugin> | |
</gazebo> | |
<link name="j2n6s300_link_6"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/hand_3finger.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/ring_small.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/hand_3finger.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.99"/> | |
<origin xyz="0 0 -0.06"/> | |
<inertia ixx="0.0003453236187" ixy="0" ixz="0" iyy="0.0003453236187" iyz="0" izz="0.0005816"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_6" type="continuous"> | |
<parent link="j2n6s300_link_5"/> | |
<child link="j2n6s300_link_6"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="20" lower="-6.28318530718" upper="6.28318530718" velocity="0.837758040957"/> | |
<origin rpy="1.0471975512 0 3.14159265359" xyz="0 -0.03703 -0.06414"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<transmission name="j2n6s300_joint_6_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_6"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_6_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>160</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<!--For torque sensing in simulation--> | |
<gazebo reference="j2n6s300_joint_6"> | |
<provideFeedback>true</provideFeedback> | |
</gazebo> | |
<gazebo> | |
<plugin filename="libgazebo_ros_ft_sensor.so" name="ft_sensor"> | |
<updateRate>30.0</updateRate> | |
<topicName>j2n6s300_joint_6_ft_sensor_topic</topicName> | |
<jointName>j2n6s300_joint_6</jointName> | |
</plugin> | |
</gazebo> | |
<link name="j2n6s300_end_effector"/> | |
<joint name="j2n6s300_joint_end_effector" type="fixed"> | |
<parent link="j2n6s300_link_6"/> | |
<child link="j2n6s300_end_effector"/> | |
<axis xyz="0 0 0"/> | |
<limit effort="2000" lower="0" upper="0" velocity="1"/> | |
<origin rpy="3.14159265359 0 1.57079632679" xyz="0 0 -0.1600"/> | |
</joint> | |
<link name="j2n6s300_link_finger_1"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.01"/> | |
<origin xyz="0.022 0 0"/> | |
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_finger_1" type="revolute"> | |
<parent link="j2n6s300_link_6"/> | |
<child link="j2n6s300_link_finger_1"/> | |
<axis xyz="0 0 1"/> | |
<origin rpy="-1.570796327 .649262481663582 1.35961148639407" xyz="0.00279 0.03126 -0.11467"/> | |
<limit effort="2" lower="0" upper="1.51" velocity="1"/> | |
</joint> | |
<transmission name="j2n6s300_joint_finger_1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_finger_1"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_finger_1_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<link name="j2n6s300_link_finger_tip_1"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_distal.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_distal.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.01"/> | |
<origin xyz="0.022 0 0"/> | |
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_finger_tip_1" type="revolute"> | |
<parent link="j2n6s300_link_finger_1"/> | |
<child link="j2n6s300_link_finger_tip_1"/> | |
<axis xyz="0 0 1"/> | |
<origin rpy="0 0 0" xyz="0.044 -0.003 0"/> | |
<limit effort="2" lower="0" upper="2" velocity="1"/> | |
</joint> | |
<transmission name="j2n6s300_joint_finger_tip_1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_finger_tip_1"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_finger_tip_1_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<link name="j2n6s300_link_finger_2"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.01"/> | |
<origin xyz="0.022 0 0"/> | |
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_finger_2" type="revolute"> | |
<parent link="j2n6s300_link_6"/> | |
<child link="j2n6s300_link_finger_2"/> | |
<axis xyz="0 0 1"/> | |
<origin rpy="-1.570796327 .649262481663582 -1.38614049188413" xyz="0.02226 -0.02707 -0.11482"/> | |
<limit effort="2" lower="0" upper="1.51" velocity="1"/> | |
</joint> | |
<transmission name="j2n6s300_joint_finger_2_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_finger_2"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_finger_2_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<link name="j2n6s300_link_finger_tip_2"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_distal.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_distal.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.01"/> | |
<origin xyz="0.022 0 0"/> | |
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_finger_tip_2" type="revolute"> | |
<parent link="j2n6s300_link_finger_2"/> | |
<child link="j2n6s300_link_finger_tip_2"/> | |
<axis xyz="0 0 1"/> | |
<origin rpy="0 0 0" xyz="0.044 -0.003 0"/> | |
<limit effort="2" lower="0" upper="2" velocity="1"/> | |
</joint> | |
<transmission name="j2n6s300_joint_finger_tip_2_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_finger_tip_2"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_finger_tip_2_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<link name="j2n6s300_link_finger_3"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.01"/> | |
<origin xyz="0.022 0 0"/> | |
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_finger_3" type="revolute"> | |
<parent link="j2n6s300_link_6"/> | |
<child link="j2n6s300_link_finger_3"/> | |
<axis xyz="0 0 1"/> | |
<origin rpy="-1.570796327 .649262481663582 -1.75545216211587" xyz="-0.02226 -0.02707 -0.11482"/> | |
<limit effort="2" lower="0" upper="1.51" velocity="1"/> | |
</joint> | |
<transmission name="j2n6s300_joint_finger_3_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_finger_3"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_finger_3_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
<link name="j2n6s300_link_finger_tip_3"> | |
<visual> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_distal.dae"/> | |
</geometry> | |
<material name="carbon_fiber"> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="package://kinova_description/meshes/finger_distal.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.01"/> | |
<origin xyz="0.022 0 0"/> | |
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> | |
</inertial> | |
</link> | |
<joint name="j2n6s300_joint_finger_tip_3" type="revolute"> | |
<parent link="j2n6s300_link_finger_3"/> | |
<child link="j2n6s300_link_finger_tip_3"/> | |
<axis xyz="0 0 1"/> | |
<origin rpy="0 0 0" xyz="0.044 -0.003 0"/> | |
<limit effort="2" lower="0" upper="2" velocity="1"/> | |
</joint> | |
<transmission name="j2n6s300_joint_finger_tip_3_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="j2n6s300_joint_finger_tip_3"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="j2n6s300_joint_finger_tip_3_actuator"> | |
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
</transmission> | |
</robot> | |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment