Skip to content

Commit

Permalink
Add files via upload
Browse files Browse the repository at this point in the history
  • Loading branch information
RoboDD authored Jul 31, 2024
1 parent eb75147 commit 049dd50
Show file tree
Hide file tree
Showing 3 changed files with 537 additions and 0 deletions.
72 changes: 72 additions & 0 deletions build_lite6.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
#!/usr/bin/env python
# Copy this file to ~/.local/lib/python3.8/site-packages/rtbdata/xacro
import numpy as np
from roboticstoolbox.robot.Robot import Robot
from spatialmath import SE3


class Lite6(Robot):
"""
Class that imports a Panda URDF model
``Panda()`` is a class which imports a Franka-Emika Panda robot definition
from a URDF file. The model describes its kinematic and graphical
characteristics.
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.URDF.Panda()
>>> print(robot)
Defined joint configurations are:
- qz, zero joint angle configuration, 'L' shaped configuration
- qr, vertical 'READY' configuration
- qs, arm is stretched out in the x-direction
- qn, arm is at a nominal non-singular configuration
.. codeauthor:: Jesse Haviland
.. sectionauthor:: Peter Corke
"""

def __init__(self):

links, name, urdf_string, urdf_filepath = self.URDF_read(
"lite6.urdf"
)

super().__init__(
links,
name=name,
manufacturer="UFactory",
# gripper_links=links[9],
urdf_string=urdf_string,
urdf_filepath=urdf_filepath,
)

# self.grippers[0].tool = SE3(0, 0, 0.1034)

self.qdlim = np.array(
[2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100]
)

self.qr = np.array([0.0, 0.2792, 0.8499, 0.0, 0.5724, 0.0])
self.qz = np.zeros(7)

self.addconfiguration("qr", self.qr)
self.addconfiguration("qz", self.qz)


if __name__ == "__main__": # pragma nocover

r = Lite6()

# r.qr

qz = np.zeros(6)
qr = np.array([0.0, 0.2792, 0.8499, 0.0, 0.5724, 0.0])
print(r.fkine(qr))

# for link in r.grippers[0].links:
# print(link)
215 changes: 215 additions & 0 deletions lite6.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,215 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from xarm_device.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="Lite6">
<!-- Insert at the beginning of xarm_device_macro.xacro -->
<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="Red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<material name="Silver">
<color rgba="0.753 0.753 0.753 1.0"/>
</material>
<link name="world"/>
<joint name="world_joint" type="fixed">
<parent link="world"/>
<child link="link_base"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="link_base">
<inertial>
<origin rpy="0 0 0" xyz="-0.00829544579053192 3.26357432323433E-05 0.0631194584987089"/>
<mass value="1.65393501783165"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/visual/link_base.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="White"/>
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/collision/link_base.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<link name="link1">
<inertial>
<origin rpy="0 0 0" xyz="-0.00036 0.04195 -0.0025"/>
<mass value="1.411"/>
<inertia ixx="0.0014516400000000001" ixy="-1.24e-05" ixz="6.7e-06" iyy="0.0008872999999999999" iyz="-0.0001255" izz="0.00131993"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/visual/link1.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="White"/>
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/collision/link1.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="joint1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.2435"/>
<parent link="link_base"/>
<child link="link1"/>
<axis xyz="0 0 1"/>
<limit effort="50.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link2">
<inertial>
<origin rpy="0 0 0" xyz="0.179 0.0 0.0584"/>
<mass value="1.34"/>
<inertia ixx="0.0015854" ixy="6.766e-06" ixz="0.00115136" iyy="0.0056097" iyz="-1.1399999999999999e-06" izz="0.00485"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/visual/link2.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="White"/>
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/collision/link2.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="joint2" type="revolute">
<origin rpy="1.5708 -1.5708 3.1416" xyz="0 0 0"/>
<parent link="link1"/>
<child link="link2"/>
<axis xyz="0 0 1"/>
<limit effort="50.0" lower="-2.61799" upper="2.61799" velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link3">
<inertial>
<origin rpy="0 0 0" xyz="0.072 -0.0357 -0.001"/>
<mass value="0.953"/>
<inertia ixx="0.0008861" ixy="0.00039286999999999997" ixz="-7.065999999999999e-05" iyy="0.0015784999999999998" iyz="2.4449999999999998e-05" izz="0.00184677"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/visual/link3.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="White"/>
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/collision/link3.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="joint3" type="revolute">
<origin rpy="-3.1416 0 1.5708" xyz="0.2002 0 0"/>
<parent link="link2"/>
<child link="link3"/>
<axis xyz="0 0 1"/>
<limit effort="32.0" lower="-0.061087" upper="5.235988" velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link4">
<inertial>
<origin rpy="0 0 0" xyz="-0.002 -0.0285 -0.0813"/>
<mass value="1.284"/>
<inertia ixx="0.003705" ixy="2e-06" ixz="-7.17e-06" iyy="0.0030455" iyz="0.00093188" izz="0.0015412999999999998"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/visual/link4.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="White"/>
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/collision/link4.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="joint4" type="revolute">
<origin rpy="1.5708 0 0" xyz="0.087 -0.22761 0"/>
<parent link="link3"/>
<child link="link4"/>
<axis xyz="0 0 1"/>
<limit effort="32.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link5">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.01 0.0019"/>
<mass value="0.804"/>
<inertia ixx="0.0005667999999999999" ixy="-6e-07" ixz="5.299999999999999e-06" iyy="0.0005076999999999999" iyz="4.8e-07" izz="0.00053"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/visual/link5.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="White"/>
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/collision/link5.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="joint5" type="revolute">
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
<parent link="link4"/>
<child link="link5"/>
<axis xyz="0 0 1"/>
<limit effort="32.0" lower="-2.1642" upper="2.1642" velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link6">
<inertial>
<origin rpy="0 0 0" xyz="0.0 -0.00194 -0.0102"/>
<mass value="0.13"/>
<inertia ixx="7.726e-05" ixy="-1e-06" ixz="-4e-07" iyy="8.5665e-05" iyz="6e-07" izz="0.00014813999999999997"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/visual/link6.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="Silver"/>
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/lite6/collision/link6.stl"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
<joint name="joint6" type="revolute">
<origin rpy="-1.5708 0 0" xyz="0 0.0625 0"/>
<parent link="link5"/>
<child link="link6"/>
<axis xyz="0 0 1"/>
<limit effort="20.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
</robot>

Loading

0 comments on commit 049dd50

Please sign in to comment.