initial forking commit
This commit is contained in:
62
robots/fer/dynamics.yaml
Normal file
62
robots/fer/dynamics.yaml
Normal file
@@ -0,0 +1,62 @@
|
||||
joint1:
|
||||
dynamic:
|
||||
D: 1
|
||||
K: 7000
|
||||
damping: 0.003
|
||||
friction: 0.2
|
||||
mu_coulomb: 0
|
||||
mu_viscous: 16
|
||||
|
||||
joint2:
|
||||
dynamic:
|
||||
D: 1
|
||||
K: 7000
|
||||
damping: 0.003
|
||||
friction: 0.2
|
||||
mu_coulomb: 0
|
||||
mu_viscous: 16
|
||||
|
||||
joint3:
|
||||
dynamic:
|
||||
D: 1
|
||||
K: 7000
|
||||
damping: 0.003
|
||||
friction: 0.2
|
||||
mu_coulomb: 0
|
||||
mu_viscous: 16
|
||||
|
||||
joint4:
|
||||
dynamic:
|
||||
D: 1
|
||||
K: 7000
|
||||
damping: 0.003
|
||||
friction: 0.2
|
||||
mu_coulomb: 0
|
||||
mu_viscous: 16
|
||||
|
||||
joint5:
|
||||
dynamic:
|
||||
D: 1
|
||||
K: 7000
|
||||
damping: 0.003
|
||||
friction: 0.2
|
||||
mu_coulomb: 0
|
||||
mu_viscous: 16
|
||||
|
||||
joint6:
|
||||
dynamic:
|
||||
D: 1
|
||||
K: 7000
|
||||
damping: 0.003
|
||||
friction: 0.2
|
||||
mu_coulomb: 0
|
||||
mu_viscous: 16
|
||||
|
||||
joint7:
|
||||
dynamic:
|
||||
D: 1
|
||||
K: 7000
|
||||
damping: 0.003
|
||||
friction: 0.2
|
||||
mu_coulomb: 0
|
||||
mu_viscous: 16
|
||||
66
robots/fer/fer.urdf.xacro
Normal file
66
robots/fer/fer.urdf.xacro
Normal file
@@ -0,0 +1,66 @@
|
||||
<?xml version='1.0' encoding='utf-8'?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fer">
|
||||
|
||||
<xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro"/>
|
||||
|
||||
<!--
|
||||
DEPRECATION NOTICE
|
||||
argument arm_id is no longer supported and will be removed in the future.
|
||||
This argument is ignored.
|
||||
-->
|
||||
<xacro:arg name="arm_id" default="fer" />
|
||||
|
||||
<!-- Don't print a prefix for joints, visuals, and links? -->
|
||||
<xacro:arg name="no_prefix" default="false"/>
|
||||
|
||||
<!-- Should an end-effector be mounted at the flange?" -->
|
||||
<xacro:arg name="hand" default="true" />
|
||||
|
||||
<!-- Which end-effector would be mounted at the flange?" -->
|
||||
<xacro:arg name="ee_id" default="franka_hand" />
|
||||
|
||||
<!-- Is the robot being simulated in gazebo?" -->
|
||||
<xacro:arg name="gazebo" default="false" />
|
||||
<!-- If `gazebo` arg is set, to which frame shall $(arm_id)_link0 be parented. Empty string for not fixing at all -->
|
||||
<xacro:arg name="parent" default="world" />
|
||||
<!-- If `gazebo` arg is set and `parent` not empty, what position offset between `parent` & $(arm_id)_link0 -->
|
||||
<xacro:arg name="xyz" default="0 0 0" />
|
||||
<!-- If `gazebo` arg is set and `parent` not empty, what rotation offset between `parent` & $(arm_id)_link0 -->
|
||||
<xacro:arg name="rpy" default="0 0 0" />
|
||||
|
||||
<!-- Should self-collision be enabled? -->
|
||||
<xacro:arg name="with_sc" default="false" />
|
||||
|
||||
<!-- Is the robot being controlled with ros2_control?" -->
|
||||
<xacro:arg name="ros2_control" default="false" />
|
||||
<!-- IP address or hostname of the robot" -->
|
||||
<xacro:arg name="robot_ip" default="" />
|
||||
<!-- Should a fake hardware be used? -->
|
||||
<xacro:arg name="use_fake_hardware" default="false" />
|
||||
<!-- Should fake sensors be used? -->
|
||||
<xacro:arg name="fake_sensor_commands" default="false" />
|
||||
<!-- Should the robot be spawned in Gazebo with effort interfaces?" -->
|
||||
<xacro:arg name="gazebo_effort" default="false" />
|
||||
|
||||
<!-- For a multi arm setup, we need a threaded robot running async-->
|
||||
<xacro:arg name="multi_arm" default="false" />
|
||||
|
||||
<xacro:franka_robot arm_id="fer"
|
||||
joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fer/joint_limits.yaml')}"
|
||||
inertials="${xacro.load_yaml('$(find franka_description)/robots/fer/inertials.yaml')}"
|
||||
kinematics="${xacro.load_yaml('$(find franka_description)/robots/fer/kinematics.yaml')}"
|
||||
dynamics="${xacro.load_yaml('$(find franka_description)/robots/fer/dynamics.yaml')}"
|
||||
gazebo="$(arg gazebo)"
|
||||
hand="$(arg hand)"
|
||||
ee_id="$(arg ee_id)"
|
||||
with_sc="$(arg with_sc)"
|
||||
ros2_control="$(arg ros2_control)"
|
||||
robot_ip="$(arg robot_ip)"
|
||||
use_fake_hardware="$(arg use_fake_hardware)"
|
||||
fake_sensor_commands="$(arg fake_sensor_commands)"
|
||||
gazebo_effort="$(arg gazebo_effort)"
|
||||
no_prefix="$(arg no_prefix)"
|
||||
arm_prefix= ""
|
||||
connected_to= "base">
|
||||
</xacro:franka_robot>
|
||||
</robot>
|
||||
96
robots/fer/inertials.yaml
Normal file
96
robots/fer/inertials.yaml
Normal file
@@ -0,0 +1,96 @@
|
||||
link0:
|
||||
origin:
|
||||
xyz: -0.0172 0.0004 0.0745
|
||||
rpy: 0 0 0
|
||||
mass: 2.3966
|
||||
inertia:
|
||||
xx: 0.0090
|
||||
xy: 0.0000
|
||||
xz: 0.0020
|
||||
yy: 0.0115
|
||||
yz: 0.0000
|
||||
zz: 0.0085
|
||||
link1:
|
||||
origin:
|
||||
xyz: 0.00033 -0.02204 -0.04762
|
||||
rpy: 0 0 0
|
||||
mass: 2.7907
|
||||
inertia:
|
||||
xx: 0.01564782655
|
||||
xy: 0.00000531236
|
||||
xz: -0.00003676721
|
||||
yy: 0.01439883526
|
||||
yz: -0.00248480843
|
||||
zz: 0.00500443991
|
||||
link2:
|
||||
origin:
|
||||
xyz: 0.00038 -0.09211 0.01908
|
||||
rpy: 0 0 0
|
||||
mass: 2.5420
|
||||
inertia:
|
||||
xx: 0.01662427728
|
||||
xy: 0.00003086077
|
||||
xz: 0.00000835940
|
||||
yy: 0.00462501261
|
||||
yz: 0.00355899830
|
||||
zz: 0.01545124526
|
||||
link3:
|
||||
origin:
|
||||
xyz: 0.05152 0.01696 -0.02971
|
||||
rpy: 0 0 0
|
||||
mass: 2.2513
|
||||
inertia:
|
||||
xx: 0.00631741992
|
||||
xy: 0.00097309955
|
||||
xz: 0.00292525834
|
||||
yy: 0.00866285493
|
||||
yz: 0.00093469224
|
||||
zz: 0.00657804051
|
||||
link4:
|
||||
origin:
|
||||
xyz: -0.05113 0.05825 0.01698
|
||||
rpy: 0 0 0
|
||||
mass: 2.2037
|
||||
inertia:
|
||||
xx: 0.00784585566
|
||||
xy: -0.00339591957
|
||||
xz: 0.00158704074
|
||||
yy: 0.00649543136
|
||||
yz: -0.00181477884
|
||||
zz: 0.01003079917
|
||||
link5:
|
||||
origin:
|
||||
xyz: -0.00005 0.03730 -0.09280
|
||||
rpy: 0 0 0
|
||||
mass: 2.2855
|
||||
inertia:
|
||||
xx: 0.02297014781
|
||||
xy: -0.00000949345
|
||||
xz: -0.00002063156
|
||||
yy: 0.02095060919
|
||||
yz: 0.00382345782
|
||||
zz: 0.00430606551
|
||||
link6:
|
||||
origin:
|
||||
xyz: 0.06572 -0.00371 0.00153
|
||||
rpy: 0 0 0
|
||||
mass: 1.353
|
||||
inertia:
|
||||
xx: 0.00087964522
|
||||
xy: -0.00021487814
|
||||
xz: -0.00011911662
|
||||
yy: 0.00277796968
|
||||
yz: 0.00001274322
|
||||
zz: 0.00286701969
|
||||
link7:
|
||||
origin:
|
||||
xyz: 0.00089 -0.00044 0.05491
|
||||
rpy: 0 0 0
|
||||
mass: 0.35973
|
||||
inertia:
|
||||
xx: 0.00019541063
|
||||
xy: 0.00000165231
|
||||
xz: 0.00000148826
|
||||
yy: 0.00019210361
|
||||
yz: -0.00000131132
|
||||
zz: 0.00017936256
|
||||
48
robots/fer/joint_limits.yaml
Normal file
48
robots/fer/joint_limits.yaml
Normal file
@@ -0,0 +1,48 @@
|
||||
joint1:
|
||||
limit:
|
||||
lower: -2.8973
|
||||
upper: 2.8973
|
||||
velocity: 2.1750
|
||||
effort: 87.0
|
||||
|
||||
joint2:
|
||||
limit:
|
||||
lower: -1.7628
|
||||
upper: 1.7628
|
||||
velocity: 2.1750
|
||||
effort: 87.0
|
||||
|
||||
joint3:
|
||||
limit:
|
||||
lower: -2.8973
|
||||
upper: 2.8973
|
||||
velocity: 2.1750
|
||||
effort: 87.0
|
||||
|
||||
joint4:
|
||||
limit:
|
||||
lower: -3.0718
|
||||
upper: -0.0698
|
||||
velocity: 2.1750
|
||||
effort: 87.0
|
||||
|
||||
joint5:
|
||||
limit:
|
||||
lower: -2.8973
|
||||
upper: 2.8973
|
||||
velocity: 2.6100
|
||||
effort: 12.0
|
||||
|
||||
joint6:
|
||||
limit:
|
||||
lower: -0.0175
|
||||
upper: 3.7525
|
||||
velocity: 2.6100
|
||||
effort: 12.0
|
||||
|
||||
joint7:
|
||||
limit:
|
||||
lower: -2.8973
|
||||
upper: 2.8973
|
||||
velocity: 2.6100
|
||||
effort: 12.0
|
||||
72
robots/fer/kinematics.yaml
Normal file
72
robots/fer/kinematics.yaml
Normal file
@@ -0,0 +1,72 @@
|
||||
joint1:
|
||||
kinematic:
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0.333
|
||||
roll: 0
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
|
||||
joint2:
|
||||
kinematic:
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0
|
||||
roll: -1.570796326794897
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
|
||||
joint3:
|
||||
kinematic:
|
||||
x: 0
|
||||
y: -0.316
|
||||
z: 0
|
||||
roll: 1.570796326794897
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
|
||||
joint4:
|
||||
kinematic:
|
||||
x: 0.0825
|
||||
y: 0
|
||||
z: 0
|
||||
roll: 1.570796326794897
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
|
||||
joint5:
|
||||
kinematic:
|
||||
x: -0.0825
|
||||
y: 0.384
|
||||
z: 0
|
||||
roll: -1.570796326794897
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
|
||||
joint6:
|
||||
kinematic:
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0
|
||||
roll: 1.570796326794897
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
|
||||
joint7:
|
||||
kinematic:
|
||||
x: 0.088
|
||||
y: 0
|
||||
z: 0
|
||||
roll: 1.570796326794897
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
|
||||
# Joint to tool origin
|
||||
joint8:
|
||||
kinematic:
|
||||
x: 0
|
||||
y: 0
|
||||
z: 0.107
|
||||
roll: 0
|
||||
pitch: 0
|
||||
yaw: 0
|
||||
Reference in New Issue
Block a user