initial forking commit
This commit is contained in:
21
end_effectors/cobot_pump/cobot_pump.urdf.xacro
Normal file
21
end_effectors/cobot_pump/cobot_pump.urdf.xacro
Normal file
@@ -0,0 +1,21 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="cobot_pump">
|
||||
<xacro:include filename="$(find franka_description)/end_effectors/common/utils.xacro" />
|
||||
<xacro:include filename="$(find franka_description)/end_effectors/common/ee_with_one_link.xacro"/>
|
||||
<xacro:include filename="$(find franka_description)/end_effectors/cobot_pump/cobot_pump_arguments.xacro"/>
|
||||
|
||||
<xacro:ee_with_one_link connected_to="$(arg special_connection)"
|
||||
arm_id="$(arg arm_id)"
|
||||
ee_id="$(arg ee_id)"
|
||||
ee_inertials="${xacro.load_yaml('$(find franka_description)/end_effectors/$(arg ee_id)/inertials.yaml')}"
|
||||
rpy_ee="$(arg rpy_ee)"
|
||||
xyz_ee="$(arg xyz_ee)"
|
||||
tcp_xyz="$(arg tcp_xyz)"
|
||||
tcp_rpy="$(arg tcp_rpy)"
|
||||
safety_distance="$(arg safety_distance)"
|
||||
gazebo="$(arg gazebo)"
|
||||
description_pkg="$(arg description_pkg)"
|
||||
with_sc="$(arg with_sc)">
|
||||
</xacro:ee_with_one_link>
|
||||
|
||||
</robot>
|
||||
37
end_effectors/cobot_pump/cobot_pump_arguments.xacro
Normal file
37
end_effectors/cobot_pump/cobot_pump_arguments.xacro
Normal file
@@ -0,0 +1,37 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<!-- Name for the robot -->
|
||||
<xacro:arg name="arm_id" default="fp3" />
|
||||
|
||||
<!-- End-effector id" -->
|
||||
<xacro:arg name="ee_id" default="cobot_pump" />
|
||||
|
||||
<!-- Where is the end-effector connected to, if different from the robot flange? -->
|
||||
<xacro:arg name="special_connection" default="" />
|
||||
|
||||
<!-- Should self-collision be enabled? -->
|
||||
<xacro:arg name="with_sc" default="false" />
|
||||
|
||||
<!-- Position offset between ee and parent frame -->
|
||||
<xacro:arg name="xyz_ee" default="0 0 0" />
|
||||
|
||||
<!-- Rotation offset between ee and parent frame -->
|
||||
<xacro:arg name="rpy_ee" default= "0 0 0" />
|
||||
|
||||
<!-- Position offset between ee frame and tcp frame -->
|
||||
<xacro:arg name="tcp_xyz" default="0 0 0.105" />
|
||||
|
||||
<!-- Rotation offset between ee frame and tcp frame -->
|
||||
<xacro:arg name="tcp_rpy" default="0 0 0" />
|
||||
|
||||
<!-- Safety distance for the collision capsules -->
|
||||
<xacro:arg name="safety_distance" default="0.03" />
|
||||
|
||||
<!-- Is the robot being simulated in gazebo? -->
|
||||
<xacro:arg name="gazebo" default="false" />
|
||||
|
||||
<!-- Name of the description package -->
|
||||
<xacro:arg name="description_pkg" default="franka_description" />
|
||||
|
||||
</robot>
|
||||
13
end_effectors/cobot_pump/inertials.yaml
Normal file
13
end_effectors/cobot_pump/inertials.yaml
Normal file
@@ -0,0 +1,13 @@
|
||||
cobot_pump:
|
||||
origin:
|
||||
xyz: 0 0 0.063
|
||||
rpy: 0 0 0
|
||||
mass: 1.01
|
||||
inertia:
|
||||
xx: 0.001
|
||||
yy: 0.001
|
||||
zz: 0.001
|
||||
xy: 0
|
||||
xz: 0
|
||||
yz: 0
|
||||
|
||||
Reference in New Issue
Block a user