robot customization in one script!
This commit is contained in:
parent
5cbdf490ad
commit
028279998c
22
README.md
22
README.md
@ -50,10 +50,18 @@ By default, it allows to hold a M6 threaded rod aligned with the wrist rotation
|
||||
according to your needs.
|
||||
|
||||
### 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.
|
||||
The default arm name is `wx250s` and one will create a new arm configuration `wx250s_custom`. To do so:
|
||||
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 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. 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/`
|
||||
Once the Hardware modification has been completed, several files need to be updated in interbotix packages to use the new arm, named `ẁx250s_custom`. To do so, run the `install.sh` script as follows:
|
||||
```
|
||||
./install.sh
|
||||
```
|
||||
The script ask several infos to update the interbotix packages files. Also, the kinematics matrices `M` and `Slist` are computed. These matrices are needed by the Python API which will drive the robotic arm.
|
||||
|
||||
|
||||
```
|
||||
ros2 launch interbotix_xsarm_descriptions xsarm_description.launch.py robot_model:=wx250s_custom use_joint_pub_gui:=true
|
||||
```
|
||||
You should see this:
|
||||
|
||||

|
||||
|
||||
###
|
||||
|
50
wx250s_custom/install.sh
Executable file
50
wx250s_custom/install.sh
Executable file
@ -0,0 +1,50 @@
|
||||
#!/bin/bash
|
||||
|
||||
# Tweak the default interbotix_ws install to add a customized robot wx250s_custom
|
||||
|
||||
read -p "Enter the interbotix packages installation path [default: ~/interbotix_ws]:" DIR
|
||||
DIR=${DIR:-~/interbotix_ws}
|
||||
|
||||
cp xs_common.py "$DIR/src/interbotix_ros_toolboxes/interbotix_xs_toolbox/interbotix_xs_modules/interbotix_xs_modules/xs_common/"
|
||||
cp wx250s_custom.yaml "$DIR/src/interbotix_ros_manipulators/interbotix_ros_xsarms/interbotix_xsarm_control/config/"
|
||||
cp -r wx250s_custom_meshes "$DIR/src/interbotix_ros_manipulators/interbotix_ros_xsarms/interbotix_xsarm_descriptions/meshes/"
|
||||
|
||||
VAR=`awk 'NR==451{ print; exit }' wx250s_custom.urdf.xacro`
|
||||
VAR=`awk -F'"' '{print $2}' <<< $VAR`
|
||||
|
||||
read -p "Enter the coordinate between wrist_rotate joint and SMA center in m [default: ${VAR}]:" COORD
|
||||
COORD=${COORD:-${VAR}}
|
||||
|
||||
cp wx250s_custom.urdf.xacro wx250s_custom.urdf.xacro~
|
||||
|
||||
sed -i "451s/$VAR/$COORD/" wx250s_custom.urdf.xacro~
|
||||
|
||||
# convert to urdf file needed for kinematic_from_description package
|
||||
ros2 run xacro xacro wx250s_custom.urdf.xacro~ > out.urdf
|
||||
|
||||
# move the urdf.xacro file
|
||||
mv wx250s_custom.urdf.xacro~ "$DIR/src/interbotix_ros_manipulators/interbotix_ros_xsarms/interbotix_xsarm_descriptions/urdf/wx250s_custom.urdf.xacro"
|
||||
|
||||
#
|
||||
git clone https://github.com/Interbotix/kinematics_from_description.git
|
||||
cd kinematics_from_description
|
||||
python setup.py install --user
|
||||
cd ..
|
||||
rm -rf kinematics_from_description
|
||||
|
||||
cp mr_descriptions.py mr_descriptions.py~
|
||||
|
||||
python kinematics.py
|
||||
|
||||
mv mr_descriptions.py "$DIR/src/interbotix_ros_toolboxes/interbotix_xs_toolbox/interbotix_xs_modules/interbotix_xs_modules/xs_robot/"
|
||||
|
||||
mv mr_descriptions.py~ mr_descriptions.py
|
||||
|
||||
rm out.urdf
|
||||
|
||||
cd $DIR
|
||||
|
||||
rm -rf build
|
||||
rm -rf install
|
||||
|
||||
colcon build
|
37
wx250s_custom/kinematics.py
Normal file
37
wx250s_custom/kinematics.py
Normal file
@ -0,0 +1,37 @@
|
||||
#!/usr/bin/env python3
|
||||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Created on Fri Apr 7 15:38:46 2023
|
||||
|
||||
@author: Pierre Lecomte
|
||||
"""
|
||||
import numpy as np
|
||||
from kinematics_from_description.kfd import KinematicsFromDescriptionTool as KFD
|
||||
|
||||
tool = KFD(
|
||||
{
|
||||
"body_frame": "sma_link",
|
||||
"space_frame": "base_link",
|
||||
"namespace": "wx250s_custom",
|
||||
}
|
||||
)
|
||||
|
||||
tool.load_desc_from_file('out.urdf')
|
||||
tool.run()
|
||||
|
||||
print("Slist:")
|
||||
print(tool.Slist.T)
|
||||
|
||||
print("M:")
|
||||
print(tool.M)
|
||||
|
||||
x = f"""class wx250s_custom(ModernRoboticsDescription):
|
||||
Slist = np.array(
|
||||
{np.array2string(tool.Slist.T, separator=',')}
|
||||
).T
|
||||
|
||||
M = np.array({np.array2string(tool.M, separator=',')})
|
||||
"""
|
||||
|
||||
with open("mr_descriptions.py","a") as f:
|
||||
f.writelines(x)
|
12
wx250s_custom/matrices.txt
Normal file
12
wx250s_custom/matrices.txt
Normal file
@ -0,0 +1,12 @@
|
||||
Slist:
|
||||
[[ 0. 0. 1. 0. 0. 0. ]
|
||||
[ 0. 1. 0. -0.11065 0. 0. ]
|
||||
[ 0. 1. 0. -0.36065 0. 0.04975]
|
||||
[ 1. 0. 0. 0. 0.36065 0. ]
|
||||
[ 0. 1. 0. -0.36065 0. 0.29975]
|
||||
[ 1. 0. 0. 0. 0.36065 0. ]]
|
||||
M:
|
||||
[[1. 0. 0. 0.49275]
|
||||
[0. 1. 0. 0. ]
|
||||
[0. 0. 1. 0.36065]
|
||||
[0. 0. 0. 1. ]]
|
233
wx250s_custom/mr_descriptions.py
Normal file
233
wx250s_custom/mr_descriptions.py
Normal file
@ -0,0 +1,233 @@
|
||||
# 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.
|
||||
|
||||
"""
|
||||
Modern Robotics Descriptions for all Interbotix X-Series Arms.
|
||||
|
||||
This module contains properties required by the Modern Robotics library to perform
|
||||
kinematic calculations such as the Joint Screw Axes and Home Configuration for each
|
||||
X-Series robot.
|
||||
|
||||
Note that the end-effector is positioned at '<robot_name>/ee_gripper_link' and that the
|
||||
Space frame is positioned at '<robot_name>/base_link'.
|
||||
|
||||
To calculate your own MR Description, check out the kinematics_from_description package:
|
||||
https://github.com/Interbotix/kinematics_from_description
|
||||
"""
|
||||
|
||||
from abc import ABC
|
||||
|
||||
import numpy as np
|
||||
|
||||
|
||||
class ModernRoboticsDescription(ABC):
|
||||
"""
|
||||
Abstract base class for other MR Description classes.
|
||||
|
||||
Derived classes should override the Slist and M member variables.
|
||||
"""
|
||||
|
||||
Slist: np.ndarray = None
|
||||
"""
|
||||
Joint screw axes in the space frame when the manipulator is at the home position, in the format
|
||||
of a matrix with axes as the columns
|
||||
"""
|
||||
|
||||
M: np.ndarray = None
|
||||
"""The home configuration (position and orientation) of the end-effector"""
|
||||
|
||||
|
||||
class px100(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.0931, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.1931, 0.0, 0.035],
|
||||
[0.0, 1.0, 0.0, -0.1931, 0.0, 0.135]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.248575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.1931],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class px150(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.10457, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.25457, 0.0, 0.05],
|
||||
[0.0, 1.0, 0.0, -0.25457, 0.0, 0.2],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.25457, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.358575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.25457],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class rx150(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.10457, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.25457, 0.0, 0.05],
|
||||
[0.0, 1.0, 0.0, -0.25457, 0.0, 0.2],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.25457, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.358575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.25457],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class rx200(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.10457, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.30457, 0.0, 0.05],
|
||||
[0.0, 1.0, 0.0, -0.30457, 0.0, 0.25],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.30457, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.408575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.30457],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class vx250(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.12705, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.37705, 0.0, 0.06],
|
||||
[0.0, 1.0, 0.0, -0.37705, 0.0, 0.31],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.37705, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.468575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.37705],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class vx300(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.12705, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.42705, 0.0, 0.05955],
|
||||
[0.0, 1.0, 0.0, -0.42705, 0.0, 0.35955],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.42705, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.536494],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.42705],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class vx300s(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.12705, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.42705, 0.0, 0.05955],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.42705, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.42705, 0.0, 0.35955],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.42705, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.536494],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.42705],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class wx200(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.11065, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.31065, 0.0, 0.05],
|
||||
[0.0, 1.0, 0.0, -0.31065, 0.0, 0.25],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.31065, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.408575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.31065],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class wx250(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.11065, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.36065, 0.0, 0.04975],
|
||||
[0.0, 1.0, 0.0, -0.36065, 0.0, 0.29975],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.36065, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.458325],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.36065],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class wx250s(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.11065, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.36065, 0.0, 0.04975],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.36065, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.36065, 0.0, 0.29975],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.36065, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.458325],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.36065],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class mobile_px100(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.08518, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.18518, 0.0, 0.035],
|
||||
[0.0, 1.0, 0.0, -0.18518, 0.0, 0.135]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.248575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.18518],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class mobile_wx200(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.104825, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.304825, 0.0, 0.05],
|
||||
[0.0, 1.0, 0.0, -0.304825, 0.0, 0.25],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.304825, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.408575],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.304825],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
||||
|
||||
class mobile_wx250s(ModernRoboticsDescription):
|
||||
Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.104825, 0.0, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.354825, 0.0, 0.04975],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.354825, 0.0],
|
||||
[0.0, 1.0, 0.0, -0.354825, 0.0, 0.29975],
|
||||
[1.0, 0.0, 0.0, 0.0, 0.354825, 0.0]]).T
|
||||
|
||||
M = np.array([[1.0, 0.0, 0.0, 0.458325],
|
||||
[0.0, 1.0, 0.0, 0.0],
|
||||
[0.0, 0.0, 1.0, 0.354825],
|
||||
[0.0, 0.0, 0.0, 1.0]])
|
||||
|
BIN
wx250s_custom/rviz.png
Normal file
BIN
wx250s_custom/rviz.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 192 KiB |
@ -1,700 +0,0 @@
|
||||
<?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>
|
@ -11,6 +11,7 @@
|
||||
<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="use_gripper" default="false"/>
|
||||
<xacro:arg name="external_urdf_loc" default=""/>
|
||||
<xacro:arg name="hardware_type" default="actual"/>
|
||||
|
||||
@ -487,9 +488,6 @@
|
||||
</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>
|
||||
|
Loading…
Reference in New Issue
Block a user