Initial Commit
URDF and STLs stolen from https://github.com/ongdexter/ar3_core/tree/master/ar3_description Bare minumum state publisher from ROS2 tutorials
This commit is contained in:
commit
9eff9ec145
20 changed files with 985 additions and 0 deletions
171
.gitignore
vendored
Normal file
171
.gitignore
vendored
Normal file
|
@ -0,0 +1,171 @@
|
|||
|
||||
# Created by https://www.toptal.com/developers/gitignore/api/python,vim
|
||||
# Edit at https://www.toptal.com/developers/gitignore?templates=python,vim
|
||||
|
||||
### Python ###
|
||||
# Byte-compiled / optimized / DLL files
|
||||
__pycache__/
|
||||
*.py[cod]
|
||||
*$py.class
|
||||
|
||||
# C extensions
|
||||
*.so
|
||||
|
||||
# Distribution / packaging
|
||||
.Python
|
||||
build/
|
||||
develop-eggs/
|
||||
dist/
|
||||
downloads/
|
||||
eggs/
|
||||
.eggs/
|
||||
lib/
|
||||
lib64/
|
||||
parts/
|
||||
sdist/
|
||||
var/
|
||||
wheels/
|
||||
share/python-wheels/
|
||||
*.egg-info/
|
||||
.installed.cfg
|
||||
*.egg
|
||||
MANIFEST
|
||||
|
||||
# PyInstaller
|
||||
# Usually these files are written by a python script from a template
|
||||
# before PyInstaller builds the exe, so as to inject date/other infos into it.
|
||||
*.manifest
|
||||
*.spec
|
||||
|
||||
# Installer logs
|
||||
pip-log.txt
|
||||
pip-delete-this-directory.txt
|
||||
|
||||
# Unit test / coverage reports
|
||||
htmlcov/
|
||||
.tox/
|
||||
.nox/
|
||||
.coverage
|
||||
.coverage.*
|
||||
.cache
|
||||
nosetests.xml
|
||||
coverage.xml
|
||||
*.cover
|
||||
*.py,cover
|
||||
.hypothesis/
|
||||
.pytest_cache/
|
||||
cover/
|
||||
|
||||
# Translations
|
||||
*.mo
|
||||
*.pot
|
||||
|
||||
# Django stuff:
|
||||
*.log
|
||||
local_settings.py
|
||||
db.sqlite3
|
||||
db.sqlite3-journal
|
||||
|
||||
# Flask stuff:
|
||||
instance/
|
||||
.webassets-cache
|
||||
|
||||
# Scrapy stuff:
|
||||
.scrapy
|
||||
|
||||
# Sphinx documentation
|
||||
docs/_build/
|
||||
|
||||
# PyBuilder
|
||||
.pybuilder/
|
||||
target/
|
||||
|
||||
# Jupyter Notebook
|
||||
.ipynb_checkpoints
|
||||
|
||||
# IPython
|
||||
profile_default/
|
||||
ipython_config.py
|
||||
|
||||
# pyenv
|
||||
# For a library or package, you might want to ignore these files since the code is
|
||||
# intended to run in multiple environments; otherwise, check them in:
|
||||
# .python-version
|
||||
|
||||
# pipenv
|
||||
# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control.
|
||||
# However, in case of collaboration, if having platform-specific dependencies or dependencies
|
||||
# having no cross-platform support, pipenv may install dependencies that don't work, or not
|
||||
# install all needed dependencies.
|
||||
#Pipfile.lock
|
||||
|
||||
# PEP 582; used by e.g. github.com/David-OConnor/pyflow
|
||||
__pypackages__/
|
||||
|
||||
# Celery stuff
|
||||
celerybeat-schedule
|
||||
celerybeat.pid
|
||||
|
||||
# SageMath parsed files
|
||||
*.sage.py
|
||||
|
||||
# Environments
|
||||
.env
|
||||
.venv
|
||||
env/
|
||||
venv/
|
||||
ENV/
|
||||
env.bak/
|
||||
venv.bak/
|
||||
|
||||
# Spyder project settings
|
||||
.spyderproject
|
||||
.spyproject
|
||||
|
||||
# Rope project settings
|
||||
.ropeproject
|
||||
|
||||
# mkdocs documentation
|
||||
/site
|
||||
|
||||
# mypy
|
||||
.mypy_cache/
|
||||
.dmypy.json
|
||||
dmypy.json
|
||||
|
||||
# Pyre type checker
|
||||
.pyre/
|
||||
|
||||
# pytype static type analyzer
|
||||
.pytype/
|
||||
|
||||
# Cython debug symbols
|
||||
cython_debug/
|
||||
|
||||
### Vim ###
|
||||
# Swap
|
||||
[._]*.s[a-v][a-z]
|
||||
!*.svg # comment out if you don't need vector files
|
||||
[._]*.sw[a-p]
|
||||
[._]s[a-rt-v][a-z]
|
||||
[._]ss[a-gi-z]
|
||||
[._]sw[a-p]
|
||||
|
||||
# Session
|
||||
Session.vim
|
||||
Sessionx.vim
|
||||
|
||||
# Temporary
|
||||
.netrwhist
|
||||
*~
|
||||
# Auto-generated tag files
|
||||
tags
|
||||
# Persistent undo
|
||||
[._]*.un~
|
||||
|
||||
# End of https://www.toptal.com/developers/gitignore/api/python,vim
|
||||
|
||||
build/
|
||||
install/
|
||||
log/
|
||||
|
0
src/ar3_description/ar3_description/__init__.py
Normal file
0
src/ar3_description/ar3_description/__init__.py
Normal file
85
src/ar3_description/ar3_description/state_publisher.py
Normal file
85
src/ar3_description/ar3_description/state_publisher.py
Normal file
|
@ -0,0 +1,85 @@
|
|||
from math import sin, cos, pi
|
||||
import rclpy, random
|
||||
from rclpy.node import Node
|
||||
from rclpy.qos import QoSProfile
|
||||
from geometry_msgs.msg import Quaternion
|
||||
from sensor_msgs.msg import JointState
|
||||
from tf2_ros import TransformBroadcaster, TransformStamped
|
||||
|
||||
class StatePublisher(Node):
|
||||
|
||||
def __init__(self):
|
||||
rclpy.init()
|
||||
super().__init__('state_publisher')
|
||||
|
||||
qos_profile = QoSProfile(depth=10)
|
||||
self.joint_pub = self.create_publisher(JointState, 'joint_states', qos_profile)
|
||||
self.broadcaster = TransformBroadcaster(self, qos=qos_profile)
|
||||
self.nodeName = self.get_name()
|
||||
self.get_logger().info("{0} started".format(self.nodeName))
|
||||
|
||||
degree = pi / 180.0
|
||||
loop_rate = self.create_rate(30)
|
||||
|
||||
# robot state
|
||||
tilt = 0.
|
||||
tinc = degree
|
||||
swivel = 0.
|
||||
angle = 0.
|
||||
height = 0.
|
||||
hinc = 0.005
|
||||
|
||||
# message declarations
|
||||
odom_trans = TransformStamped()
|
||||
odom_trans.header.frame_id = 'odom'
|
||||
odom_trans.child_frame_id = 'base_link'
|
||||
joint_state = JointState()
|
||||
|
||||
try:
|
||||
while rclpy.ok():
|
||||
rclpy.spin_once(self)
|
||||
|
||||
# update joint_state
|
||||
now = self.get_clock().now()
|
||||
joint_state.header.stamp = now.to_msg()
|
||||
joint_state.name = ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6']
|
||||
# joint_state.position = [sin(angle) * pi / 1] * 6
|
||||
# joint_state.position = [random.random() * pi / 2] * 6
|
||||
# joint_state.position = [angle * 16, pi/2., -25 / 180 * pi, 0., 0., 0.]
|
||||
# joint_state.position = [angle * 0.01 * random.random()] * 6
|
||||
joint_state.position = [0., 0., 0., 0., angle, 0.]
|
||||
|
||||
# update transform
|
||||
# (moving in a circle with radius=2)
|
||||
odom_trans.header.stamp = now.to_msg()
|
||||
odom_trans.transform.translation.x = 0.0# cos(angle) * 0.4
|
||||
odom_trans.transform.translation.y = 0.0# sin(angle) * 0.4
|
||||
odom_trans.transform.translation.z = 0.0
|
||||
odom_trans.transform.rotation = \
|
||||
euler_to_quaternion(0, 0, 0) # roll,pitch,yaw
|
||||
|
||||
# send the joint state and transform
|
||||
self.joint_pub.publish(joint_state)
|
||||
self.broadcaster.sendTransform(odom_trans)
|
||||
|
||||
# Create new robot state
|
||||
angle += degree
|
||||
|
||||
# This will adjust as needed per iteration
|
||||
loop_rate.sleep()
|
||||
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
|
||||
def euler_to_quaternion(roll, pitch, yaw):
|
||||
qx = sin(roll/2) * cos(pitch/2) * cos(yaw/2) - cos(roll/2) * sin(pitch/2) * sin(yaw/2)
|
||||
qy = cos(roll/2) * sin(pitch/2) * cos(yaw/2) + sin(roll/2) * cos(pitch/2) * sin(yaw/2)
|
||||
qz = cos(roll/2) * cos(pitch/2) * sin(yaw/2) - sin(roll/2) * sin(pitch/2) * cos(yaw/2)
|
||||
qw = cos(roll/2) * cos(pitch/2) * cos(yaw/2) + sin(roll/2) * sin(pitch/2) * sin(yaw/2)
|
||||
return Quaternion(x=qx, y=qy, z=qz, w=qw)
|
||||
|
||||
def main():
|
||||
node = StatePublisher()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
36
src/ar3_description/launch/demo.launch.py
Normal file
36
src/ar3_description/launch/demo.launch.py
Normal file
|
@ -0,0 +1,36 @@
|
|||
import os
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='false')
|
||||
|
||||
urdf_file_name = 'ar3.urdf'
|
||||
urdf = os.path.join(
|
||||
get_package_share_directory('ar3_description'),
|
||||
urdf_file_name)
|
||||
with open(urdf, 'r') as infp:
|
||||
robot_desc = infp.read()
|
||||
|
||||
return LaunchDescription([
|
||||
DeclareLaunchArgument(
|
||||
'use_sim_time',
|
||||
default_value='false',
|
||||
description='Use simulation (Gazebo) clock if true'),
|
||||
Node(
|
||||
package='robot_state_publisher',
|
||||
executable='robot_state_publisher',
|
||||
name='robot_state_publisher',
|
||||
output='screen',
|
||||
parameters=[{'use_sim_time': use_sim_time, 'robot_description': robot_desc}],
|
||||
arguments=[urdf]),
|
||||
Node(
|
||||
package='ar3_description',
|
||||
executable='state_publisher',
|
||||
name='state_publisher',
|
||||
output='screen'),
|
||||
])
|
BIN
src/ar3_description/meshes/base_link.STL
Normal file
BIN
src/ar3_description/meshes/base_link.STL
Normal file
Binary file not shown.
BIN
src/ar3_description/meshes/link_1.STL
Normal file
BIN
src/ar3_description/meshes/link_1.STL
Normal file
Binary file not shown.
BIN
src/ar3_description/meshes/link_2.STL
Normal file
BIN
src/ar3_description/meshes/link_2.STL
Normal file
Binary file not shown.
BIN
src/ar3_description/meshes/link_3.STL
Normal file
BIN
src/ar3_description/meshes/link_3.STL
Normal file
Binary file not shown.
BIN
src/ar3_description/meshes/link_4.STL
Normal file
BIN
src/ar3_description/meshes/link_4.STL
Normal file
Binary file not shown.
BIN
src/ar3_description/meshes/link_5.STL
Normal file
BIN
src/ar3_description/meshes/link_5.STL
Normal file
Binary file not shown.
BIN
src/ar3_description/meshes/link_6.STL
Normal file
BIN
src/ar3_description/meshes/link_6.STL
Normal file
Binary file not shown.
21
src/ar3_description/package.xml
Normal file
21
src/ar3_description/package.xml
Normal file
|
@ -0,0 +1,21 @@
|
|||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>ar3_description</name>
|
||||
<version>1.0.0</version>
|
||||
<description>Robot description and state publisher for the AR3 arm</description>
|
||||
<maintainer email="tmuller2017@my.fit.edu">Thomas Muller</maintainer>
|
||||
<maintainer email="farell2017@my.fit.edu">John Farell</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
<test_depend>ament_pep257</test_depend>
|
||||
<test_depend>python3-pytest</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_python</build_type>
|
||||
</export>
|
||||
</package>
|
0
src/ar3_description/resource/ar3_description
Normal file
0
src/ar3_description/resource/ar3_description
Normal file
4
src/ar3_description/setup.cfg
Normal file
4
src/ar3_description/setup.cfg
Normal file
|
@ -0,0 +1,4 @@
|
|||
[develop]
|
||||
script-dir=$base/lib/ar3_description
|
||||
[install]
|
||||
install-scripts=$base/lib/ar3_description
|
32
src/ar3_description/setup.py
Normal file
32
src/ar3_description/setup.py
Normal file
|
@ -0,0 +1,32 @@
|
|||
import os
|
||||
from glob import glob
|
||||
from setuptools import setup
|
||||
from setuptools import find_packages
|
||||
|
||||
package_name = 'ar3_description'
|
||||
|
||||
setup(
|
||||
name=package_name,
|
||||
version='0.0.0',
|
||||
packages=[package_name],
|
||||
data_files=[
|
||||
('share/ament_index/resource_index/packages',
|
||||
['resource/' + package_name]),
|
||||
('share/' + package_name, ['package.xml']),
|
||||
('share/' + package_name, glob('launch/*.py')),
|
||||
('share/' + package_name, glob('urdf/*')),
|
||||
('share/' + package_name + '/meshes', glob('meshes/*'))
|
||||
],
|
||||
install_requires=['setuptools'],
|
||||
zip_safe=True,
|
||||
maintainer=['Thomas Muller', 'John Farell'],
|
||||
maintainer_email=['tmuller2017@my.fit.edu', 'farell2017@my.fit.edu'],
|
||||
description='Robot description and state publisher for the AR3 arm',
|
||||
license='TODO: License declaration',
|
||||
tests_require=['pytest'],
|
||||
entry_points={
|
||||
'console_scripts': [
|
||||
'state_publisher = ar3_description.state_publisher:main'
|
||||
],
|
||||
},
|
||||
)
|
23
src/ar3_description/test/test_copyright.py
Normal file
23
src/ar3_description/test/test_copyright.py
Normal file
|
@ -0,0 +1,23 @@
|
|||
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
from ament_copyright.main import main
|
||||
import pytest
|
||||
|
||||
|
||||
@pytest.mark.copyright
|
||||
@pytest.mark.linter
|
||||
def test_copyright():
|
||||
rc = main(argv=['.', 'test'])
|
||||
assert rc == 0, 'Found errors'
|
25
src/ar3_description/test/test_flake8.py
Normal file
25
src/ar3_description/test/test_flake8.py
Normal file
|
@ -0,0 +1,25 @@
|
|||
# Copyright 2017 Open Source Robotics Foundation, Inc.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
from ament_flake8.main import main_with_errors
|
||||
import pytest
|
||||
|
||||
|
||||
@pytest.mark.flake8
|
||||
@pytest.mark.linter
|
||||
def test_flake8():
|
||||
rc, errors = main_with_errors(argv=[])
|
||||
assert rc == 0, \
|
||||
'Found %d code style errors / warnings:\n' % len(errors) + \
|
||||
'\n'.join(errors)
|
23
src/ar3_description/test/test_pep257.py
Normal file
23
src/ar3_description/test/test_pep257.py
Normal file
|
@ -0,0 +1,23 @@
|
|||
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
from ament_pep257.main import main
|
||||
import pytest
|
||||
|
||||
|
||||
@pytest.mark.linter
|
||||
@pytest.mark.pep257
|
||||
def test_pep257():
|
||||
rc = main(argv=['.', 'test'])
|
||||
assert rc == 0, 'Found code style errors / warnings'
|
361
src/ar3_description/urdf/ar3.urdf
Normal file
361
src/ar3_description/urdf/ar3.urdf
Normal file
|
@ -0,0 +1,361 @@
|
|||
<robot
|
||||
name="ar3">
|
||||
<link
|
||||
name="base_link">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-4.6941E-06 0.054174 0.038824"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.7102" />
|
||||
<inertia
|
||||
ixx="0.0039943"
|
||||
ixy="3.697E-07"
|
||||
ixz="-5.7364E-08"
|
||||
iyy="0.0014946"
|
||||
iyz="-0.00036051"
|
||||
izz="0.0042554" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/base_link.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/base_link.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link
|
||||
name="link_1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.022706 0.04294 -0.12205"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.88065" />
|
||||
<inertia
|
||||
ixx="0.0034"
|
||||
ixy="0.00042296"
|
||||
ixz="-0.00089231"
|
||||
iyy="0.0041778"
|
||||
iyz="0.0010848"
|
||||
izz="0.0027077" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_1.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_1.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint_1"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0 0.003445"
|
||||
rpy="3.1416 -1.0248E-21 -1.6736E-05" />
|
||||
<parent
|
||||
link="base_link" />
|
||||
<child
|
||||
link="link_1" />
|
||||
<axis
|
||||
xyz="0 0 1" />
|
||||
</joint>
|
||||
<link
|
||||
name="link_2">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.064818 -0.11189 -0.038671"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.57738" />
|
||||
<inertia
|
||||
ixx="0.0047312"
|
||||
ixy="0.0022624"
|
||||
ixz="0.00032144"
|
||||
iyy="0.0020836"
|
||||
iyz="-0.00056569"
|
||||
izz="0.0056129" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_2.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_2.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint_2"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0.064146 -0.16608"
|
||||
rpy="1.5708 0.5236 -1.5708" />
|
||||
<parent
|
||||
link="link_1" />
|
||||
<child
|
||||
link="link_2" />
|
||||
<axis
|
||||
xyz="0 0 -1" />
|
||||
</joint>
|
||||
<link
|
||||
name="link_3">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.00029765 -0.023661 -1.04720367321"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.1787" />
|
||||
<inertia
|
||||
ixx="0.0001685"
|
||||
ixy="-2.7713E-05"
|
||||
ixz="5.6885E-06"
|
||||
iyy="0.00012865"
|
||||
iyz="2.9256E-05"
|
||||
izz="0.00020744" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_3.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_3.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint_3"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0.1525 -0.26414 0"
|
||||
rpy="3.3431E-16 -1.4164E-16 -1.4953816339" />
|
||||
<parent
|
||||
link="link_2" />
|
||||
<child
|
||||
link="link_3" />
|
||||
<axis
|
||||
xyz="0 0 -1" />
|
||||
</joint>
|
||||
<link
|
||||
name="link_4">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0016798 -0.00057319 -0.074404"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.34936" />
|
||||
<inertia
|
||||
ixx="0.0030532"
|
||||
ixy="-1.8615E-05"
|
||||
ixz="-7.0047E-05"
|
||||
iyy="0.0031033"
|
||||
iyz="-2.3301E-05"
|
||||
izz="0.00022264" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_4.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_4.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint_4"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0 0.00675"
|
||||
rpy="1.5708 -1.2554 -1.5708" />
|
||||
<parent
|
||||
link="link_3" />
|
||||
<child
|
||||
link="link_4" />
|
||||
<axis
|
||||
xyz="0 0 -1" />
|
||||
</joint>
|
||||
<link
|
||||
name="link_5">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0015066 -1.3102E-05 -0.012585"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.11562" />
|
||||
<inertia
|
||||
ixx="5.5035E-05"
|
||||
ixy="-1.019E-08"
|
||||
ixz="-2.6243E-06"
|
||||
iyy="8.2921E-05"
|
||||
iyz="1.4437E-08"
|
||||
izz="5.2518E-05" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_5.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_5.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint_5"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0 -0.22225"
|
||||
rpy="3.1416 0 -2.8262" />
|
||||
<parent
|
||||
link="link_4" />
|
||||
<child
|
||||
link="link_5" />
|
||||
<axis
|
||||
xyz="-1 0 0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link_6">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="2.9287E-10 -1.6472E-09 0.0091432"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.013863" />
|
||||
<inertia
|
||||
ixx="1.3596E-06"
|
||||
ixy="3.0585E-13"
|
||||
ixz="5.7102E-14"
|
||||
iyy="1.7157E-06"
|
||||
iyz="6.3369E-09"
|
||||
izz="2.4332E-06" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_6.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://ar3_description/meshes/link_6.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint_6"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="-0.000294 0 0.02117"
|
||||
rpy="0 0 3.1416" />
|
||||
<parent
|
||||
link="link_5" />
|
||||
<child
|
||||
link="link_6" />
|
||||
<axis
|
||||
xyz="0 0 1" />
|
||||
</joint>
|
||||
</robot>
|
204
src/ar3_description/urdf/ar3.urdf.xacro
Normal file
204
src/ar3_description/urdf/ar3.urdf.xacro
Normal file
|
@ -0,0 +1,204 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from ar3.urdf | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="ar3">
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-4.6941E-06 0.054174 0.038824"/>
|
||||
<mass value="0.7102"/>
|
||||
<inertia ixx="0.0039943" ixy="3.697E-07" ixz="-5.7364E-08" iyy="0.0014946" iyz="-0.00036051" izz="0.0042554"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/base_link.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/base_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="link_1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.022706 0.04294 -0.12205"/>
|
||||
<mass value="0.88065"/>
|
||||
<inertia ixx="0.0034" ixy="0.00042296" ixz="-0.00089231" iyy="0.0041778" iyz="0.0010848" izz="0.0027077"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_1.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_1.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="joint_1" type="revolute">
|
||||
<origin rpy="${pi} 0 0" xyz="0 0 0.003445"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="link_1"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.96706" upper="2.96706" effort="0" velocity="0"/>
|
||||
</joint>
|
||||
<link name="link_2">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.064818 -0.11189 -0.038671"/>
|
||||
<mass value="0.57738"/>
|
||||
<inertia ixx="0.0047312" ixy="0.0022624" ixz="0.00032144" iyy="0.0020836" iyz="-0.00056569" izz="0.0056129"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_2.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_2.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="joint_2" type="revolute">
|
||||
<origin rpy="1.5708 0.5236 -1.5708" xyz="0 0.064146 -0.16608"/>
|
||||
<parent link="link_1"/>
|
||||
<child link="link_2"/>
|
||||
<axis xyz="0 0 -1"/>
|
||||
<limit lower="${-39.6 / 180.0 * pi}" upper="${pi / 2.0}" effort="0" velocity="0"/>
|
||||
</joint>
|
||||
<link name="link_3">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00029765 -0.023661 -0.0019125"/>
|
||||
<mass value="0.1787"/>
|
||||
<inertia ixx="0.0001685" ixy="-2.7713E-05" ixz="5.6885E-06" iyy="0.00012865" iyz="2.9256E-05" izz="0.00020744"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_3.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_3.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="joint_3" type="revolute">
|
||||
<origin rpy="0 0 -1.04720367321" xyz="0.1525 -0.26414 0"/>
|
||||
<parent link="link_2"/>
|
||||
<child link="link_3"/>
|
||||
<axis xyz="0 0 -1"/>
|
||||
<limit lower="0.0174533" upper="2.5080381" effort="0" velocity="0"/>
|
||||
</joint>
|
||||
<link name="link_4">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.0016798 -0.00057319 -0.074404"/>
|
||||
<mass value="0.34936"/>
|
||||
<inertia ixx="0.0030532" ixy="-1.8615E-05" ixz="-7.0047E-05" iyy="0.0031033" iyz="-2.3301E-05" izz="0.00022264"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_4.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_4.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="joint_4" type="revolute">
|
||||
<origin rpy="1.5708 -1.2554 -1.5708" xyz="0 0 0.00675"/>
|
||||
<parent link="link_3"/>
|
||||
<child link="link_4"/>
|
||||
<axis xyz="0 0 -1"/>
|
||||
<limit lower="-2.8710666" upper="2.8710666" effort="0" velocity="0"/>
|
||||
</joint>
|
||||
<link name="link_5">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0015066 -1.3102E-05 -0.012585"/>
|
||||
<mass value="0.11562"/>
|
||||
<inertia ixx="5.5035E-05" ixy="-1.019E-08" ixz="-2.6243E-06" iyy="8.2921E-05" iyz="1.4437E-08" izz="5.2518E-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_5.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_5.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="joint_5" type="revolute">
|
||||
<origin rpy="${pi} 0 -2.8262" xyz="0 0 -0.22225"/>
|
||||
<parent link="link_4"/>
|
||||
<child link="link_5"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-1.81776042" upper="1.81776042" effort="0" velocity="0"/>
|
||||
</joint>
|
||||
<link name="link_6">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="2.9287E-10 -1.6472E-09 0.0091432"/>
|
||||
<mass value="0.013863"/>
|
||||
<inertia ixx="1.3596E-06" ixy="3.0585E-13" ixz="5.7102E-14" iyy="1.7157E-06" iyz="6.3369E-09" izz="2.4332E-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_6.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://ar3_description/meshes/link_6.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="joint_6" type="revolute">
|
||||
<origin rpy="0 0 3.1416" xyz="-0.000294 0 0.02117"/>
|
||||
<parent link="link_5"/>
|
||||
<child link="link_6"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.5848326" upper="2.5848326" effort="0" velocity="0"/>
|
||||
</joint>
|
||||
</robot>
|
||||
|
Loading…
Reference in a new issue