customization ok in rviz
This commit is contained in:
parent
c821a60651
commit
5cbdf490ad
@ -52,7 +52,8 @@ according to your needs.
|
|||||||
### Software modifications
|
### Software modifications
|
||||||
Once the physical modification of the robotic arm has been completed, several files need to be updated to use ROS 2 with the new arm.
|
Once the physical modification of the robotic arm has been completed, several files need to be updated to use ROS 2 with the new arm.
|
||||||
The default arm name is `wx250s` and one will create a new arm configuration `wx250s_custom`. To do so:
|
The default arm name is `wx250s` and one will create a new arm configuration `wx250s_custom`. To do so:
|
||||||
1. Open the file `~/interbotix_ws/install/interbotix_xs_modules/lib/python3.10/site-packages/interbotix_xs_modules/xs_common/xs_common.py` and add `wx250_custom` to the `_XSARM_MODELS` tuple (near line 32).
|
1. Copy the file [/wx250s_custom/xs_common.py] to `~/interbotix_ws/install/interbotix_xs_modules/lib/python3.10/site-packages/interbotix_xs_modules/xs_common/xs_common.py`.
|
||||||
2. Copy the [/wx250s_custom](http://sekisushai.net/git/sekisushai/small/src/branch/master/wx250s_custom/wx250s_custom.urdf.xacro) to folder `~/interbotix_ws/install/interbotix_xsarm_descriptions/share/interbotix_xsarm_descriptions/urdf/`.
|
2. Copy the file [/wx250s_custom/wx250s_custom.urdf.xacro](http://sekisushai.net/git/sekisushai/small/src/branch/master/wx250s_custom/wx250s_custom.urdf.xacro) to `~/interbotix_ws/src/interbotix_ros_manipulators/interbotix_ros_xsarms/interbotix_xsarm_descriptions/urdf/`.
|
||||||
3. Open the file `wx250s_custom.urdf.xacro`
|
3. Copy the file [/wx250s_custom/wx250s_custom.yaml]() to `~/interbotix_ws/src/interbotix_ros_manipulators/interbotix_ros_xsarms/interbotix_xsarm_control/config/wx250s_custom.yaml`
|
||||||
|
4. Copy the folder [/wx250s_custom/wx259s_custom_meshes]() to `~/interbotix_ws/src/interbotix_ros_manipulators/interbotix_ros_xsarms/interbotix_xsarm_descriptions/meshes/`
|
||||||
|
10. Run command `colcon build` in folder `~/interbotix_ws/`
|
||||||
|
BIN
wx250s_custom/WidowX-250s.pdf
Normal file
BIN
wx250s_custom/WidowX-250s.pdf
Normal file
Binary file not shown.
700
wx250s_custom/wx250s_custom.urdf
Normal file
700
wx250s_custom/wx250s_custom.urdf
Normal file
@ -0,0 +1,700 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot name="wx250s_custom" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<material name="interbotix_black">
|
||||||
|
<texture filename="package://interbotix_xsarm_descriptions/meshes/interbotix_black.png"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="world"/>
|
||||||
|
<joint name="fixed" type="fixed">
|
||||||
|
<parent
|
||||||
|
link="world"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/base_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="wx250s_custom/base_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/base.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/base.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="-0.0380446000 0.0006138920 0.0193354000"/>
|
||||||
|
<mass value="0.538736"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0021150000"
|
||||||
|
iyy="0.0006921000"
|
||||||
|
izz="0.0025240000"
|
||||||
|
ixy="-0.0000163500"
|
||||||
|
ixz="0.0000006998"
|
||||||
|
iyz="0.0000464200"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="waist" type="revolute">
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit
|
||||||
|
effort="10"
|
||||||
|
lower="-3.141582653589793"
|
||||||
|
upper="3.141582653589793"
|
||||||
|
velocity="3.141592653589793"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0.072"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/base_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/shoulder_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/shoulder_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 -0.003"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/shoulder.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 -0.003"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/shoulder.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0.0000223482 0.0000414609 0.0066287000"/>
|
||||||
|
<mass value="0.480879"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0003790000"
|
||||||
|
iyy="0.0005557000"
|
||||||
|
izz="0.0005889000"
|
||||||
|
ixy="0.0000000022"
|
||||||
|
ixz="-0.0000003561"
|
||||||
|
iyz="0.0000012245"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="shoulder" type="revolute">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="20"
|
||||||
|
lower="-1.8849555921538759"
|
||||||
|
upper="-1.9896753472735356"
|
||||||
|
velocity="3.141592653589793"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0.03865"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/shoulder_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/upper_arm_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/upper_arm_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_arm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_arm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0.0171605000 0.0000002725 0.1913230000"/>
|
||||||
|
<mass value="0.430811"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0034630000"
|
||||||
|
iyy="0.0035870000"
|
||||||
|
izz="0.0004566000"
|
||||||
|
ixy="-0.0000000001"
|
||||||
|
ixz="-0.0000000002"
|
||||||
|
iyz="0.0004272000"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="elbow" type="revolute">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="15"
|
||||||
|
lower="-2.1467549799530254"
|
||||||
|
upper="1.605702911834783"
|
||||||
|
velocity="3.141592653589793"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.04975 0 0.25"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/upper_arm_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/upper_forearm_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/upper_forearm_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.1079630000 0.0001158760 0"/>
|
||||||
|
<mass value="0.234589"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000397100"
|
||||||
|
iyy="0.0008878000"
|
||||||
|
izz="0.0008880000"
|
||||||
|
ixy="0.0000023528"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="forearm_roll" type="revolute">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit
|
||||||
|
effort="2"
|
||||||
|
lower="-3.141582653589793"
|
||||||
|
upper="3.141582653589793"
|
||||||
|
velocity="3.141592653589793"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.175 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/upper_forearm_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/lower_forearm_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/lower_forearm_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="3.141592653589793 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/lower_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="3.141592653589793 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/lower_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="3.141592653589793 0 0"
|
||||||
|
xyz="0.0374395000 0.0052225200 0"/>
|
||||||
|
<mass value="0.220991"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000636900"
|
||||||
|
iyy="0.0001677000"
|
||||||
|
izz="0.0001834000"
|
||||||
|
ixy="-0.0000229200"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="wrist_angle" type="revolute">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="5"
|
||||||
|
lower="-1.7453292519943295"
|
||||||
|
upper="2.1467549799530254"
|
||||||
|
velocity="3.141592653589793"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.075 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/lower_forearm_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/wrist_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/wrist_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/wrist.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/wrist.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0.0423600000 -0.0000106630 0.0105770000"/>
|
||||||
|
<mass value="0.084957"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000308200"
|
||||||
|
iyy="0.0000282200"
|
||||||
|
izz="0.0000315200"
|
||||||
|
ixy="0.0000000191"
|
||||||
|
ixz="0.0000000023"
|
||||||
|
iyz="0.0000025481"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Include the gripper if used -->
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<joint name="wrist_rotate" type="revolute">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit
|
||||||
|
effort="1"
|
||||||
|
lower="-3.141582653589793"
|
||||||
|
upper="3.141582653589793"
|
||||||
|
velocity="3.141592653589793"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.065 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/wrist_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/gripper_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/gripper_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="-0.02 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="-0.02 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0.0216310000 0.0000002516 0.0114100000"/>
|
||||||
|
<mass value="0.072885"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000253700"
|
||||||
|
iyy="0.0000183600"
|
||||||
|
izz="0.0000167400"
|
||||||
|
ixy="0.0000000000"
|
||||||
|
ixz="0.0000000000"
|
||||||
|
iyz="0.0000004340"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="ee_arm" type="fixed">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.043 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/gripper_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/ee_arm_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/ee_arm_link">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.001"
|
||||||
|
iyy="0.001"
|
||||||
|
izz="0.001"
|
||||||
|
ixy="0"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="gripper" type="continuous">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit
|
||||||
|
effort="1"
|
||||||
|
velocity="3.141592653589793"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.0055 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/ee_arm_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/gripper_prop_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/gripper_prop_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="-0.0685 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_prop.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="-0.0685 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_prop.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0.0008460000 -0.0000016817 0.0000420000"/>
|
||||||
|
<mass value="0.00434"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000005923"
|
||||||
|
iyy="0.0000011156"
|
||||||
|
izz="0.0000005743"
|
||||||
|
ixy="0.0000000000"
|
||||||
|
ixz="0.0000003195"
|
||||||
|
iyz="-0.0000000004"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- If the AR tag is being used, then add the AR tag mount -->
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<!-- If the gripper bar is being used, then also add the gripper bar -->
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<joint name="gripper_bar" type="fixed">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/ee_arm_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/gripper_bar_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/gripper_bar_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="-0.063 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_bar.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="-0.063 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_bar.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 1.5707963267948966"
|
||||||
|
xyz="0.0096870000 0.0000008177 0.0049620000"/>
|
||||||
|
<mass value="0.034199"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000074125"
|
||||||
|
iyy="0.0000284300"
|
||||||
|
izz="0.0000286000"
|
||||||
|
ixy="-0.0000000008"
|
||||||
|
ixz="-0.0000000006"
|
||||||
|
iyz="-0.0000013889"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="ee_bar" type="fixed">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.023 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/gripper_bar_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/fingers_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/fingers_link">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.001"
|
||||||
|
iyy="0.001"
|
||||||
|
izz="0.001"
|
||||||
|
ixy="0"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- If the gripper fingers are being used, add those as well -->
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<joint name="left_finger" type="prismatic">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="5"
|
||||||
|
lower="0.015"
|
||||||
|
upper="0.037"
|
||||||
|
velocity="1"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/fingers_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/left_finger_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/left_finger_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="3.141592653589793 3.141592653589793 0"
|
||||||
|
xyz="0 0.005 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_finger.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="3.141592653589793 3.141592653589793 0"
|
||||||
|
xyz="0 0.005 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_finger.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="3.141592653589793 3.141592653589793 1.5707963267948966"
|
||||||
|
xyz="0.0138160000 0.0000000000 0.0000000000"/>
|
||||||
|
<mass value="0.016246"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000047310"
|
||||||
|
iyy="0.0000015506"
|
||||||
|
izz="0.0000037467"
|
||||||
|
ixy="-0.0000004560"
|
||||||
|
ixz="0.0000000000"
|
||||||
|
iyz="0.0000000000"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="right_finger" type="prismatic">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="5"
|
||||||
|
lower="-0.037"
|
||||||
|
upper="-0.015"
|
||||||
|
velocity="1"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/fingers_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/right_finger_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
|
||||||
|
<mimic
|
||||||
|
joint="left_finger"
|
||||||
|
multiplier="-1"
|
||||||
|
offset="0"/>
|
||||||
|
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/right_finger_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 3.141592653589793 0"
|
||||||
|
xyz="0 -0.005 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_finger.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 3.141592653589793 0"
|
||||||
|
xyz="0 -0.005 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/gripper_finger.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 3.141592653589793 1.5707963267948966"
|
||||||
|
xyz="0.0138160000 0.0000000000 0.0000000000"/>
|
||||||
|
<mass value="0.016246"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000047310"
|
||||||
|
iyy="0.0000015506"
|
||||||
|
izz="0.0000037467"
|
||||||
|
ixy="0.0000004560"
|
||||||
|
ixz="0.0000000000"
|
||||||
|
iyz="0.0000000000"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="ee_gripper" type="fixed">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.128 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="wx250s_custom/fingers_link"/>
|
||||||
|
<child
|
||||||
|
link="wx250s_custom/ee_gripper_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="wx250s_custom/ee_gripper_link">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.001"
|
||||||
|
iyy="0.001"
|
||||||
|
izz="0.001"
|
||||||
|
ixy="0"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
</robot>
|
501
wx250s_custom/wx250s_custom.urdf.xacro
Normal file
501
wx250s_custom/wx250s_custom.urdf.xacro
Normal file
@ -0,0 +1,501 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot name="wx250s_custom" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:property name="robot_model"
|
||||||
|
value="wx250s_custom"
|
||||||
|
scope="global"/>
|
||||||
|
<xacro:property name="dof"
|
||||||
|
value="6"
|
||||||
|
scope="global"/>
|
||||||
|
|
||||||
|
<xacro:arg name="robot_name" default="${robot_model}"/>
|
||||||
|
<xacro:arg name="base_link_frame" default="base_link"/>
|
||||||
|
<xacro:arg name="use_world_frame" default="true"/>
|
||||||
|
<xacro:arg name="external_urdf_loc" default=""/>
|
||||||
|
<xacro:arg name="hardware_type" default="actual"/>
|
||||||
|
|
||||||
|
<xacro:property name="mesh_directory" value="package://interbotix_xsarm_descriptions/meshes/${robot_model}_meshes"/>
|
||||||
|
<xacro:property name="urdf_loc" value="$(arg external_urdf_loc)"/>
|
||||||
|
<xacro:property name="hardware_type" value="$(arg hardware_type)"/>
|
||||||
|
<xacro:property name="pi_offset" value="0.00001"/>
|
||||||
|
|
||||||
|
<xacro:property name="waist_limit_effort" value="10"/>
|
||||||
|
<xacro:property name="waist_limit_lower" value="${-pi + pi_offset}"/>
|
||||||
|
<xacro:property name="waist_limit_upper" value="${pi - pi_offset}"/>
|
||||||
|
<xacro:property name="waist_limit_vel" value="${pi}"/>
|
||||||
|
|
||||||
|
<xacro:property name="shoulder_limit_effort" value="100"/><!-- 20 -->
|
||||||
|
<xacro:property name="shoulder_limit_lower" value="${radians(-108)}"/>
|
||||||
|
<xacro:property name="shoulder_limit_upper" value="${radians(114)}"/>
|
||||||
|
<xacro:property name="shoulder_limit_vel" value="${pi}"/>
|
||||||
|
|
||||||
|
<xacro:property name="elbow_limit_effort" value="15"/>
|
||||||
|
<xacro:property name="elbow_limit_lower" value="${radians(-123)}"/>
|
||||||
|
<xacro:property name="elbow_limit_upper" value="${radians(92)}"/>
|
||||||
|
<xacro:property name="elbow_limit_vel" value="${pi}"/>
|
||||||
|
|
||||||
|
<xacro:property name="forearm_roll_limit_effort" value="2"/>
|
||||||
|
<xacro:property name="forearm_roll_limit_lower" value="${-pi + pi_offset}"/>
|
||||||
|
<xacro:property name="forearm_roll_limit_upper" value="${pi - pi_offset}"/>
|
||||||
|
<xacro:property name="forearm_roll_limit_vel" value="${pi}"/>
|
||||||
|
|
||||||
|
<xacro:property name="wrist_angle_limit_effort" value="5"/>
|
||||||
|
<xacro:property name="wrist_angle_limit_lower" value="${radians(-100)}"/>
|
||||||
|
<xacro:property name="wrist_angle_limit_upper" value="${radians(123)}"/>
|
||||||
|
<xacro:property name="wrist_angle_limit_vel" value="${pi}"/>
|
||||||
|
|
||||||
|
<xacro:property name="wrist_rotate_limit_effort" value="1"/>
|
||||||
|
<xacro:property name="wrist_rotate_limit_lower" value="${-pi + pi_offset}"/>
|
||||||
|
<xacro:property name="wrist_rotate_limit_upper" value="${pi - pi_offset}"/>
|
||||||
|
<xacro:property name="wrist_rotate_limit_vel" value="${pi}"/>
|
||||||
|
|
||||||
|
<xacro:property name="gripper_limit_vel" value="${pi}"/>
|
||||||
|
|
||||||
|
<xacro:property name="finger_limit_effort" value="5"/>
|
||||||
|
<xacro:property name="finger_limit_lower" value="0.015"/>
|
||||||
|
<xacro:property name="finger_limit_upper" value="0.037"/>
|
||||||
|
<xacro:property name="finger_limit_vel" value="1"/>
|
||||||
|
|
||||||
|
<material name="interbotix_black">
|
||||||
|
<texture filename="package://interbotix_xsarm_descriptions/meshes/interbotix_black.png"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<xacro:if value="$(arg use_world_frame)">
|
||||||
|
<link name="world"/>
|
||||||
|
<joint name="fixed" type="fixed">
|
||||||
|
<parent
|
||||||
|
link="world"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/$(arg base_link_frame)"/>
|
||||||
|
</joint>
|
||||||
|
</xacro:if> <!-- use_world_frame -->
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/$(arg base_link_frame)">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/base.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/base.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="-0.0380446000 0.0006138920 0.0193354000"/>
|
||||||
|
<mass value="0.538736"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0021150000"
|
||||||
|
iyy="0.0006921000"
|
||||||
|
izz="0.0025240000"
|
||||||
|
ixy="-0.0000163500"
|
||||||
|
ixz="0.0000006998"
|
||||||
|
iyz="0.0000464200"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="waist" type="revolute">
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit
|
||||||
|
effort="${waist_limit_effort}"
|
||||||
|
lower="${waist_limit_lower}"
|
||||||
|
upper="${waist_limit_upper}"
|
||||||
|
velocity="${waist_limit_vel}"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0.072"/>
|
||||||
|
<parent
|
||||||
|
link="$(arg robot_name)/$(arg base_link_frame)"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/shoulder_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/shoulder_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 -0.003"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/shoulder.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 -0.003"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/shoulder.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0.0000223482 0.0000414609 0.0066287000"/>
|
||||||
|
<mass value="0.480879"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0003790000"
|
||||||
|
iyy="0.0005557000"
|
||||||
|
izz="0.0005889000"
|
||||||
|
ixy="0.0000000022"
|
||||||
|
ixz="-0.0000003561"
|
||||||
|
iyz="0.0000012245"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="shoulder" type="revolute">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="${shoulder_limit_effort}"
|
||||||
|
lower="${shoulder_limit_lower}"
|
||||||
|
upper="${shoulder_limit_upper}"
|
||||||
|
velocity="${shoulder_limit_vel}"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0.03865"/>
|
||||||
|
<parent
|
||||||
|
link="$(arg robot_name)/shoulder_link"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/upper_arm_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/upper_arm_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_arm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_arm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0.0171605000 0.0000002725 0.1913230000"/>
|
||||||
|
<mass value="0.430811"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0034630000"
|
||||||
|
iyy="0.0035870000"
|
||||||
|
izz="0.0004566000"
|
||||||
|
ixy="-0.0000000001"
|
||||||
|
ixz="-0.0000000002"
|
||||||
|
iyz="0.0004272000"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="elbow" type="revolute">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="${elbow_limit_effort}"
|
||||||
|
lower="${elbow_limit_lower}"
|
||||||
|
upper="${elbow_limit_upper}"
|
||||||
|
velocity="${elbow_limit_vel}"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.04975 0 0.25"/>
|
||||||
|
<parent
|
||||||
|
link="$(arg robot_name)/upper_arm_link"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/upper_forearm_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/upper_forearm_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/upper_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.1079630000 0.0001158760 0"/>
|
||||||
|
<mass value="0.234589"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000397100"
|
||||||
|
iyy="0.0008878000"
|
||||||
|
izz="0.0008880000"
|
||||||
|
ixy="0.0000023528"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="forearm_roll" type="revolute">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit
|
||||||
|
effort="${forearm_roll_limit_effort}"
|
||||||
|
lower="${forearm_roll_limit_lower}"
|
||||||
|
upper="${forearm_roll_limit_upper}"
|
||||||
|
velocity="${forearm_roll_limit_vel}"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.175 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="$(arg robot_name)/upper_forearm_link"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/lower_forearm_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/lower_forearm_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="${pi} 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/lower_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="${pi} 0 0"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/lower_forearm.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="${pi} 0 0"
|
||||||
|
xyz="0.0374395000 0.0052225200 0"/>
|
||||||
|
<mass value="0.220991"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000636900"
|
||||||
|
iyy="0.0001677000"
|
||||||
|
izz="0.0001834000"
|
||||||
|
ixy="-0.0000229200"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="wrist_angle" type="revolute">
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit
|
||||||
|
effort="${wrist_angle_limit_effort}"
|
||||||
|
lower="${wrist_angle_limit_lower}"
|
||||||
|
upper="${wrist_angle_limit_upper}"
|
||||||
|
velocity="${wrist_angle_limit_vel}"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.075 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="$(arg robot_name)/lower_forearm_link"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/wrist_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/wrist_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/wrist.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/wrist.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0.0423600000 -0.0000106630 0.0105770000"/>
|
||||||
|
<mass value="0.084957"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000308200"
|
||||||
|
iyy="0.0000282200"
|
||||||
|
izz="0.0000315200"
|
||||||
|
ixy="0.0000000191"
|
||||||
|
ixz="0.0000000023"
|
||||||
|
iyz="0.0000025481"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="wrist_rotate" type="revolute">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit
|
||||||
|
effort="${wrist_rotate_limit_effort}"
|
||||||
|
lower="${wrist_rotate_limit_lower}"
|
||||||
|
upper="${wrist_rotate_limit_upper}"
|
||||||
|
velocity="${wrist_rotate_limit_vel}"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.065 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="$(arg robot_name)/wrist_link"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/sma_attach_link"/>
|
||||||
|
<dynamics
|
||||||
|
friction="0.1"
|
||||||
|
damping="0.1"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/sma_attach_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0.007 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/attach.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="interbotix_black"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0.007 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/attach.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0.0216310000 0.0000002516 0.0114100000"/>
|
||||||
|
<mass value="0.072885"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.0000253700"
|
||||||
|
iyy="0.0000183600"
|
||||||
|
izz="0.0000167400"
|
||||||
|
ixy="0.0000000000"
|
||||||
|
ixz="0.0000000000"
|
||||||
|
iyz="0.0000004340"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="sma" type="fixed">
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 0"
|
||||||
|
xyz="0.128 0 0"/>
|
||||||
|
<parent
|
||||||
|
link="$(arg robot_name)/sma_attach_link"/>
|
||||||
|
<child
|
||||||
|
link="$(arg robot_name)/sma_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="$(arg robot_name)/sma_link">
|
||||||
|
<visual>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/sma.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin
|
||||||
|
rpy="0 0 ${pi/2}"
|
||||||
|
xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="${mesh_directory}/sma.stl"
|
||||||
|
scale="0.001 0.001 0.001"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.1"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.001"
|
||||||
|
iyy="0.001"
|
||||||
|
izz="0.001"
|
||||||
|
ixy="0"
|
||||||
|
ixz="0"
|
||||||
|
iyz="0"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<xacro:include filename="$(find interbotix_xsarm_descriptions)/urdf/control.urdf.xacro"/>
|
||||||
|
<xacro:include filename="$(find interbotix_xsarm_descriptions)/urdf/gazebo_configs.urdf.xacro"/>
|
||||||
|
|
||||||
|
<xacro:if value="${hardware_type == 'gz_classic'}">
|
||||||
|
<xacro:gazebo_configs/>
|
||||||
|
</xacro:if>
|
||||||
|
|
||||||
|
<xacro:if value="${urdf_loc != ''}">
|
||||||
|
<xacro:include filename="${urdf_loc}"/>
|
||||||
|
</xacro:if>
|
||||||
|
|
||||||
|
</robot>
|
104
wx250s_custom/wx250s_custom.yaml
Normal file
104
wx250s_custom/wx250s_custom.yaml
Normal file
@ -0,0 +1,104 @@
|
|||||||
|
port: /dev/ttyDXL
|
||||||
|
|
||||||
|
joint_order: [waist, shoulder, elbow, forearm_roll, wrist_angle, wrist_rotate]
|
||||||
|
sleep_positions: [0, -1.80, 1.55, 0, 0.8, 0]
|
||||||
|
|
||||||
|
joint_state_publisher:
|
||||||
|
update_rate: 100
|
||||||
|
publish_states: true
|
||||||
|
topic_name: joint_states
|
||||||
|
|
||||||
|
groups:
|
||||||
|
arm: [waist, shoulder, elbow, forearm_roll, wrist_angle, wrist_rotate]
|
||||||
|
|
||||||
|
shadows:
|
||||||
|
shoulder:
|
||||||
|
shadow_list: [shoulder_shadow]
|
||||||
|
calibrate: true
|
||||||
|
elbow:
|
||||||
|
shadow_list: [elbow_shadow]
|
||||||
|
calibrate: true
|
||||||
|
|
||||||
|
sisters:
|
||||||
|
|
||||||
|
motors:
|
||||||
|
waist:
|
||||||
|
ID: 1
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 0
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 0
|
||||||
|
Max_Position_Limit: 4095
|
||||||
|
Secondary_ID: 255
|
||||||
|
|
||||||
|
shoulder:
|
||||||
|
ID: 2
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 0
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 819
|
||||||
|
Max_Position_Limit: 3345
|
||||||
|
Secondary_ID: 255
|
||||||
|
|
||||||
|
shoulder_shadow:
|
||||||
|
ID: 3
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 1
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 819
|
||||||
|
Max_Position_Limit: 3345
|
||||||
|
Secondary_ID: 2
|
||||||
|
|
||||||
|
elbow:
|
||||||
|
ID: 4
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 0
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 648
|
||||||
|
Max_Position_Limit: 3094
|
||||||
|
Secondary_ID: 255
|
||||||
|
|
||||||
|
elbow_shadow:
|
||||||
|
ID: 5
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 1
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 648
|
||||||
|
Max_Position_Limit: 3094
|
||||||
|
Secondary_ID: 4
|
||||||
|
|
||||||
|
forearm_roll:
|
||||||
|
ID: 6
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 0
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 0
|
||||||
|
Max_Position_Limit: 4095
|
||||||
|
Secondary_ID: 255
|
||||||
|
|
||||||
|
wrist_angle:
|
||||||
|
ID: 7
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 1
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 910
|
||||||
|
Max_Position_Limit: 3447
|
||||||
|
Secondary_ID: 255
|
||||||
|
|
||||||
|
wrist_rotate:
|
||||||
|
ID: 8
|
||||||
|
Baud_Rate: 3
|
||||||
|
Return_Delay_Time: 0
|
||||||
|
Drive_Mode: 0
|
||||||
|
Velocity_Limit: 131
|
||||||
|
Min_Position_Limit: 0
|
||||||
|
Max_Position_Limit: 4095
|
||||||
|
Secondary_ID: 255
|
||||||
|
|
@ -2,6 +2,8 @@ include <../cad/threads.scad>;
|
|||||||
|
|
||||||
$fn=128;
|
$fn=128;
|
||||||
|
|
||||||
|
rotate([90,0,0])
|
||||||
|
translate([-28.5/2,-46.5/2+11,0])
|
||||||
difference(){
|
difference(){
|
||||||
union(){
|
union(){
|
||||||
linear_extrude(4)
|
linear_extrude(4)
|
||||||
|
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/attach.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/attach.stl
Normal file
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/base.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/base.stl
Normal file
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/lower_forearm.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/lower_forearm.stl
Normal file
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/shoulder.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/shoulder.stl
Normal file
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/sma.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/sma.stl
Normal file
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/upper_arm.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/upper_arm.stl
Normal file
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/upper_forearm.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/upper_forearm.stl
Normal file
Binary file not shown.
BIN
wx250s_custom/wx250s_custom_meshes/wrist.stl
Normal file
BIN
wx250s_custom/wx250s_custom_meshes/wrist.stl
Normal file
Binary file not shown.
88
wx250s_custom/xs_common.py
Normal file
88
wx250s_custom/xs_common.py
Normal file
@ -0,0 +1,88 @@
|
|||||||
|
# Copyright 2022 Trossen Robotics
|
||||||
|
#
|
||||||
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
# modification, are permitted provided that the following conditions are met:
|
||||||
|
#
|
||||||
|
# * Redistributions of source code must retain the above copyright
|
||||||
|
# notice, this list of conditions and the following disclaimer.
|
||||||
|
#
|
||||||
|
# * Redistributions in binary form must reproduce the above copyright
|
||||||
|
# notice, this list of conditions and the following disclaimer in the
|
||||||
|
# documentation and/or other materials provided with the distribution.
|
||||||
|
#
|
||||||
|
# * Neither the name of the copyright holder nor the names of its
|
||||||
|
# contributors may be used to endorse or promote products derived from
|
||||||
|
# this software without specific prior written permission.
|
||||||
|
#
|
||||||
|
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||||
|
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
||||||
|
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||||
|
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||||
|
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||||
|
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||||
|
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
# POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
|
||||||
|
from typing import List, Tuple
|
||||||
|
|
||||||
|
# Tuple of valid Interbotix X-Series arm models
|
||||||
|
_XSARM_MODELS = (
|
||||||
|
'px100',
|
||||||
|
'px150',
|
||||||
|
'rx150',
|
||||||
|
'rx200',
|
||||||
|
'wx200',
|
||||||
|
'wx250',
|
||||||
|
'wx250s',
|
||||||
|
'wx250s_custom',
|
||||||
|
'vx250',
|
||||||
|
'vx300',
|
||||||
|
'vx300s',
|
||||||
|
'mobile_px100',
|
||||||
|
'mobile_wx200',
|
||||||
|
'mobile_wx250s',
|
||||||
|
)
|
||||||
|
|
||||||
|
# Tuple of valid Interbotix LoCoBot models
|
||||||
|
_XSLOCOBOT_MODELS = (
|
||||||
|
'locobot_base',
|
||||||
|
'locobot_px100',
|
||||||
|
'locobot_wx200',
|
||||||
|
'locobot_wx250s',
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
def get_interbotix_xsarm_models() -> Tuple[str]:
|
||||||
|
"""Get the tuple of valid Interbotix X-Series arm models."""
|
||||||
|
return _XSARM_MODELS
|
||||||
|
|
||||||
|
|
||||||
|
def get_interbotix_xslocobot_models() -> Tuple[str]:
|
||||||
|
"""Get the tuple of valid Interbotix LoCoBot models."""
|
||||||
|
return _XSLOCOBOT_MODELS
|
||||||
|
|
||||||
|
|
||||||
|
def get_interbotix_xsarm_joints(robot_model: str) -> List[str]:
|
||||||
|
"""
|
||||||
|
Return a list of joints in the robot_model.
|
||||||
|
|
||||||
|
:param robot_model: The robot model to get the joints of
|
||||||
|
:return: A list of joint names of the given robot model
|
||||||
|
:raises: KeyError if the robot model is not valid
|
||||||
|
"""
|
||||||
|
if robot_model in ('mobile_px100', 'px100'):
|
||||||
|
return ['waist', 'shoulder', 'elbow', 'wrist_angle', 'left_finger']
|
||||||
|
elif robot_model in ('px150', 'rx150', 'rx200', 'wx200', 'wx250', 'vx250', 'vx300'):
|
||||||
|
return ['waist', 'shoulder', 'elbow', 'wrist_angle', 'wrist_rotate', 'left_finger']
|
||||||
|
elif robot_model in ('wx250s_custom'):
|
||||||
|
return ['waist', 'shoulder', 'elbow', 'forearm_roll', 'wrist_angle', 'wrist_rotate']
|
||||||
|
elif robot_model in ('mobile_wx250s', 'wx250s', 'vx300s'):
|
||||||
|
return [
|
||||||
|
'waist', 'shoulder', 'elbow', 'forearm_roll',
|
||||||
|
'wrist_angle', 'wrist_rotate', 'left_finger'
|
||||||
|
]
|
||||||
|
else:
|
||||||
|
raise KeyError(f'{robot_model} is not a valid robot model.')
|
Loading…
Reference in New Issue
Block a user