Skip to content
Snippets Groups Projects
Commit 97651fde authored by jeo65286's avatar jeo65286
Browse files

Edit fr3_franka_hand.urdf file

parent 9f01c637
No related branches found
No related tags found
No related merge requests found
This diff is collapsed.
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /workspaces/src/franka_description/robots/fr3/fr3.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="fr3">
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
<!-- arm_id: Namespace of the robot arm. Serves to differentiate between arms in case of multiple instances. -->
<!-- joint_limits: description of the joint limits that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')} -->
<!-- kinematics: description of the kinematics that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/kinematics.yaml')} -->
<!-- inertials: description of the inertials that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/inertials.yaml')} -->
<!-- dynamics: description of the dynamics that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/dynamics.yaml')} -->
<link name="base">
</link>
<joint name="fr3_base_joint" type="fixed">
<parent link="base"/>
<child link="fr3_link0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link0">
<visual name="fr3_link0_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link0.dae"/>
</geometry>
</visual>
<collision name="fr3_link0_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link0.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.0172 0.0004 0.0745"/>
<mass value="2.3966"/>
<inertia ixx="0.009" ixy="0.0" ixz="0.002" iyy="0.0115" iyz="0.0" izz="0.0085"/>
</inertial>
</link>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link1">
<visual name="fr3_link1_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link1.dae"/>
</geometry>
</visual>
<collision name="fr3_link1_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link1.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0000004128 -0.0181251324 -0.0386035970"/>
<mass value="2.9274653454"/>
<inertia ixx="0.023927316485107913" ixy="1.3317903455714081e-05" ixz="-0.00011404774918616684" iyy="0.0224821613275756" iyz="-0.0019950320628240115" izz="0.006350098258530016"/>
</inertial>
</link>
<joint name="fr3_joint1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.333"/>
<parent link="fr3_link0"/>
<child link="fr3_link1"/>
<axis xyz="0 0 1"/>
<limit effort="87.0" lower="-2.7437" upper="2.7437" velocity="2.62"/>
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.7437" soft_upper_limit="2.7437"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.2" mu_coulomb="0" mu_viscous="16"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link2">
<visual name="fr3_link2_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link2.dae"/>
</geometry>
</visual>
<collision name="fr3_link2_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link2.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0031828864 -0.0743221644 0.0088146084"/>
<mass value="2.9355370338"/>
<inertia ixx="0.041938946257609425" ixy="0.00020257331521090626" ixz="0.004077784227179924" iyy="0.02514514885014724" iyz="-0.0042252158006570156" izz="0.06170214472888839"/>
</inertial>
</link>
<joint name="fr3_joint2" type="revolute">
<origin rpy="-1.570796326794897 0 0" xyz="0 0 0"/>
<parent link="fr3_link1"/>
<child link="fr3_link2"/>
<axis xyz="0 0 1"/>
<limit effort="87.0" lower="-1.7837" upper="1.7837" velocity="2.62"/>
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7837" soft_upper_limit="1.7837"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.2" mu_coulomb="0" mu_viscous="16"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link3">
<visual name="fr3_link3_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link3.dae"/>
</geometry>
</visual>
<collision name="fr3_link3_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link3.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0407015686 -0.0048200565 -0.0289730823"/>
<mass value="2.2449013699"/>
<inertia ixx="0.02410142547240885" ixy="0.002404694559042109" ixz="-0.002856269270114313" iyy="0.01974053266708178" iyz="-0.002104212683891874" izz="0.019044494482244823"/>
</inertial>
</link>
<joint name="fr3_joint3" type="revolute">
<origin rpy="1.570796326794897 0 0" xyz="0 -0.316 0"/>
<parent link="fr3_link2"/>
<child link="fr3_link3"/>
<axis xyz="0 0 1"/>
<limit effort="87.0" lower="-2.9007" upper="2.9007" velocity="2.62"/>
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.9007" soft_upper_limit="2.9007"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.2" mu_coulomb="0" mu_viscous="16"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link4">
<visual name="fr3_link4_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link4.dae"/>
</geometry>
</visual>
<collision name="fr3_link4_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link4.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.0459100965 0.0630492960 -0.0085187868"/>
<mass value="2.6155955791"/>
<inertia ixx="0.03452998321913202" ixy="0.01322552265982813" ixz="0.01015142998484113" iyy="0.028881621933049058" iyz="-0.0009762833870704552" izz="0.04125471171146641"/>
</inertial>
</link>
<joint name="fr3_joint4" type="revolute">
<origin rpy="1.570796326794897 0 0" xyz="0.0825 0 0"/>
<parent link="fr3_link3"/>
<child link="fr3_link4"/>
<axis xyz="0 0 1"/>
<limit effort="87.0" lower="-3.0421" upper="-0.1518" velocity="2.62"/>
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0421" soft_upper_limit="-0.1518"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.2" mu_coulomb="0" mu_viscous="16"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link5">
<visual name="fr3_link5_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link5.dae"/>
</geometry>
</visual>
<collision name="fr3_link5_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link5.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.0016039605 0.0292536262 -0.0972965990"/>
<mass value="2.3271207594"/>
<inertia ixx="0.051610278463662895" ixy="-0.005715173387783472" ixz="-0.0035673167625872135" iyy="0.04787729713371481" iyz="0.010673985108535986" izz="0.016423625579357254"/>
</inertial>
</link>
<joint name="fr3_joint5" type="revolute">
<origin rpy="-1.570796326794897 0 0" xyz="-0.0825 0.384 0"/>
<parent link="fr3_link4"/>
<child link="fr3_link5"/>
<axis xyz="0 0 1"/>
<limit effort="12.0" lower="-2.8065" upper="2.8065" velocity="5.26"/>
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8065" soft_upper_limit="2.8065"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.2" mu_coulomb="0" mu_viscous="16"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link6">
<visual name="fr3_link6_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link6.dae"/>
</geometry>
</visual>
<collision name="fr3_link6_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link6.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0597131221 -0.0410294666 -0.0101692726"/>
<mass value="1.8170376524"/>
<inertia ixx="0.005412333594383447" ixy="0.006193456360285834" ixz="0.0014219289306117652" iyy="0.014058329545509979" iyz="-0.0013140753741120031" izz="0.016080817924212554"/>
</inertial>
</link>
<joint name="fr3_joint6" type="revolute">
<origin rpy="1.570796326794897 0 0" xyz="0 0 0"/>
<parent link="fr3_link5"/>
<child link="fr3_link6"/>
<axis xyz="0 0 1"/>
<limit effort="12.0" lower="0.5445" upper="4.5169" velocity="4.18"/>
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="0.5445" soft_upper_limit="4.5169"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.2" mu_coulomb="0" mu_viscous="16"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_link7">
<visual name="fr3_link7_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/visual/link7.dae"/>
</geometry>
</visual>
<collision name="fr3_link7_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/fr3/collision/link7.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0045225817 0.0086261921 -0.0161633251"/>
<mass value="0.6271432862"/>
<inertia ixx="0.00021092389150104718" ixy="-2.433299114461931e-05" ixz="4.564480393778983e-05" iyy="0.00017718568002411474" iyz="8.744070223226438e-05" izz="5.993190599659971e-05"/>
</inertial>
</link>
<joint name="fr3_joint7" type="revolute">
<origin rpy="1.570796326794897 0 0" xyz="0.088 0 0"/>
<parent link="fr3_link6"/>
<child link="fr3_link7"/>
<axis xyz="0 0 1"/>
<limit effort="12.0" lower="-3.0159" upper="3.0159" velocity="5.26"/>
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0159" soft_upper_limit="3.0159"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.2" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="fr3_link8"/>
<joint name="fr3_joint8" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.107"/>
<parent link="fr3_link7"/>
<child link="fr3_link8"/>
</joint>
<joint name="fr3_hand_joint" type="fixed">
<parent link="fr3_link8"/>
<child link="fr3_hand"/>
<origin rpy="0 0 -0.7853981633974483" xyz="0 0 0"/>
</joint>
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="fr3_hand">
<visual name="fr3_hand_visual">
<geometry>
<mesh filename="package://franka_description/meshes/robot_ee/franka_hand_white/visual/hand.dae"/>
</geometry>
</visual>
<collision name="fr3_hand_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_ee/franka_hand_white/collision/hand.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.01 0 0.03"/>
<mass value="0.73"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.0025" iyz="0" izz="0.0017"/>
</inertial>
</link>
<!-- Define the hand_tcp frame -->
<link name="fr3_hand_tcp"/>
<joint name="fr3_hand_tcp_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.1034"/>
<parent link="fr3_hand"/>
<child link="fr3_hand_tcp"/>
</joint>
</robot>
...@@ -146,7 +146,8 @@ private: ...@@ -146,7 +146,8 @@ private:
const std::string repo_path = "/home/jwhong/nix-project/impedance_controller/"; const std::string repo_path = "/home/jwhong/nix-project/impedance_controller/";
/* AutoDiff module using Pinocchio & CasADi */ /* AutoDiff module using Pinocchio & CasADi */
std::string urdf_filename = std::string(repo_path + "assets/model/fr3_hand.urdf"); // std::string urdf_filename = std::string(repo_path + "assets/model/fr3_hand.urdf");
std::string urdf_filename = std::string(repo_path + "assets/model/fr3_franka_hand.urdf");
std::unique_ptr<SymbolicAutoDiff> autodiff_; std::unique_ptr<SymbolicAutoDiff> autodiff_;
pinocchio::Model model_; pinocchio::Model model_;
pinocchio::Data data_; pinocchio::Data data_;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment