Add custom xarm packages
This commit is contained in:
36
src/custom_xarm_description/urdf/lite6/lite6.gazebo.xacro
Executable file
36
src/custom_xarm_description/urdf/lite6/lite6.gazebo.xacro
Executable file
@@ -0,0 +1,36 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="lite6_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>
|
||||
110
src/custom_xarm_description/urdf/lite6/lite6.ros2_control.xacro
Executable file
110
src/custom_xarm_description/urdf/lite6/lite6.ros2_control.xacro
Executable file
@@ -0,0 +1,110 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<xacro:macro name="lite6_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.61799} joint2_upper_limit:=${2.61799}
|
||||
joint3_lower_limit:=${-0.061087} joint3_upper_limit:=${5.235988}
|
||||
joint4_lower_limit:=${-2.0*pi} joint4_upper_limit:=${2.0*pi}
|
||||
joint5_lower_limit:=${-2.1642} joint5_upper_limit:=${2.1642}
|
||||
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">lite</param>
|
||||
<param name="add_gripper">${add_gripper}</param>
|
||||
</xacro:if>
|
||||
</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>
|
||||
75
src/custom_xarm_description/urdf/lite6/lite6.transmission.xacro
Executable file
75
src/custom_xarm_description/urdf/lite6/lite6.transmission.xacro
Executable file
@@ -0,0 +1,75 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="lite6_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>
|
||||
367
src/custom_xarm_description/urdf/lite6/lite6.urdf.xacro
Executable file
367
src/custom_xarm_description/urdf/lite6/lite6.urdf.xacro
Executable file
@@ -0,0 +1,367 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<xacro:macro name="lite6_urdf" params="prefix
|
||||
joint1_lower_limit:=${-2.0*pi} joint1_upper_limit:=${2.0*pi}
|
||||
joint2_lower_limit:=${-2.61799} joint2_upper_limit:=${2.61799}
|
||||
joint3_lower_limit:=${-0.061087} joint3_upper_limit:=${5.235988}
|
||||
joint4_lower_limit:=${-2.0*pi} joint4_upper_limit:=${2.0*pi}
|
||||
joint5_lower_limit:=${-2.1642} joint5_upper_limit:=${2.1642}
|
||||
joint6_lower_limit:=${-2.0*pi} joint6_upper_limit:=${2.0*pi}">
|
||||
|
||||
<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">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.00829544579053192 3.26357432323433E-05 0.0631194584987089"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.65393501783165" />
|
||||
<inertia
|
||||
ixx="0"
|
||||
ixy="0"
|
||||
ixz="0"
|
||||
iyy="0"
|
||||
iyz="0"
|
||||
izz="0" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/base.stl"/>
|
||||
</geometry>
|
||||
<material name="${prefix}White" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/base.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="${prefix}link1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.00036 0.03788 -0.0027"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.169" />
|
||||
<inertia
|
||||
ixx="1.45164E-03"
|
||||
ixy="1.24E-05"
|
||||
ixz="-6.7E-06"
|
||||
iyy="8.873E-04"
|
||||
iyz="1.255E-04"
|
||||
izz="1.31993E-03" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link1.stl"/>
|
||||
</geometry>
|
||||
<material name="${prefix}White" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link1.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="${prefix}joint1" type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0.2435"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="${prefix}link_base" />
|
||||
<child
|
||||
link="${prefix}link1" />
|
||||
<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">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.178 0.0 0.0576"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.192" />
|
||||
<inertia
|
||||
ixx="1.5854E-03"
|
||||
ixy="-6.766E-06"
|
||||
ixz="-1.15136E-03"
|
||||
iyy="5.6097E-03"
|
||||
iyz="1.14E-06"
|
||||
izz="4.85E-03" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link2.stl"/>
|
||||
</geometry>
|
||||
<material name="${prefix}White" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link2.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="${prefix}joint2" type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="1.5708 -1.5708 3.1416" />
|
||||
<parent
|
||||
link="${prefix}link1" />
|
||||
<child
|
||||
link="${prefix}link2" />
|
||||
<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">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.07285 -0.030 -0.0009"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.930" />
|
||||
<inertia
|
||||
ixx="8.861E-04"
|
||||
ixy="-3.9287E-04"
|
||||
ixz="7.066E-05"
|
||||
iyy="1.5785E-03"
|
||||
iyz="-2.445E-05"
|
||||
izz="1.84677E-03" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link3.stl"/>
|
||||
</geometry>
|
||||
<material name="${prefix}White" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link3.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="${prefix}joint3" type="revolute">
|
||||
<origin
|
||||
xyz="0.2002 0 0"
|
||||
rpy="-3.1416 0 1.5708" />
|
||||
<parent
|
||||
link="${prefix}link2" />
|
||||
<child
|
||||
link="${prefix}link3" />
|
||||
<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">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0004 -0.0275 -0.0817"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.31" />
|
||||
<inertia
|
||||
ixx="3.705E-03"
|
||||
ixy="-2.0E-06"
|
||||
ixz="7.17E-06"
|
||||
iyy="3.0455E-03"
|
||||
iyz="-9.3188E-04"
|
||||
izz="1.5413E-03" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link4.stl"/>
|
||||
</geometry>
|
||||
<material name="${prefix}White" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link4.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="${prefix}joint4" type="revolute">
|
||||
<origin
|
||||
xyz="0.087 -0.22761 0"
|
||||
rpy="1.5708 0 0" />
|
||||
<parent
|
||||
link="${prefix}link3" />
|
||||
<child
|
||||
link="${prefix}link4" />
|
||||
<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">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0 0.010 0.0019"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.784" />
|
||||
<inertia
|
||||
ixx="5.668E-04"
|
||||
ixy="6E-07"
|
||||
ixz="-5.3E-06"
|
||||
iyy="5.077E-04"
|
||||
iyz="-4.8E-07"
|
||||
izz="5.3E-04" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link5.stl"/>
|
||||
</geometry>
|
||||
<material name="${prefix}White" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link5.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="${prefix}joint5" type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="1.5708 0 0" />
|
||||
<parent
|
||||
link="${prefix}link4" />
|
||||
<child
|
||||
link="${prefix}link5" />
|
||||
<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">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0 -0.00194 -0.0102"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.180" />
|
||||
<inertia
|
||||
ixx="7.726E-05"
|
||||
ixy="1E-06"
|
||||
ixz="4E-07"
|
||||
iyy="8.5665E-05"
|
||||
iyz="-6E-07"
|
||||
izz="1.4814E-04" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link6.stl"/>
|
||||
</geometry>
|
||||
<material name="${prefix}Silver" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file:///$(find xarm_description)/meshes/lite6/visual/link6.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="${prefix}joint6" type="revolute">
|
||||
<origin
|
||||
xyz="0 0.0625 0"
|
||||
rpy="-1.5708 0 0" />
|
||||
<parent
|
||||
link="${prefix}link5" />
|
||||
<child
|
||||
link="${prefix}link6" />
|
||||
<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>
|
||||
67
src/custom_xarm_description/urdf/lite6/lite6_robot_macro.xacro
Executable file
67
src/custom_xarm_description/urdf/lite6/lite6_robot_macro.xacro
Executable file
@@ -0,0 +1,67 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="lite6" >
|
||||
<xacro:macro name="lite6_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 lite6 relative macros: -->
|
||||
<xacro:include filename="$(find xarm_description)/urdf/lite6/lite6.ros2_control.xacro" />
|
||||
<xacro:include filename="$(find xarm_description)/urdf/lite6/lite6.urdf.xacro" />
|
||||
<xacro:include filename="$(find xarm_description)/urdf/lite6/lite6.transmission.xacro" />
|
||||
<xacro:include filename="$(find xarm_description)/urdf/lite6/lite6.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:lite6_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}" joint1_upper_limit="${pi}"
|
||||
joint2_lower_limit="${-2.61799}" joint2_upper_limit="${2.61799}"
|
||||
joint3_lower_limit="${-0.061087}" joint3_upper_limit="${5.235988}"
|
||||
joint4_lower_limit="${-pi}" joint4_upper_limit="${pi}"
|
||||
joint5_lower_limit="${-2.1642}" joint5_upper_limit="${2.1642}"
|
||||
joint6_lower_limit="${-pi}" joint6_upper_limit="${pi}"/>
|
||||
<xacro:lite6_urdf prefix="${prefix}"
|
||||
joint1_lower_limit="${-pi}" joint1_upper_limit="${pi}"
|
||||
joint2_lower_limit="${-2.61799}" joint2_upper_limit="${2.61799}"
|
||||
joint3_lower_limit="${-0.061087}" joint3_upper_limit="${5.235988}"
|
||||
joint4_lower_limit="${-pi}" joint4_upper_limit="${pi}"
|
||||
joint5_lower_limit="${-2.1642}" joint5_upper_limit="${2.1642}"
|
||||
joint6_lower_limit="${-pi}" joint6_upper_limit="${pi}"/>
|
||||
</xacro:if>
|
||||
<xacro:unless value="${limited}">
|
||||
<xacro:lite6_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:lite6_urdf prefix="${prefix}"/>
|
||||
</xacro:unless>
|
||||
|
||||
<xacro:lite6_transmission prefix="${prefix}" hard_interface="${'EffortJointInterface' if effort_control else 'VelocityJointInterface' if velocity_control else 'PositionJointInterface'}" />
|
||||
|
||||
<xacro:lite6_gazebo prefix="${prefix}" />
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
Reference in New Issue
Block a user