Add custom xarm packages

This commit is contained in:
2023-03-21 13:33:51 +02:00
parent 1763aee9ca
commit e42e0fea90
176 changed files with 13024 additions and 6 deletions

View File

@@ -0,0 +1,36 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="xarm6_gazebo" params="prefix">
<gazebo reference="${prefix}link_base">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}link1">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}link2">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}link3">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}link4">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}link5">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="${prefix}link6">
<selfCollide>true</selfCollide>
</gazebo>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,118 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="xarm6_ros2_control" params="prefix
velocity_control:='false'
ros2_control_plugin:='uf_robot_hardware/UFRobotSystemHardware'
hw_ns:='xarm' add_gripper:='false'
robot_ip:='' report_type:='normal' baud_checkset:='true' default_gripper_baud:=2000000
joint1_lower_limit:=${-2.0*pi} joint1_upper_limit:=${2.0*pi}
joint2_lower_limit:=${-2.059} joint2_upper_limit:=${2.0944}
joint3_lower_limit:=${-3.927} joint3_upper_limit:=${0.19198}
joint4_lower_limit:=${-2.0*pi} joint4_upper_limit:=${2.0*pi}
joint5_lower_limit:=${-1.69297} joint5_upper_limit:=${pi}
joint6_lower_limit:=${-2.0*pi} joint6_upper_limit:=${2.0*pi}">
<ros2_control name="${prefix}${ros2_control_plugin}" type="system">
<hardware>
<plugin>${ros2_control_plugin}</plugin>
<xacro:if value="${ros2_control_plugin == 'uf_robot_hardware/UFRobotSystemHardware'}">
<param name="hw_ns">${prefix}${hw_ns}</param>
<param name="velocity_control">${velocity_control}</param>
<param name="prefix">P${prefix}</param>
<param name="robot_ip">R${robot_ip}</param>
<param name="report_type">${report_type}</param>
<param name="dof">6</param>
<param name="baud_checkset">${baud_checkset}</param>
<param name="default_gripper_baud">${default_gripper_baud}</param>
<param name="robot_type">xarm</param>
<param name="add_gripper">${add_gripper}</param>
</xacro:if>
<!-- fake -->
<!-- <plugin>fake_components/GenericSystem</plugin> -->
<!-- gazebo -->
<!-- <plugin>gazebo_ros2_control/GazeboSystem</plugin> -->
<!-- real xarm -->
<!-- <plugin>uf_robot_hardware/UFRobotSystemHardware</plugin> -->
</hardware>
<joint name="${prefix}joint1">
<command_interface name="position">
<param name="min">${joint1_lower_limit}</param>
<param name="max">${joint1_upper_limit}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.14</param>
<param name="max">3.14</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<!-- <state_interface name="effort"/> -->
</joint>
<joint name="${prefix}joint2">
<command_interface name="position">
<param name="min">${joint2_lower_limit}</param>
<param name="max">${joint2_upper_limit}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.14</param>
<param name="max">3.14</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<!-- <state_interface name="effort"/> -->
</joint>
<joint name="${prefix}joint3">
<command_interface name="position">
<param name="min">${joint3_lower_limit}</param>
<param name="max">${joint3_upper_limit}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.14</param>
<param name="max">3.14</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<!-- <state_interface name="effort"/> -->
</joint>
<joint name="${prefix}joint4">
<command_interface name="position">
<param name="min">${joint4_lower_limit}</param>
<param name="max">${joint4_upper_limit}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.14</param>
<param name="max">3.14</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<!-- <state_interface name="effort"/> -->
</joint>
<joint name="${prefix}joint5">
<command_interface name="position">
<param name="min">${joint5_lower_limit}</param>
<param name="max">${joint5_upper_limit}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.14</param>
<param name="max">3.14</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<!-- <state_interface name="effort"/> -->
</joint>
<joint name="${prefix}joint6">
<command_interface name="position">
<param name="min">${joint6_lower_limit}</param>
<param name="max">${joint6_upper_limit}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.14</param>
<param name="max">3.14</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<!-- <state_interface name="effort"/> -->
</joint>
</ros2_control>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,75 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="xarm6_transmission"
params="prefix hard_interface:=EffortJointInterface reduction:=100">
<transmission name="${prefix}tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint1">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}motor1">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint2">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}motor2">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}tran3">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint3">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}motor3">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}tran4">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint4">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}motor3">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}tran5">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint5">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}motor5">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}tran6">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint6">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}motor6">
<hardwareInterface>hardware_interface/${hard_interface}</hardwareInterface>
<mechanicalReduction>${reduction}</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,335 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="xarm6_urdf" params="prefix
joint1_lower_limit:=${-2.0*pi} joint1_upper_limit:=${2.0*pi}
joint2_lower_limit:=${-2.059} joint2_upper_limit:=${2.0944}
joint3_lower_limit:=${-3.927} joint3_upper_limit:=${0.19198}
joint4_lower_limit:=${-2.0*pi} joint4_upper_limit:=${2.0*pi}
joint5_lower_limit:=${-1.69297} joint5_upper_limit:=${pi}
joint6_lower_limit:=${-2.0*pi} joint6_upper_limit:=${2.0*pi}">
<material name="${prefix}Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="${prefix}Red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="${prefix}White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<material name="${prefix}Silver">
<color rgba="0.753 0.753 0.753 1.0"/>
</material>
<link name="${prefix}link_base">
<visual>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/base.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/base.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${prefix}White" />
</visual>
<collision>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/base.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/base.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="0.0 0.0 0.09103" rpy="0 0 0" />
<mass value="2.7" />
<inertia
ixx="0.00494875"
ixy="-3.5E-06"
ixz="1.25E-05"
iyy="0.00494174"
iyz="1.67E-06"
izz="0.002219" />
</inertial>
</link>
<link name="${prefix}link1">
<visual>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link1.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link1.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${prefix}White" />
</visual>
<collision>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link1.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link1.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="-0.002 0.02692 -0.01332" rpy="0 0 0"/>
<mass value="2.16"/>
<inertia
ixx="0.00539427"
ixy="1.095E-05"
ixz="1.635E-06"
iyy="0.0048979"
iyz="0.000793"
izz="0.00311573"/>
</inertial>
</link>
<joint name="${prefix}joint1" type="revolute">
<parent link="${prefix}link_base"/>
<child link="${prefix}link1"/>
<origin xyz="0 0 0.267" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit
lower="${joint1_lower_limit}"
upper="${joint1_upper_limit}"
effort="50.0"
velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="${prefix}link2">
<visual>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link2.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link2.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${prefix}White" />
</visual>
<collision>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link2.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link2.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<origin
xyz="0.03531 -0.21398 0.03386"
rpy="0 0 0" />
<mass
value="1.71" />
<inertia
ixx="0.0248674"
ixy="-0.00430651"
ixz="-0.00067797"
iyy="0.00485548"
iyz="0.00457245"
izz="0.02387827" />
</inertial>
</link>
<joint name="${prefix}joint2" type="revolute">
<parent link="${prefix}link1"/>
<child link="${prefix}link2"/>
<origin xyz="0 0 0" rpy="-1.5708 0 0" />
<axis xyz="0 0 1"/>
<limit
lower="${joint2_lower_limit}"
upper="${joint2_upper_limit}"
effort="50.0"
velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="${prefix}link3">
<visual>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link3.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link3.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${prefix}White" />
</visual>
<collision>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link3.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link3.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<origin
xyz="0.06781 0.10749 0.01457"
rpy="0 0 0" />
<mass
value="1.384" />
<inertia
ixx="0.0053694"
ixy="0.0014185"
ixz="-0.00092094"
iyy="0.0032423"
iyz="-0.00169178"
izz="0.00501731" />
</inertial>
</link>
<joint name="${prefix}joint3" type="revolute">
<parent link="${prefix}link2"/>
<child link="${prefix}link3"/>
<origin xyz="0.0535 -0.2845 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit
lower="${joint3_lower_limit}"
upper="${joint3_upper_limit}"
effort="32.0"
velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="${prefix}link4">
<visual>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link4.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link4.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${prefix}White" />
</visual>
<collision>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link4.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link4.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="-0.00021 0.02578 -0.02538" rpy="0 0 0"/>
<mass value="1.115"/>
<inertia
ixx="0.00439263"
ixy="5.028E-05"
ixz="1.374E-05"
iyy="0.0040077"
iyz="0.00045338"
izz="0.00110321"/>
</inertial>
</link>
<joint name="${prefix}joint4" type="revolute">
<parent link="${prefix}link3"/>
<child link="${prefix}link4"/>
<origin xyz="0.0775 0.3425 0" rpy="-1.5708 0 0"/>
<axis xyz="0 0 1"/>
<limit
lower="${joint4_lower_limit}"
upper="${joint4_upper_limit}"
effort="32.0"
velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="${prefix}link5">
<visual>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link5.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link5.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${prefix}White" />
</visual>
<collision>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link5.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link5.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<origin
xyz="0.05428 0.01781 0.00543"
rpy="0 0 0" />
<mass
value="1.275" />
<inertia
ixx="0.001202758"
ixy="0.000492428"
ixz="-0.00039147"
iyy="0.0022876"
iyz="-1.235E-04"
izz="0.0026866" />
</inertial>
</link>
<joint name="${prefix}joint5" type="revolute">
<parent link="${prefix}link4"/>
<child link="${prefix}link5"/>
<origin xyz="0 0 0" rpy="1.5708 0 0"/>
<axis xyz="0 0 1"/>
<limit
lower="${joint5_lower_limit}"
upper="${joint5_upper_limit}"
effort="32.0"
velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="${prefix}link6">
<visual>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link6.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link6.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${prefix}Silver" />
</visual>
<collision>
<geometry>
<!-- <mesh filename="package://xarm_description/meshes/xarm6/visual/link6.stl"/> -->
<mesh filename="file:///$(find xarm_description)/meshes/xarm6/visual/link6.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<origin
xyz="0 0.00064 -0.00952"
rpy="0 0 0" />
<mass
value="0.1096" />
<inertia
ixx="4.5293E-05"
ixy="0"
ixz="0"
iyy="4.8111E-05"
iyz="0"
izz="7.9715E-05" />
</inertial>
</link>
<joint name="${prefix}joint6" type="revolute">
<parent link="${prefix}link5"/>
<child link="${prefix}link6"/>
<origin xyz="0.076 0.097 0" rpy="-1.5708 0 0"/>
<axis xyz="0 0 1"/>
<limit
lower="${joint6_lower_limit}"
upper="${joint6_upper_limit}"
effort="20.0"
velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<!-- <link name="${prefix}link_eef" />
<joint
name="${prefix}joint_eef"
type="fixed">
<origin
xyz="0 0 0"
rpy="0 0 0" />
<parent
link="${prefix}link6" />
<child
link="${prefix}link_eef" />
</joint> -->
</xacro:macro>
</robot>

