initial forking commit
This commit is contained in:
62
robots/fr3/dynamics.yaml
Normal file
62
robots/fr3/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
|
||||
65
robots/fr3/fr3.urdf.xacro
Normal file
65
robots/fr3/fr3.urdf.xacro
Normal file
@@ -0,0 +1,65 @@
|
||||
<?xml version='1.0' encoding='utf-8'?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fr3">
|
||||
|
||||
<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="fr3" />
|
||||
|
||||
<!-- 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" />
|
||||
|
||||
<!-- 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?" -->
|
||||
<xacro:arg name="gazebo" 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="fr3"
|
||||
joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')}"
|
||||
inertials="${xacro.load_yaml('$(find franka_description)/robots/fr3/inertials.yaml')}"
|
||||
kinematics="${xacro.load_yaml('$(find franka_description)/robots/fr3/kinematics.yaml')}"
|
||||
dynamics="${xacro.load_yaml('$(find franka_description)/robots/fr3/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>
|
||||
97
robots/fr3/inertials.yaml
Normal file
97
robots/fr3/inertials.yaml
Normal file
@@ -0,0 +1,97 @@
|
||||
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.0000004128 -0.0181251324 -0.0386035970
|
||||
rpy: 0 0 0
|
||||
mass: 2.9274653454
|
||||
inertia:
|
||||
inertia:
|
||||
xx: 0.023927316485107913
|
||||
xy: 1.3317903455714081e-05
|
||||
xz: -0.00011404774918616684
|
||||
yy: 0.0224821613275756
|
||||
yz: -0.0019950320628240115
|
||||
zz: 0.006350098258530016
|
||||
link2:
|
||||
origin:
|
||||
xyz: 0.0031828864 -0.0743221644 0.0088146084
|
||||
rpy: 0 0 0
|
||||
mass: 2.9355370338
|
||||
inertia:
|
||||
xx: 0.041938946257609425
|
||||
xy: 0.00020257331521090626
|
||||
xz: 0.004077784227179924
|
||||
yy: 0.02514514885014724
|
||||
yz: -0.0042252158006570156
|
||||
zz: 0.06170214472888839
|
||||
link3:
|
||||
origin:
|
||||
xyz: 0.0407015686 -0.0048200565 -0.0289730823
|
||||
rpy: 0 0 0
|
||||
mass: 2.2449013699
|
||||
inertia:
|
||||
xx: 0.02410142547240885
|
||||
xy: 0.002404694559042109
|
||||
xz: -0.002856269270114313
|
||||
yy: 0.01974053266708178
|
||||
yz: -0.002104212683891874
|
||||
zz: 0.019044494482244823
|
||||
link4:
|
||||
origin:
|
||||
xyz: -0.0459100965 0.0630492960 -0.0085187868
|
||||
rpy: 0 0 0
|
||||
mass: 2.6155955791
|
||||
inertia:
|
||||
xx: 0.03452998321913202
|
||||
xy: 0.01322552265982813
|
||||
xz: 0.01015142998484113
|
||||
yy: 0.028881621933049058
|
||||
yz: -0.0009762833870704552
|
||||
zz: 0.04125471171146641
|
||||
link5:
|
||||
origin:
|
||||
xyz: -0.0016039605 0.0292536262 -0.0972965990
|
||||
rpy: 0 0 0
|
||||
mass: 2.3271207594
|
||||
inertia:
|
||||
xx: 0.051610278463662895
|
||||
xy: -0.005715173387783472
|
||||
xz: -0.0035673167625872135
|
||||
yy: 0.04787729713371481
|
||||
yz: 0.010673985108535986
|
||||
zz: 0.016423625579357254
|
||||
link6:
|
||||
origin:
|
||||
xyz: 0.0597131221 -0.0410294666 -0.0101692726
|
||||
rpy: 0 0 0
|
||||
mass: 1.8170376524
|
||||
inertia:
|
||||
xx: 0.005412333594383447
|
||||
xy: 0.006193456360285834
|
||||
xz: 0.0014219289306117652
|
||||
yy: 0.014058329545509979
|
||||
yz: -0.0013140753741120031
|
||||
zz: 0.016080817924212554
|
||||
link7:
|
||||
origin:
|
||||
xyz: 0.0045225817 0.0086261921 -0.0161633251
|
||||
rpy: 0 0 0
|
||||
mass: 0.6271432862
|
||||
inertia:
|
||||
xx: 0.00021092389150104718
|
||||
xy: -2.433299114461931e-05
|
||||
xz: 4.564480393778983e-05
|
||||
yy: 0.00017718568002411474
|
||||
yz: 8.744070223226438e-05
|
||||
zz: 5.993190599659971e-05
|
||||
48
robots/fr3/joint_limits.yaml
Normal file
48
robots/fr3/joint_limits.yaml
Normal file
@@ -0,0 +1,48 @@
|
||||
joint1:
|
||||
limit:
|
||||
lower: -2.7437
|
||||
upper: 2.7437
|
||||
velocity: 2.62
|
||||
effort: 87.0
|
||||
|
||||
joint2:
|
||||
limit:
|
||||
lower: -1.7837
|
||||
upper: 1.7837
|
||||
velocity: 2.62
|
||||
effort: 87.0
|
||||
|
||||
joint3:
|
||||
limit:
|
||||
lower: -2.9007
|
||||
upper: 2.9007
|
||||
velocity: 2.62
|
||||
effort: 87.0
|
||||
|
||||
joint4:
|
||||
limit:
|
||||
lower: -3.0421
|
||||
upper: -0.1518
|
||||
velocity: 2.62
|
||||
effort: 87.0
|
||||
|
||||
joint5:
|
||||
limit:
|
||||
lower: -2.8065
|
||||
upper: 2.8065
|
||||
velocity: 5.26
|
||||
effort: 12.0
|
||||
|
||||
joint6:
|
||||
limit:
|
||||
lower: 0.5445
|
||||
upper: 4.5169
|
||||
velocity: 4.18
|
||||
effort: 12.0
|
||||
|
||||
joint7:
|
||||
limit:
|
||||
lower: -3.0159
|
||||
upper: 3.0159
|
||||
velocity: 5.26
|
||||
effort: 12.0
|
||||
72
robots/fr3/kinematics.yaml
Normal file
72
robots/fr3/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