View File

@@ -0,0 +1,67 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="xarm6" >
<xacro:macro name="xarm6_robot" params="prefix:='' namespace:='xarm' limited:='false' effort_control:='false'
velocity_control:='false' attach_to:='world' xyz:='0 0 0' rpy:='0 0 0' load_gazebo_plugin:='false'
ros2_control_plugin:='uf_robot_hardware/UFRobotSystemHardware' ros2_control_params:='' add_gripper:='false'
robot_ip:='' report_type:='normal' baud_checkset:='true' default_gripper_baud:=2000000 ">
<!-- include xarm6 relative macros: -->
<xacro:include filename="$(find xarm_description)/urdf/xarm6/xarm6.ros2_control.xacro" />
<xacro:include filename="$(find xarm_description)/urdf/xarm6/xarm6.urdf.xacro" />
<xacro:include filename="$(find xarm_description)/urdf/xarm6/xarm6.transmission.xacro" />
<xacro:include filename="$(find xarm_description)/urdf/xarm6/xarm6.gazebo.xacro" />
<!-- gazebo_plugin -->
<xacro:if value="${load_gazebo_plugin}">
<xacro:include filename="$(find xarm_description)/urdf/common/common.gazebo.xacro" />
<xacro:gazebo_ros_control_plugin prefix="${prefix}" ros2_control_params="${ros2_control_params}"/>
</xacro:if>
<!-- add one world link if no 'attach_to' specified -->
<xacro:if value="${attach_to == 'world'}">
<link name="world" />
</xacro:if>
<joint name="${prefix}world_joint" type="fixed">
<parent link="${attach_to}" />
<child link = "${prefix}link_base" />
<origin xyz="${xyz}" rpy="${rpy}" />
</joint>
<xacro:if value="${limited}">
<xacro:xarm6_ros2_control prefix="${prefix}"
velocity_control="${velocity_control}"
ros2_control_plugin="${ros2_control_plugin}"
hw_ns="${namespace}" add_gripper="${add_gripper}"
robot_ip="${robot_ip}" report_type="${report_type}"
baud_checkset="${baud_checkset}" default_gripper_baud="${default_gripper_baud}"
joint1_lower_limit="${-pi*0.99}" joint1_upper_limit="${pi*0.99}"
joint2_lower_limit="${-2.059}" joint2_upper_limit="${2.0944}"
joint3_lower_limit="${-pi*0.99}" joint3_upper_limit="${0.19198}"
joint4_lower_limit="${-pi*0.99}" joint4_upper_limit="${pi*0.99}"
joint5_lower_limit="${-1.69297}" joint5_upper_limit="${pi*0.99}"
joint6_lower_limit="${-pi*0.99}" joint6_upper_limit="${pi*0.99}"/>
<xacro:xarm6_urdf prefix="${prefix}"
joint1_lower_limit="${-pi*0.99}" joint1_upper_limit="${pi*0.99}"
joint2_lower_limit="${-2.059}" joint2_upper_limit="${2.0944}"
joint3_lower_limit="${-pi*0.99}" joint3_upper_limit="${0.19198}"
joint4_lower_limit="${-pi*0.99}" joint4_upper_limit="${pi*0.99}"
joint5_lower_limit="${-1.69297}" joint5_upper_limit="${pi*0.99}"
joint6_lower_limit="${-pi*0.99}" joint6_upper_limit="${pi*0.99}"/>
</xacro:if>
<xacro:unless value="${limited}">
<xacro:xarm6_ros2_control prefix="${prefix}" velocity_control="${velocity_control}"
ros2_control_plugin="${ros2_control_plugin}"
hw_ns="${namespace}" add_gripper="${add_gripper}"
robot_ip="${robot_ip}" report_type="${report_type}"
baud_checkset="${baud_checkset}" default_gripper_baud="${default_gripper_baud}" />
<xacro:xarm6_urdf prefix="${prefix}"/>
</xacro:unless>
<xacro:xarm6_transmission prefix="${prefix}" hard_interface="${'EffortJointInterface' if effort_control else 'VelocityJointInterface' if velocity_control else 'PositionJointInterface'}" />
<xacro:xarm6_gazebo prefix="${prefix}" />
</xacro:macro>
</robot>