refactor pybullet/gym to allow instantiating environments directly from a pybullet install:
work-in-progress (need to add missing data files, fix paths etc)
example:
pip install pybullet
pip install gym
python
import gym
import pybullet
import pybullet_envs
env = gym.make("HumanoidBulletEnv-v0")
This commit is contained in:
@@ -5,6 +5,8 @@ recursive-include Extras *.h
|
||||
recursive-include Extras *.hpp
|
||||
recursive-include src *.h
|
||||
recursive-include src *.hpp
|
||||
recursive-include data *.*
|
||||
recursive-include examples/pybullet/gym *.*
|
||||
include examples/ThirdPartyLibs/enet/unix.c
|
||||
include examples/OpenGLWindow/X11OpenGLWindow.cpp
|
||||
include examples/ThirdPartyLibs/Glew/glew.c
|
||||
|
||||
@@ -1,21 +0,0 @@
|
||||
"""An actor network."""
|
||||
import tensorflow as tf
|
||||
import sonnet as snt
|
||||
|
||||
class ActorNetwork(snt.AbstractModule):
|
||||
"""An actor network as a sonnet Module."""
|
||||
|
||||
def __init__(self, layer_sizes, action_size, name='target_actor'):
|
||||
super(ActorNetwork, self).__init__(name=name)
|
||||
self._layer_sizes = layer_sizes
|
||||
self._action_size = action_size
|
||||
|
||||
def _build(self, inputs):
|
||||
state = inputs
|
||||
for output_size in self._layer_sizes:
|
||||
state = snt.Linear(output_size)(state)
|
||||
state = tf.nn.relu(state)
|
||||
|
||||
action = tf.tanh(
|
||||
snt.Linear(self._action_size, name='action')(state))
|
||||
return action
|
||||
@@ -1,37 +0,0 @@
|
||||
"""Loads a DDPG agent without too much external dependencies
|
||||
"""
|
||||
from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
from __future__ import print_function
|
||||
|
||||
import os
|
||||
import collections
|
||||
import numpy as np
|
||||
import tensorflow as tf
|
||||
import pdb
|
||||
|
||||
class SimpleAgent():
|
||||
def __init__(
|
||||
self,
|
||||
session,
|
||||
ckpt_path,
|
||||
actor_layer_size,
|
||||
observation_dim=28
|
||||
):
|
||||
self._ckpt_path = ckpt_path
|
||||
self._session = session
|
||||
self._observation_dim = observation_dim
|
||||
self._build()
|
||||
|
||||
def _build(self):
|
||||
saver = tf.train.import_meta_graph(self._ckpt_path + '.meta')
|
||||
saver.restore(
|
||||
sess=self._session,
|
||||
save_path=self._ckpt_path)
|
||||
self._action = tf.get_collection('action_op')[0]
|
||||
self._obs = tf.get_collection('observation_placeholder')[0]
|
||||
|
||||
def __call__(self, observation):
|
||||
feed_dict={self._obs: observation}
|
||||
out_action = self._session.run(self._action, feed_dict=feed_dict)
|
||||
return out_action[0]
|
||||
@@ -1,46 +0,0 @@
|
||||
"""Loads a DDPG agent without too much external dependencies
|
||||
"""
|
||||
from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
from __future__ import print_function
|
||||
|
||||
import os
|
||||
import collections
|
||||
import numpy as np
|
||||
import tensorflow as tf
|
||||
|
||||
import sonnet as snt
|
||||
from agents import actor_net
|
||||
|
||||
class SimpleAgent():
|
||||
def __init__(
|
||||
self,
|
||||
session,
|
||||
ckpt_path,
|
||||
actor_layer_size,
|
||||
observation_size=(28,),
|
||||
action_size=8,
|
||||
):
|
||||
self._ckpt_path = ckpt_path
|
||||
self._actor_layer_size = actor_layer_size
|
||||
self._observation_size = observation_size
|
||||
self._action_size = action_size
|
||||
self._session = session
|
||||
self._build()
|
||||
|
||||
def _build(self):
|
||||
self._agent_net = actor_net.ActorNetwork(self._actor_layer_size, self._action_size)
|
||||
self._obs = tf.placeholder(tf.float32, self._observation_size)
|
||||
with tf.name_scope('Act'):
|
||||
batch_obs = snt.nest.pack_iterable_as(self._obs,
|
||||
snt.nest.map(lambda x: tf.expand_dims(x, 0),
|
||||
snt.nest.flatten_iterable(self._obs)))
|
||||
self._action = self._agent_net(batch_obs)
|
||||
saver = tf.train.Saver()
|
||||
saver.restore(
|
||||
sess=self._session,
|
||||
save_path=self._ckpt_path)
|
||||
|
||||
def __call__(self, observation):
|
||||
out_action = self._session.run(self._action, feed_dict={self._obs: observation})
|
||||
return out_action[0]
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import envs
|
||||
from .. import pybullet_envs
|
||||
import time
|
||||
|
||||
def relu(x):
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import envs
|
||||
import pybullet_envs
|
||||
import time
|
||||
|
||||
def relu(x):
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import envs
|
||||
import pybullet_envs
|
||||
import time
|
||||
|
||||
def relu(x):
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import envs
|
||||
import pybullet_envs
|
||||
import time
|
||||
|
||||
def relu(x):
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import envs
|
||||
import pybullet_envs
|
||||
import time
|
||||
|
||||
def relu(x):
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import envs
|
||||
import pybullet_envs
|
||||
import time
|
||||
|
||||
def relu(x):
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import envs
|
||||
import pybullet_envs
|
||||
import time
|
||||
|
||||
def relu(x):
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
import gym
|
||||
from envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
|
||||
from baselines import deepq
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import gym
|
||||
|
||||
from baselines import deepq
|
||||
from envs.bullet.cartpole_bullet import CartPoleBulletEnv
|
||||
from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv
|
||||
|
||||
def main():
|
||||
env = gym.make('CartPoleBulletEnv-v0')
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
import gym
|
||||
from envs.bullet.racecarGymEnv import RacecarGymEnv
|
||||
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
||||
|
||||
from baselines import deepq
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
import gym
|
||||
from envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
||||
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
||||
|
||||
from baselines import deepq
|
||||
|
||||
|
||||
@@ -1,7 +0,0 @@
|
||||
from envs.bullet.cartpole_bullet import CartPoleBulletEnv
|
||||
from envs.bullet.minitaur_bullet import MinitaurBulletEnv
|
||||
from envs.bullet.racecarGymEnv import RacecarGymEnv
|
||||
from envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
||||
from envs.bullet.simpleHumanoidGymEnv import SimpleHumanoidGymEnv
|
||||
from envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
from envs.bullet.kukaCamGymEnv import KukaCamGymEnv
|
||||
@@ -1,5 +1,5 @@
|
||||
|
||||
from envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
import time
|
||||
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
|
||||
from envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
import time
|
||||
|
||||
|
||||
|
||||
@@ -9,7 +9,7 @@ import math
|
||||
import numpy as np
|
||||
import tensorflow as tf
|
||||
|
||||
from envs.bullet.minitaurGymEnv import MinitaurGymEnv
|
||||
from pybullet_envs.bullet.minitaurGymEnv import MinitaurGymEnv
|
||||
|
||||
try:
|
||||
import sonnet
|
||||
|
||||
@@ -4,131 +4,131 @@ from gym.envs.registration import registry, register, make, spec
|
||||
|
||||
register(
|
||||
id='CartPoleBulletEnv-v0',
|
||||
entry_point='envs.bullet:CartPoleBulletEnv',
|
||||
entry_point='pybullet_envs.bullet:CartPoleBulletEnv',
|
||||
timestep_limit=1000,
|
||||
reward_threshold=950.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='MinitaurBulletEnv-v0',
|
||||
entry_point='envs.bullet:MinitaurBulletEnv',
|
||||
entry_point='pybullet_envs.bullet:MinitaurBulletEnv',
|
||||
timestep_limit=1000,
|
||||
reward_threshold=5.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='RacecarBulletEnv-v0',
|
||||
entry_point='envs.bullet:RacecarBulletEnv',
|
||||
entry_point='pybullet_envs.bullet:RacecarBulletEnv',
|
||||
timestep_limit=1000,
|
||||
reward_threshold=5.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='RacecarZedBulletEnv-v0',
|
||||
entry_point='envs.bullet:RacecarZEDGymEnv',
|
||||
entry_point='pybullet_envs.bullet:RacecarZEDGymEnv',
|
||||
timestep_limit=1000,
|
||||
reward_threshold=5.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='SimpleHumanoidBulletEnv-v0',
|
||||
entry_point='envs.bullet:SimpleHumanoidGymEnv',
|
||||
entry_point='pybullet_envs.bullet:SimpleHumanoidGymEnv',
|
||||
timestep_limit=1000,
|
||||
reward_threshold=5.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='KukaBulletEnv-v0',
|
||||
entry_point='envs.bullet:KukaGymEnv',
|
||||
entry_point='pybullet_envs.bullet:KukaGymEnv',
|
||||
timestep_limit=1000,
|
||||
reward_threshold=5.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='KukaCamBulletEnv-v0',
|
||||
entry_point='envs.bullet:KukaCamGymEnv',
|
||||
entry_point='pybullet_envs.bullet:KukaCamGymEnv',
|
||||
timestep_limit=1000,
|
||||
reward_threshold=5.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='InvertedPendulumBulletEnv-v0',
|
||||
entry_point='envs.gym_pendulum_envs:InvertedPendulumBulletEnv',
|
||||
entry_point='pybullet_envs.gym_pendulum_envs:InvertedPendulumBulletEnv',
|
||||
max_episode_steps=1000,
|
||||
reward_threshold=950.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='InvertedDoublePendulumBulletEnv-v0',
|
||||
entry_point='envs.gym_pendulum_envs:InvertedDoublePendulumBulletEnv',
|
||||
entry_point='pybullet_envs.gym_pendulum_envs:InvertedDoublePendulumBulletEnv',
|
||||
max_episode_steps=1000,
|
||||
reward_threshold=9100.0,
|
||||
)
|
||||
|
||||
register(
|
||||
id='InvertedPendulumSwingupBulletEnv-v0',
|
||||
entry_point='envs.gym_pendulum_envs:InvertedPendulumSwingupBulletEnv',
|
||||
entry_point='pybullet_envs.gym_pendulum_envs:InvertedPendulumSwingupBulletEnv',
|
||||
max_episode_steps=1000,
|
||||
reward_threshold=800.0,
|
||||
)
|
||||
|
||||
# register(
|
||||
# id='ReacherBulletEnv-v0',
|
||||
# entry_point='envs.gym_manipulator_envs:ReacherBulletEnv',
|
||||
# entry_point='pybullet_envs.gym_manipulator_envs:ReacherBulletEnv',
|
||||
# max_episode_steps=150,
|
||||
# reward_threshold=18.0,
|
||||
# )
|
||||
#
|
||||
# register(
|
||||
# id='PusherBulletEnv-v0',
|
||||
# entry_point='envs.gym_manipulator_envs:PusherBulletEnv',
|
||||
# entry_point='pybullet_envs.gym_manipulator_envs:PusherBulletEnv',
|
||||
# max_episode_steps=150,
|
||||
# reward_threshold=18.0,
|
||||
# )
|
||||
#
|
||||
# register(
|
||||
# id='ThrowerBulletEnv-v0',
|
||||
# entry_point='envs.gym_manipulator_envs:ThrowerBulletEnv',
|
||||
# entry_point='pybullet_envs.gym_manipulator_envs:ThrowerBulletEnv',
|
||||
# max_episode_steps=100,
|
||||
# reward_threshold=18.0,
|
||||
# )
|
||||
#
|
||||
# register(
|
||||
# id='StrikerBulletEnv-v0',
|
||||
# entry_point='envs.gym_manipulator_envs:StrikerBulletEnv',
|
||||
# entry_point='pybullet_envs.gym_manipulator_envs:StrikerBulletEnv',
|
||||
# max_episode_steps=100,
|
||||
# reward_threshold=18.0,
|
||||
# )
|
||||
|
||||
register(
|
||||
id='Walker2DBulletEnv-v0',
|
||||
entry_point='envs.gym_locomotion_envs:Walker2DBulletEnv',
|
||||
entry_point='pybullet_envs.gym_locomotion_envs:Walker2DBulletEnv',
|
||||
max_episode_steps=1000,
|
||||
reward_threshold=2500.0
|
||||
)
|
||||
register(
|
||||
id='HalfCheetahBulletEnv-v0',
|
||||
entry_point='envs.gym_locomotion_envs:HalfCheetahBulletEnv',
|
||||
entry_point='pybullet_envs.gym_locomotion_envs:HalfCheetahBulletEnv',
|
||||
max_episode_steps=1000,
|
||||
reward_threshold=3000.0
|
||||
)
|
||||
|
||||
register(
|
||||
id='AntBulletEnv-v0',
|
||||
entry_point='envs.gym_locomotion_envs:AntBulletEnv',
|
||||
entry_point='pybullet_envs.gym_locomotion_envs:AntBulletEnv',
|
||||
max_episode_steps=1000,
|
||||
reward_threshold=2500.0
|
||||
)
|
||||
|
||||
register(
|
||||
id='HumanoidBulletEnv-v0',
|
||||
entry_point='envs.gym_locomotion_envs:HumanoidBulletEnv',
|
||||
entry_point='pybullet_envs.gym_locomotion_envs:HumanoidBulletEnv',
|
||||
max_episode_steps=1000
|
||||
)
|
||||
|
||||
register(
|
||||
id='HopperBulletEnv-v0',
|
||||
entry_point='envs.gym_locomotion_envs:HopperBulletEnv',
|
||||
entry_point='pybullet_envs.gym_locomotion_envs:HopperBulletEnv',
|
||||
max_episode_steps=1000,
|
||||
reward_threshold=2500.0
|
||||
)
|
||||
)
|
||||
7
examples/pybullet/gym/pybullet_envs/bullet/__init__.py
Normal file
7
examples/pybullet/gym/pybullet_envs/bullet/__init__.py
Normal file
@@ -0,0 +1,7 @@
|
||||
from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv
|
||||
from pybullet_envs.bullet.minitaur_bullet import MinitaurBulletEnv
|
||||
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
||||
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
||||
from pybullet_envs.bullet.simpleHumanoidGymEnv import SimpleHumanoidGymEnv
|
||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
from pybullet_envs.bullet.kukaCamGymEnv import KukaCamGymEnv
|
||||
@@ -76,7 +76,7 @@ class CartPoleBulletEnv(gym.Env):
|
||||
def _reset(self):
|
||||
# print("-----------reset simulation---------------")
|
||||
p.resetSimulation()
|
||||
self.cartpole = p.loadURDF("cartpole.urdf",[0,0,0])
|
||||
self.cartpole = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","cartpole.urdf"),[0,0,0])
|
||||
self.timeStep = 0.01
|
||||
p.setJointMotorControl2(self.cartpole, 1, p.VELOCITY_CONTROL, force=0)
|
||||
p.setGravity(0,0, -10)
|
||||
@@ -1,3 +1,4 @@
|
||||
import os
|
||||
import pybullet as p
|
||||
import numpy as np
|
||||
import copy
|
||||
@@ -31,7 +32,7 @@ class Kuka:
|
||||
self.reset()
|
||||
|
||||
def reset(self):
|
||||
objects = p.loadSDF("kuka_iiwa/kuka_with_gripper2.sdf")
|
||||
objects = p.loadSDF(os.path.join(os.path.dirname(__file__),"../data","kuka_iiwa/kuka_with_gripper2.sdf"))
|
||||
self.kukaUid = objects[0]
|
||||
#for i in range (p.getNumJoints(self.kukaUid)):
|
||||
# print(p.getJointInfo(self.kukaUid,i))
|
||||
@@ -42,7 +43,7 @@ class Kuka:
|
||||
p.resetJointState(self.kukaUid,jointIndex,self.jointPositions[jointIndex])
|
||||
p.setJointMotorControl2(self.kukaUid,jointIndex,p.POSITION_CONTROL,targetPosition=self.jointPositions[jointIndex],force=self.maxForce)
|
||||
|
||||
self.trayUid = p.loadURDF("tray/tray.urdf", 0.640000,0.075000,-0.190000,0.000000,0.000000,1.000000,0.000000)
|
||||
self.trayUid = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","tray/tray.urdf"), 0.640000,0.075000,-0.190000,0.000000,0.000000,1.000000,0.000000)
|
||||
self.endEffectorPos = [0.537,0.0,0.5]
|
||||
self.endEffectorAngle = 0
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
import os
|
||||
import math
|
||||
import gym
|
||||
from gym import spaces
|
||||
@@ -54,15 +55,15 @@ class KukaCamGymEnv(gym.Env):
|
||||
p.resetSimulation()
|
||||
p.setPhysicsEngineParameter(numSolverIterations=150)
|
||||
p.setTimeStep(self._timeStep)
|
||||
p.loadURDF("%splane.urdf" % self._urdfRoot,[0,0,-1])
|
||||
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"),[0,0,-1])
|
||||
|
||||
p.loadURDF("table/table.urdf", 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
|
||||
p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
|
||||
|
||||
xpos = 0.5 +0.05*random.random()
|
||||
ypos = 0 +0.05*random.random()
|
||||
ang = 3.1415925438*random.random()
|
||||
orn = p.getQuaternionFromEuler([0,0,ang])
|
||||
self.blockUid =p.loadURDF("block.urdf", xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
|
||||
self.blockUid =p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","block.urdf"), xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
|
||||
|
||||
p.setGravity(0,0,-10)
|
||||
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
|
||||
@@ -6,7 +6,7 @@ import numpy as np
|
||||
import time
|
||||
|
||||
import pybullet as p
|
||||
from envs.bullet.minitaur import Minitaur
|
||||
from pybullet_envs.bullet.minitaur import Minitaur
|
||||
|
||||
class MinitaurBulletEnv(gym.Env):
|
||||
metadata = {
|
||||
29
examples/pybullet/gym/pybullet_envs/data/block.urdf
Normal file
29
examples/pybullet/gym/pybullet_envs/data/block.urdf
Normal file
@@ -0,0 +1,29 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot name="block_2">
|
||||
<link name="block_2_base_link">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<spinning_friction value=".001"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="0.02"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<geometry>
|
||||
<box size="0.10 0.018 0.018"/>
|
||||
</geometry>
|
||||
<material name="blockmat">
|
||||
<color rgba="0.1 0.7 0.1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||
<geometry>
|
||||
<box size="0.10 0.018 0.018"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
74
examples/pybullet/gym/pybullet_envs/data/cartpole.urdf
Normal file
74
examples/pybullet/gym/pybullet_envs/data/cartpole.urdf
Normal file
@@ -0,0 +1,74 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot name="physics">
|
||||
|
||||
<link name="slideBar">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="30 0.05 0.05"/>
|
||||
</geometry>
|
||||
<origin xyz="0 0 0"/>
|
||||
<material name="green">
|
||||
<color rgba="0 0.8 .8 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="0"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="cart">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.5 0.5 0.2"/>
|
||||
</geometry>
|
||||
<origin xyz="0 0 0"/>
|
||||
<material name="blue">
|
||||
<color rgba="0 0 .8 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.5 0.5 0.2"/>
|
||||
</geometry>
|
||||
<origin xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="1"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="slider_to_cart" type="prismatic">
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin xyz="0.0 0.0 0.0"/>
|
||||
<parent link="slideBar"/>
|
||||
<child link="cart"/>
|
||||
<limit effort="1000.0" lower="-15" upper="15" velocity="5"/>
|
||||
</joint>
|
||||
|
||||
<link name="pole">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 1.0"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.5"/>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.5"/>
|
||||
<mass value="10"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="cart_to_pole" type="continuous">
|
||||
<axis xyz="0 1 0"/>
|
||||
<origin xyz="0.0 0.0 0"/>
|
||||
<parent link="cart"/>
|
||||
<child link="pole"/>
|
||||
</joint>
|
||||
|
||||
</robot>
|
||||
BIN
examples/pybullet/gym/pybullet_envs/data/checker_blue.png
Normal file
BIN
examples/pybullet/gym/pybullet_envs/data/checker_blue.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 6.2 KiB |
@@ -0,0 +1,802 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!--This file contains the SDF model of a KUKA iiwa robot with a wsg50 gripper.
|
||||
It has been produced from the varients in //third_party/robotics/models.
|
||||
Note: This file is temporary, and should be deleted once Bullet supports
|
||||
importing models in SDF. Also, this file has been specialized for Bullet,
|
||||
because the mass of the base link has been set to 0, as needed by Bullet.
|
||||
Note: All of the gripper link poses have been adjusted in the z direction
|
||||
to achieve a reasonable position of the gripper relative to the arm.
|
||||
Note: The joint names for the KUKA have been changed to J0, J1, etc. -->
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='lbr_iiwa_with_wsg50'>
|
||||
<link name='lbr_iiwa_link_0'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.1 0 0.07 0 -0 0</pose>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.03</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_0_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>/meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_0_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_0.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1.0</diffuse>
|
||||
<specular>0.4 0.4 0.4 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name='lbr_iiwa_link_1'>
|
||||
<pose frame=''>0 0 0.1575 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 -0.03 0.12 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.09</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.02</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_1_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_1_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J0' type='revolute'>
|
||||
<child>lbr_iiwa_link_1</child>
|
||||
<parent>lbr_iiwa_link_0</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_2'>
|
||||
<pose frame=''>0 0 0.36 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0003 0.059 0.042 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.044</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_2_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_2_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J1' type='revolute'>
|
||||
<child>lbr_iiwa_link_2</child>
|
||||
<parent>lbr_iiwa_link_1</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_3'>
|
||||
<pose frame=''>0 -0 0.5645 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.03 0.13 0 -0 0</pose>
|
||||
<mass>3</mass>
|
||||
<inertia>
|
||||
<ixx>0.08</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.075</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.01</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_3_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_3_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J2' type='revolute'>
|
||||
<child>lbr_iiwa_link_3</child>
|
||||
<parent>lbr_iiwa_link_2</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_4'>
|
||||
<pose frame=''>0 -0 0.78 1.5708 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.067 0.034 0 -0 0</pose>
|
||||
<mass>2.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.03</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.01</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.029</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_4_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_4_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J3' type='revolute'>
|
||||
<child>lbr_iiwa_link_4</child>
|
||||
<parent>lbr_iiwa_link_3</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_5'>
|
||||
<pose frame=''>0 -0 0.9645 0 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0001 0.021 0.076 0 -0 0</pose>
|
||||
<mass>1.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.02</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.005</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_5_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_5_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J4' type='revolute'>
|
||||
<child>lbr_iiwa_link_5</child>
|
||||
<parent>lbr_iiwa_link_4</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_6'>
|
||||
<pose frame=''>0 0 1.18 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.0006 0.0004 0 -0 0</pose>
|
||||
<mass>1.8</mass>
|
||||
<inertia>
|
||||
<ixx>0.005</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0036</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0047</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_6_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_6_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J5' type='revolute'>
|
||||
<child>lbr_iiwa_link_6</child>
|
||||
<parent>lbr_iiwa_link_5</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_7'>
|
||||
<pose frame=''>0 0 1.261 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.02 0 -0 0</pose>
|
||||
<mass>0.3</mass>
|
||||
<inertia>
|
||||
<ixx>0.001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_7_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_7_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J6' type='revolute'>
|
||||
<child>lbr_iiwa_link_7</child>
|
||||
<parent>lbr_iiwa_link_6</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.05433</lower>
|
||||
<upper>3.05433</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<!-- Attach the base of the gripper to the end of the arm -->
|
||||
<joint name='gripper_to_arm' type='fixed'>
|
||||
<parent>lbr_iiwa_link_7</parent>
|
||||
<child>base_link</child>
|
||||
</joint>
|
||||
<link name='base_link'>
|
||||
<pose frame=''>0 0 1.305 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<mass>1.2</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='base_link_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.1 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_left_finger_joint' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>left_finger</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.4</lower>
|
||||
<upper>10.01</upper>
|
||||
<effort>100</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='left_finger'>
|
||||
<pose frame=''>0 0.024 1.35 0 -0.05 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='left_finger_visual'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.08</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='left_finger_base_joint' type='fixed'>
|
||||
<parent>left_finger</parent>
|
||||
<child>left_finger_base</child>
|
||||
</joint>
|
||||
<link name='left_finger_base'>
|
||||
<pose frame=''>-0.005 0.024 1.43 0 -0.3 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.003 0 0.04 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='left_finger_base_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='left_finger_base_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='left_base_tip_joint' type='revolute'>
|
||||
<parent>left_finger_base</parent>
|
||||
<child>left_finger_tip</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.1</lower>
|
||||
<upper>10.3</upper>
|
||||
<effort>0</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='left_finger_tip'>
|
||||
<contact>
|
||||
<lateral_friction>0.8</lateral_friction>
|
||||
<spinning_friction>1.0</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>-0.02 0.024 1.49 0 0.2 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.005 0 0.026 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='left_finger_tip_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='left_finger_tip_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='base_right_finger_joint' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>right_finger</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.01</lower>
|
||||
<upper>10.4</upper>
|
||||
<effort>100</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='right_finger'>
|
||||
<pose frame=''>0 0.024 1.35 0 0.05 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='right_finger_visual'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.08</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='right_finger_base_joint' type='fixed'>
|
||||
<parent>right_finger</parent>
|
||||
<child>right_finger_base</child>
|
||||
</joint>
|
||||
<link name='right_finger_base'>
|
||||
<pose frame=''>0.005 0.024 1.43 0 0.3 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.003 0 0.04 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='right_finger_base_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='right_finger_base_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='right_base_tip_joint' type='revolute'>
|
||||
<parent>right_finger_base</parent>
|
||||
<child>right_finger_tip</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.3</lower>
|
||||
<upper>10.1</upper>
|
||||
<effort>0</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='right_finger_tip'>
|
||||
<contact>
|
||||
<lateral_friction>0.8</lateral_friction>
|
||||
<spinning_friction>1.0</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>0.02 0.024 1.49 0 -0.2 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.005 0 0.026 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='right_finger_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='right_finger_tip_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,857 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!--This file contains the SDF model of a KUKA iiwa robot with a wsg50 gripper.
|
||||
It has been produced from the varients in //third_party/robotics/models.
|
||||
Note: This file is temporary, and should be deleted once Bullet supports
|
||||
importing models in SDF. Also, this file has been specialized for Bullet,
|
||||
because the mass of the base link has been set to 0, as needed by Bullet.
|
||||
Note: All of the gripper link poses have been adjusted in the z direction
|
||||
to achieve a reasonable position of the gripper relative to the arm.
|
||||
Note: The joint names for the KUKA have been changed to J0, J1, etc. -->
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='lbr_iiwa_with_wsg50'>
|
||||
<link name='lbr_iiwa_link_0'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.1 0 0.07 0 -0 0</pose>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.03</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_0_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>/meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_0_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_0.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1.0</diffuse>
|
||||
<specular>0.4 0.4 0.4 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name='lbr_iiwa_link_1'>
|
||||
<pose frame=''>0 0 0.1575 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 -0.03 0.12 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.09</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.02</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_1_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_1_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J0' type='revolute'>
|
||||
<child>lbr_iiwa_link_1</child>
|
||||
<parent>lbr_iiwa_link_0</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_2'>
|
||||
<pose frame=''>0 0 0.36 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0003 0.059 0.042 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.044</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_2_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_2_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J1' type='revolute'>
|
||||
<child>lbr_iiwa_link_2</child>
|
||||
<parent>lbr_iiwa_link_1</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_3'>
|
||||
<pose frame=''>0 -0 0.5645 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.03 0.13 0 -0 0</pose>
|
||||
<mass>3</mass>
|
||||
<inertia>
|
||||
<ixx>0.08</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.075</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.01</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_3_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_3_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J2' type='revolute'>
|
||||
<child>lbr_iiwa_link_3</child>
|
||||
<parent>lbr_iiwa_link_2</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_4'>
|
||||
<pose frame=''>0 -0 0.78 1.5708 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.067 0.034 0 -0 0</pose>
|
||||
<mass>2.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.03</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.01</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.029</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_4_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_4_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J3' type='revolute'>
|
||||
<child>lbr_iiwa_link_4</child>
|
||||
<parent>lbr_iiwa_link_3</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_5'>
|
||||
<pose frame=''>0 -0 0.9645 0 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0001 0.021 0.076 0 -0 0</pose>
|
||||
<mass>1.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.02</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.005</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_5_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_5_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J4' type='revolute'>
|
||||
<child>lbr_iiwa_link_5</child>
|
||||
<parent>lbr_iiwa_link_4</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_6'>
|
||||
<pose frame=''>0 0 1.18 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.0006 0.0004 0 -0 0</pose>
|
||||
<mass>1.8</mass>
|
||||
<inertia>
|
||||
<ixx>0.005</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0036</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0047</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_6_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_6_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J5' type='revolute'>
|
||||
<child>lbr_iiwa_link_6</child>
|
||||
<parent>lbr_iiwa_link_5</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_7'>
|
||||
<pose frame=''>0 0 1.261 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.02 0 -0 0</pose>
|
||||
<mass>1.3</mass>
|
||||
<inertia>
|
||||
<ixx>0.001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_7_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_7_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='J6' type='revolute'>
|
||||
<child>lbr_iiwa_link_7</child>
|
||||
<parent>lbr_iiwa_link_6</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.05433</lower>
|
||||
<upper>3.05433</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<!-- Attach the base of the gripper to the end of the arm -->
|
||||
<joint name='gripper_to_arm' type='continuous'>
|
||||
<parent>lbr_iiwa_link_7</parent>
|
||||
<child>base_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
|
||||
|
||||
<link name='base_link'>
|
||||
<pose frame=''>0 0 1.305 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='base_link_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.1 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='base_link_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.1 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name='base_left_finger_joint' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>left_finger</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.4</lower>
|
||||
<upper>10.01</upper>
|
||||
<effort>100</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='left_finger'>
|
||||
<pose frame=''>0 0.024 1.35 0 -0.05 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='left_finger_visual'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.08</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='left_finger_collision'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.08</size>
|
||||
</box>
|
||||
</geometry>
|
||||
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='left_finger_base_joint' type='fixed'>
|
||||
<parent>left_finger</parent>
|
||||
<child>left_finger_base</child>
|
||||
</joint>
|
||||
<link name='left_finger_base'>
|
||||
<contact>
|
||||
<lateral_friction>0.8</lateral_friction>
|
||||
<spinning_friction>.1</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>-0.005 0.024 1.43 0 -0.3 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.003 0 0.04 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='left_finger_base_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='left_finger_base_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='left_base_tip_joint' type='revolute'>
|
||||
<parent>left_finger_base</parent>
|
||||
<child>left_finger_tip</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.1</lower>
|
||||
<upper>10.3</upper>
|
||||
<effort>0</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='left_finger_tip'>
|
||||
<contact>
|
||||
<lateral_friction>0.8</lateral_friction>
|
||||
<spinning_friction>.1</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>-0.02 0.024 1.49 0 0.2 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.005 0 0.026 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='left_finger_tip_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='left_finger_tip_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_left.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='base_right_finger_joint' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>right_finger</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.01</lower>
|
||||
<upper>10.4</upper>
|
||||
<effort>100</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='right_finger'>
|
||||
<contact>
|
||||
<lateral_friction>0.8</lateral_friction>
|
||||
<spinning_friction>.1</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>0 0.024 1.35 0 0.05 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='right_finger_visual'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.08</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='right_finger_collision'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.08</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='right_finger_base_joint' type='fixed'>
|
||||
<parent>right_finger</parent>
|
||||
<child>right_finger_base</child>
|
||||
</joint>
|
||||
<link name='right_finger_base'>
|
||||
<contact>
|
||||
<lateral_friction>0.8</lateral_friction>
|
||||
<spinning_friction>.1</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>0.005 0.024 1.43 0 0.3 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.003 0 0.04 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='right_finger_base_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='right_finger_base_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_base_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name='right_base_tip_joint' type='revolute'>
|
||||
<parent>right_finger_base</parent>
|
||||
<child>right_finger_tip</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-10.3</lower>
|
||||
<upper>10.1</upper>
|
||||
<effort>0</effort>
|
||||
<velocity>0</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='right_finger_tip'>
|
||||
<contact>
|
||||
<lateral_friction>0.8</lateral_friction>
|
||||
<spinning_friction>.1</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>0.02 0.024 1.49 0 -0.2 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.005 0 0.026 0 0 0 </pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='right_finger_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.6 0.6 0.6 1</diffuse>
|
||||
<specular>0.5 0.5 0.5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='right_finger_tip_collision'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/finger_tip_right.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,414 @@
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='lbr_iiwa'>
|
||||
<joint name='fix_to_world' type='fixed'>
|
||||
<parent>world</parent>
|
||||
<child>lbr_iiwa_link_0</child>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_0'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.1 0 0.07 0 -0 0</pose>
|
||||
<mass>0.01</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.03</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_0_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_0_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name='lbr_iiwa_link_1'>
|
||||
<pose frame=''>0 0 0.1575 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 -0.03 0.12 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.09</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.02</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_1_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_1_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_1' type='revolute'>
|
||||
<child>lbr_iiwa_link_1</child>
|
||||
<parent>lbr_iiwa_link_0</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_2'>
|
||||
<pose frame=''>0 0 0.36 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0003 0.059 0.042 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.044</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_2_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_2_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_2' type='revolute'>
|
||||
<child>lbr_iiwa_link_2</child>
|
||||
<parent>lbr_iiwa_link_1</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_3'>
|
||||
<pose frame=''>0 -0 0.5645 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.03 0.13 0 -0 0</pose>
|
||||
<mass>3</mass>
|
||||
<inertia>
|
||||
<ixx>0.08</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.075</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.01</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_3_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_3_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_3' type='revolute'>
|
||||
<child>lbr_iiwa_link_3</child>
|
||||
<parent>lbr_iiwa_link_2</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_4'>
|
||||
<pose frame=''>0 -0 0.78 1.5708 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.067 0.034 0 -0 0</pose>
|
||||
<mass>2.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.03</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.01</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.029</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_4_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_4_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_4' type='revolute'>
|
||||
<child>lbr_iiwa_link_4</child>
|
||||
<parent>lbr_iiwa_link_3</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_5'>
|
||||
<pose frame=''>0 -0 0.9645 0 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0001 0.021 0.076 0 -0 0</pose>
|
||||
<mass>1.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.02</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.005</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_5_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_5_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_5' type='revolute'>
|
||||
<child>lbr_iiwa_link_5</child>
|
||||
<parent>lbr_iiwa_link_4</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_6'>
|
||||
<pose frame=''>0 0 1.18 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.0006 0.0004 0 -0 0</pose>
|
||||
<mass>1.8</mass>
|
||||
<inertia>
|
||||
<ixx>0.005</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0036</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0047</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_6_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_6_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_6' type='revolute'>
|
||||
<child>lbr_iiwa_link_6</child>
|
||||
<parent>lbr_iiwa_link_5</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_7'>
|
||||
<pose frame=''>0 0 1.261 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.02 0 -0 0</pose>
|
||||
<mass>0.3</mass>
|
||||
<inertia>
|
||||
<ixx>0.001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_7_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_7_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_7' type='revolute'>
|
||||
<child>lbr_iiwa_link_7</child>
|
||||
<parent>lbr_iiwa_link_6</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.05433</lower>
|
||||
<upper>3.05433</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_base_left.stl
Executable file
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_base_left.stl
Executable file
Binary file not shown.
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_base_right.stl
Executable file
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_base_right.stl
Executable file
Binary file not shown.
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_tip_left.stl
Executable file
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_tip_left.stl
Executable file
Binary file not shown.
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_tip_right.stl
Executable file
BIN
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/finger_tip_right.stl
Executable file
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
6055
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_0.obj
Normal file
6055
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_0.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
5576
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_1.obj
Normal file
5576
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_1.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
2948
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_2.obj
Normal file
2948
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_2.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
3924
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_3.obj
Normal file
3924
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_3.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
3168
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_4.obj
Normal file
3168
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_4.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
2732
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_5.obj
Normal file
2732
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_5.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
2328
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_6.obj
Normal file
2328
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_6.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
3155
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_7.obj
Normal file
3155
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/meshes/link_7.obj
Normal file
File diff suppressed because it is too large
Load Diff
Binary file not shown.
459
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/model.sdf
Normal file
459
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/model.sdf
Normal file
@@ -0,0 +1,459 @@
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='lbr_iiwa'>
|
||||
<pose frame=''>0 -2.3 0.7 0 0 0</pose>
|
||||
<link name='lbr_iiwa_link_0'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.1 0 0.07 0 -0 0</pose>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.03</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_0_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_0_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name='lbr_iiwa_link_1'>
|
||||
<pose frame=''>0 0 0.1575 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 -0.03 0.12 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.09</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.02</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_1_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_1_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_1' type='revolute'>
|
||||
<child>lbr_iiwa_link_1</child>
|
||||
<parent>lbr_iiwa_link_0</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_2'>
|
||||
<pose frame=''>0 0 0.36 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0003 0.059 0.042 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.044</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_2_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_2_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_2' type='revolute'>
|
||||
<child>lbr_iiwa_link_2</child>
|
||||
<parent>lbr_iiwa_link_1</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_3'>
|
||||
<pose frame=''>0 -0 0.5645 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.03 0.13 0 -0 0</pose>
|
||||
<mass>3</mass>
|
||||
<inertia>
|
||||
<ixx>0.08</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.075</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.01</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_3_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_3_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>1.0 0.42 0.04 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_3' type='revolute'>
|
||||
<child>lbr_iiwa_link_3</child>
|
||||
<parent>lbr_iiwa_link_2</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_4'>
|
||||
<pose frame=''>0 -0 0.78 1.5708 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.067 0.034 0 -0 0</pose>
|
||||
<mass>2.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.03</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.01</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.029</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_4_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_4_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_4' type='revolute'>
|
||||
<child>lbr_iiwa_link_4</child>
|
||||
<parent>lbr_iiwa_link_3</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_5'>
|
||||
<pose frame=''>0 -0 0.9645 0 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0001 0.021 0.076 0 -0 0</pose>
|
||||
<mass>1.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.02</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.005</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_5_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_5_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.5 0.7 1.0 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_5' type='revolute'>
|
||||
<child>lbr_iiwa_link_5</child>
|
||||
<parent>lbr_iiwa_link_4</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_6'>
|
||||
<pose frame=''>0 0 1.18 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.0006 0.0004 0 -0 0</pose>
|
||||
<mass>1.8</mass>
|
||||
<inertia>
|
||||
<ixx>0.005</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0036</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0047</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_6_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_6_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>1.0 0.42 0.04 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_6' type='revolute'>
|
||||
<child>lbr_iiwa_link_6</child>
|
||||
<parent>lbr_iiwa_link_5</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_7'>
|
||||
<pose frame=''>0 0 1.261 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.02 0 -0 0</pose>
|
||||
<mass>0.3</mass>
|
||||
<inertia>
|
||||
<ixx>0.001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_7_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_7_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_7' type='revolute'>
|
||||
<child>lbr_iiwa_link_7</child>
|
||||
<parent>lbr_iiwa_link_6</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.05433</lower>
|
||||
<upper>3.05433</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
289
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/model.urdf
Normal file
289
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/model.urdf
Normal file
@@ -0,0 +1,289 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!-- ======================================================================= -->
|
||||
<!-- | This document was autogenerated by xacro from lbr_iiwa.urdf.xacro | -->
|
||||
<!-- | Original xacro: https://github.com/rtkg/lbr_iiwa/archive/master.zip | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- | Changes (kohlhoff): | -->
|
||||
<!-- | * Removed gazebo tags. | -->
|
||||
<!-- | * Removed unused materials. | -->
|
||||
<!-- | * Made mesh paths relative. | -->
|
||||
<!-- | * Removed material fields from collision segments. | -->
|
||||
<!-- | * Removed the self_collision_checking segment. | -->
|
||||
<!-- | * Removed transmission segments, since they didn't match the | -->
|
||||
<!-- | convention, will have to added back later. | -->
|
||||
<!-- ======================================================================= -->
|
||||
<!--LICENSE: -->
|
||||
<!--Copyright (c) 2015, Robert Krug & Todor Stoyanov, AASS Research Center, -->
|
||||
<!--Orebro University, Sweden -->
|
||||
<!--All rights reserved. -->
|
||||
<!-- -->
|
||||
<!--Redistribution and use in source and binary forms, with or without -->
|
||||
<!--modification, are permitted provided that the following conditions are -->
|
||||
<!--met: -->
|
||||
<!-- -->
|
||||
<!--1. Redistributions of source code must retain the above copyright notice,-->
|
||||
<!-- this list of conditions and the following disclaimer. -->
|
||||
<!-- -->
|
||||
<!--2. 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. -->
|
||||
<!-- -->
|
||||
<!--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. -->
|
||||
<robot name="lbr_iiwa" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<!-- Import Rviz colors -->
|
||||
<material name="Grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="Orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="Blue">
|
||||
<color rgba="0.5 0.7 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<!--Import the lbr iiwa macro -->
|
||||
<!--Import Transmissions -->
|
||||
<!--Include Utilities -->
|
||||
<!--The following macros are adapted from the LWR 4 definitions of the RCPRG - https://github.com/RCPRG-ros-pkg/lwr_robot -->
|
||||
<!--Little helper macros to define the inertia matrix needed for links.-->
|
||||
<!--Cuboid-->
|
||||
<!--Cylinder: length is along the y-axis! -->
|
||||
<!--lbr-->
|
||||
<link name="lbr_iiwa_link_0">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.1 0 0.07"/>
|
||||
<!--Increase mass from 5 Kg original to provide a stable base to carry the
|
||||
arm.-->
|
||||
<mass value="0.0"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.06" iyz="0" izz="0.03"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_0.obj"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_0.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_0 and link_1 -->
|
||||
<joint name="lbr_iiwa_joint_1" type="revolute">
|
||||
<parent link="lbr_iiwa_link_0"/>
|
||||
<child link="lbr_iiwa_link_1"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.1575"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.03 0.12"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.09" iyz="0" izz="0.02"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_1.obj"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_1.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_1 and link_2 -->
|
||||
<joint name="lbr_iiwa_joint_2" type="revolute">
|
||||
<parent link="lbr_iiwa_link_1"/>
|
||||
<child link="lbr_iiwa_link_2"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 0.2025"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_2">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0003 0.059 0.042"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.044"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_2.obj"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_2.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_2 and link_3 -->
|
||||
<joint name="lbr_iiwa_joint_3" type="revolute">
|
||||
<parent link="lbr_iiwa_link_2"/>
|
||||
<child link="lbr_iiwa_link_3"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0.2045 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_3">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.03 0.13"/>
|
||||
<mass value="3"/>
|
||||
<inertia ixx="0.08" ixy="0" ixz="0" iyy="0.075" iyz="0" izz="0.01"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_3.obj"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_3.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_3 and link_4 -->
|
||||
<joint name="lbr_iiwa_joint_4" type="revolute">
|
||||
<parent link="lbr_iiwa_link_3"/>
|
||||
<child link="lbr_iiwa_link_4"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_4">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.067 0.034"/>
|
||||
<mass value="2.7"/>
|
||||
<inertia ixx="0.03" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.029"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_4.obj"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_4.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_4 and link_5 -->
|
||||
<joint name="lbr_iiwa_joint_5" type="revolute">
|
||||
<parent link="lbr_iiwa_link_4"/>
|
||||
<child link="lbr_iiwa_link_5"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.1845 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_5">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0001 0.021 0.076"/>
|
||||
<mass value="1.7"/>
|
||||
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.005"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_5.obj"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_5.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_5 and link_6 -->
|
||||
<joint name="lbr_iiwa_joint_6" type="revolute">
|
||||
<parent link="lbr_iiwa_link_5"/>
|
||||
<child link="lbr_iiwa_link_6"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_6">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.0006 0.0004"/>
|
||||
<mass value="1.8"/>
|
||||
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.0036" iyz="0" izz="0.0047"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_6.obj"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_6.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_6 and link_7 -->
|
||||
<joint name="lbr_iiwa_joint_7" type="revolute">
|
||||
<parent link="lbr_iiwa_link_6"/>
|
||||
<child link="lbr_iiwa_link_7"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.081 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-3.05432619099" upper="3.05432619099" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_7">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.02"/>
|
||||
<mass value="0.3"/>
|
||||
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_7.obj"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_7.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
</robot>
|
||||
|
||||
818
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/model2.sdf
Normal file
818
examples/pybullet/gym/pybullet_envs/data/kuka_iiwa/model2.sdf
Normal file
@@ -0,0 +1,818 @@
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='lbr_iiwa'>
|
||||
<link name='lbr_iiwa_link_0'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.1 0 0.07 0 -0 0</pose>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.03</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_0_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_0_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name='lbr_iiwa_link_1'>
|
||||
<pose frame=''>0 0 0.1575 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 -0.03 0.12 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.09</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.02</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_1_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_1_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_1' type='revolute'>
|
||||
<child>lbr_iiwa_link_1</child>
|
||||
<parent>lbr_iiwa_link_0</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_2'>
|
||||
<pose frame=''>0 0 0.36 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0003 0.059 0.042 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.044</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_2_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_2_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_2' type='revolute'>
|
||||
<child>lbr_iiwa_link_2</child>
|
||||
<parent>lbr_iiwa_link_1</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_3'>
|
||||
<pose frame=''>0 -0 0.5645 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.03 0.13 0 -0 0</pose>
|
||||
<mass>3</mass>
|
||||
<inertia>
|
||||
<ixx>0.08</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.075</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.01</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_3_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_3_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_3' type='revolute'>
|
||||
<child>lbr_iiwa_link_3</child>
|
||||
<parent>lbr_iiwa_link_2</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_4'>
|
||||
<pose frame=''>0 -0 0.78 1.5708 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.067 0.034 0 -0 0</pose>
|
||||
<mass>2.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.03</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.01</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.029</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_4_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_4_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_4' type='revolute'>
|
||||
<child>lbr_iiwa_link_4</child>
|
||||
<parent>lbr_iiwa_link_3</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_5'>
|
||||
<pose frame=''>0 -0 0.9645 0 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0001 0.021 0.076 0 -0 0</pose>
|
||||
<mass>1.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.02</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.005</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_5_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_5_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_5' type='revolute'>
|
||||
<child>lbr_iiwa_link_5</child>
|
||||
<parent>lbr_iiwa_link_4</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_6'>
|
||||
<pose frame=''>0 0 1.18 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.0006 0.0004 0 -0 0</pose>
|
||||
<mass>1.8</mass>
|
||||
<inertia>
|
||||
<ixx>0.005</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0036</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0047</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_6_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_6_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_6' type='revolute'>
|
||||
<child>lbr_iiwa_link_6</child>
|
||||
<parent>lbr_iiwa_link_5</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_7'>
|
||||
<pose frame=''>0 0 1.261 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.02 0 -0 0</pose>
|
||||
<mass>0.3</mass>
|
||||
<inertia>
|
||||
<ixx>0.001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_7_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_7_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_7' type='revolute'>
|
||||
<child>lbr_iiwa_link_7</child>
|
||||
<parent>lbr_iiwa_link_6</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.05433</lower>
|
||||
<upper>3.05433</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
</model>
|
||||
|
||||
<model name='lbr_iiwa'>
|
||||
<pose frame=''>2 2 0 0 -0 0</pose>
|
||||
<link name='lbr_iiwa_link_0'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>-0.1 0 0.07 0 -0 0</pose>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.03</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_0_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_0_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name='lbr_iiwa_link_1'>
|
||||
<pose frame=''>0 0 0.1575 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 -0.03 0.12 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.09</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.02</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_1_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_1_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_1' type='revolute'>
|
||||
<child>lbr_iiwa_link_1</child>
|
||||
<parent>lbr_iiwa_link_0</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_2'>
|
||||
<pose frame=''>0 0 0.36 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0003 0.059 0.042 0 -0 0</pose>
|
||||
<mass>4</mass>
|
||||
<inertia>
|
||||
<ixx>0.05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.044</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_2_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_2_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_2' type='revolute'>
|
||||
<child>lbr_iiwa_link_2</child>
|
||||
<parent>lbr_iiwa_link_1</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_3'>
|
||||
<pose frame=''>0 -0 0.5645 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.03 0.13 0 -0 0</pose>
|
||||
<mass>3</mass>
|
||||
<inertia>
|
||||
<ixx>0.08</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.075</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.01</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_3_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_3_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_3' type='revolute'>
|
||||
<child>lbr_iiwa_link_3</child>
|
||||
<parent>lbr_iiwa_link_2</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_4'>
|
||||
<pose frame=''>0 -0 0.78 1.5708 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.067 0.034 0 -0 0</pose>
|
||||
<mass>2.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.03</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.01</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.029</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_4_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_4_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_4' type='revolute'>
|
||||
<child>lbr_iiwa_link_4</child>
|
||||
<parent>lbr_iiwa_link_3</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_5'>
|
||||
<pose frame=''>0 -0 0.9645 0 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0.0001 0.021 0.076 0 -0 0</pose>
|
||||
<mass>1.7</mass>
|
||||
<inertia>
|
||||
<ixx>0.02</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.018</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.005</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_5_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_5_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_5' type='revolute'>
|
||||
<child>lbr_iiwa_link_5</child>
|
||||
<parent>lbr_iiwa_link_4</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.96706</lower>
|
||||
<upper>2.96706</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_6'>
|
||||
<pose frame=''>0 0 1.18 1.5708 -0 -3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0.0006 0.0004 0 -0 0</pose>
|
||||
<mass>1.8</mass>
|
||||
<inertia>
|
||||
<ixx>0.005</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0036</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0047</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_6_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_6_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_6' type='revolute'>
|
||||
<child>lbr_iiwa_link_6</child>
|
||||
<parent>lbr_iiwa_link_5</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-2.0944</lower>
|
||||
<upper>2.0944</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='lbr_iiwa_link_7'>
|
||||
<pose frame=''>0 0 1.261 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.02 0 -0 0</pose>
|
||||
<mass>0.3</mass>
|
||||
<inertia>
|
||||
<ixx>0.001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='lbr_iiwa_link_7_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='lbr_iiwa_link_7_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='lbr_iiwa_joint_7' type='revolute'>
|
||||
<child>lbr_iiwa_link_7</child>
|
||||
<parent>lbr_iiwa_link_6</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.05433</lower>
|
||||
<upper>3.05433</upper>
|
||||
<effort>300</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.5</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>0</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,285 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!-- ======================================================================= -->
|
||||
<!-- | This document was autogenerated by xacro from lbr_iiwa.urdf.xacro | -->
|
||||
<!-- | Original xacro: https://github.com/rtkg/lbr_iiwa/archive/master.zip | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- | Changes (kohlhoff): | -->
|
||||
<!-- | * Removed gazebo tags. | -->
|
||||
<!-- | * Removed unused materials. | -->
|
||||
<!-- | * Made mesh paths relative. | -->
|
||||
<!-- | * Removed material fields from collision segments. | -->
|
||||
<!-- | * Removed the self_collision_checking segment. | -->
|
||||
<!-- | * Removed transmission segments, since they didn't match the | -->
|
||||
<!-- | convention, will have to added back later. | -->
|
||||
<!-- ======================================================================= -->
|
||||
<!--LICENSE: -->
|
||||
<!--Copyright (c) 2015, Robert Krug & Todor Stoyanov, AASS Research Center, -->
|
||||
<!--Orebro University, Sweden -->
|
||||
<!--All rights reserved. -->
|
||||
<!-- -->
|
||||
<!--Redistribution and use in source and binary forms, with or without -->
|
||||
<!--modification, are permitted provided that the following conditions are -->
|
||||
<!--met: -->
|
||||
<!-- -->
|
||||
<!--1. Redistributions of source code must retain the above copyright notice,-->
|
||||
<!-- this list of conditions and the following disclaimer. -->
|
||||
<!-- -->
|
||||
<!--2. 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. -->
|
||||
<!-- -->
|
||||
<!--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. -->
|
||||
<robot name="lbr_iiwa" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<!-- Import Rviz colors -->
|
||||
<material name="Grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="Orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<!--Import the lbr iiwa macro -->
|
||||
<!--Import Transmissions -->
|
||||
<!--Include Utilities -->
|
||||
<!--The following macros are adapted from the LWR 4 definitions of the RCPRG - https://github.com/RCPRG-ros-pkg/lwr_robot -->
|
||||
<!--Little helper macros to define the inertia matrix needed for links.-->
|
||||
<!--Cuboid-->
|
||||
<!--Cylinder: length is along the y-axis! -->
|
||||
<!--lbr-->
|
||||
<link name="lbr_iiwa_link_0">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.1 0 0.07"/>
|
||||
<!--Increase mass from 5 Kg original to provide a stable base to carry the
|
||||
arm.-->
|
||||
<mass value="0.01"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.06" iyz="0" izz="0.03"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_0.stl"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_0.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_0 and link_1 -->
|
||||
<joint name="lbr_iiwa_joint_1" type="revolute">
|
||||
<parent link="lbr_iiwa_link_0"/>
|
||||
<child link="lbr_iiwa_link_1"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.1575"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.03 0.12"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.09" iyz="0" izz="0.02"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_1.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_1.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_1 and link_2 -->
|
||||
<joint name="lbr_iiwa_joint_2" type="revolute">
|
||||
<parent link="lbr_iiwa_link_1"/>
|
||||
<child link="lbr_iiwa_link_2"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 0.2025"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_2">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0003 0.059 0.042"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.044"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_2.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_2.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- joint between link_2 and link_3 -->
|
||||
<joint name="lbr_iiwa_joint_3" type="revolute">
|
||||
<parent link="lbr_iiwa_link_2"/>
|
||||
<child link="lbr_iiwa_link_3"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0.2045 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_3">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.03 0.13"/>
|
||||
<mass value="3"/>
|
||||
<inertia ixx="0.08" ixy="0" ixz="0" iyy="0.075" iyz="0" izz="0.01"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_3.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_3.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_3 and link_4 -->
|
||||
<joint name="lbr_iiwa_joint_4" type="revolute">
|
||||
<parent link="lbr_iiwa_link_3"/>
|
||||
<child link="lbr_iiwa_link_4"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_4">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.067 0.034"/>
|
||||
<mass value="2.7"/>
|
||||
<inertia ixx="0.03" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.029"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_4.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_4.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_4 and link_5 -->
|
||||
<joint name="lbr_iiwa_joint_5" type="revolute">
|
||||
<parent link="lbr_iiwa_link_4"/>
|
||||
<child link="lbr_iiwa_link_5"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.1845 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_5">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0001 0.021 0.076"/>
|
||||
<mass value="1.7"/>
|
||||
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.005"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_5.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_5.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_5 and link_6 -->
|
||||
<joint name="lbr_iiwa_joint_6" type="revolute">
|
||||
<parent link="lbr_iiwa_link_5"/>
|
||||
<child link="lbr_iiwa_link_6"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_6">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.0006 0.0004"/>
|
||||
<mass value="1.8"/>
|
||||
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.0036" iyz="0" izz="0.0047"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_6.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_6.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_6 and link_7 -->
|
||||
<joint name="lbr_iiwa_joint_7" type="revolute">
|
||||
<parent link="lbr_iiwa_link_6"/>
|
||||
<child link="lbr_iiwa_link_7"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.081 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-3.05432619099" upper="3.05432619099" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_7">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.02"/>
|
||||
<mass value="0.3"/>
|
||||
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_7.stl"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/coarse/link_7.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
</robot>
|
||||
@@ -0,0 +1,289 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!-- ======================================================================= -->
|
||||
<!-- | This document was autogenerated by xacro from lbr_iiwa.urdf.xacro | -->
|
||||
<!-- | Original xacro: https://github.com/rtkg/lbr_iiwa/archive/master.zip | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- | Changes (kohlhoff): | -->
|
||||
<!-- | * Removed gazebo tags. | -->
|
||||
<!-- | * Removed unused materials. | -->
|
||||
<!-- | * Made mesh paths relative. | -->
|
||||
<!-- | * Removed material fields from collision segments. | -->
|
||||
<!-- | * Removed the self_collision_checking segment. | -->
|
||||
<!-- | * Removed transmission segments, since they didn't match the | -->
|
||||
<!-- | convention, will have to added back later. | -->
|
||||
<!-- ======================================================================= -->
|
||||
<!--LICENSE: -->
|
||||
<!--Copyright (c) 2015, Robert Krug & Todor Stoyanov, AASS Research Center, -->
|
||||
<!--Orebro University, Sweden -->
|
||||
<!--All rights reserved. -->
|
||||
<!-- -->
|
||||
<!--Redistribution and use in source and binary forms, with or without -->
|
||||
<!--modification, are permitted provided that the following conditions are -->
|
||||
<!--met: -->
|
||||
<!-- -->
|
||||
<!--1. Redistributions of source code must retain the above copyright notice,-->
|
||||
<!-- this list of conditions and the following disclaimer. -->
|
||||
<!-- -->
|
||||
<!--2. 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. -->
|
||||
<!-- -->
|
||||
<!--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. -->
|
||||
<robot name="lbr_iiwa" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<!-- Import Rviz colors -->
|
||||
<material name="Grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="Orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="Blue">
|
||||
<color rgba="0.5 0.7 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<!--Import the lbr iiwa macro -->
|
||||
<!--Import Transmissions -->
|
||||
<!--Include Utilities -->
|
||||
<!--The following macros are adapted from the LWR 4 definitions of the RCPRG - https://github.com/RCPRG-ros-pkg/lwr_robot -->
|
||||
<!--Little helper macros to define the inertia matrix needed for links.-->
|
||||
<!--Cuboid-->
|
||||
<!--Cylinder: length is along the y-axis! -->
|
||||
<!--lbr-->
|
||||
<link name="lbr_iiwa_link_0">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.1 0 0.07"/>
|
||||
<!--Increase mass from 5 Kg original to provide a stable base to carry the
|
||||
arm.-->
|
||||
<mass value="0.1"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.06" iyz="0" izz="0.03"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_0.stl"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_0.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_0 and link_1 -->
|
||||
<joint name="lbr_iiwa_joint_1" type="revolute">
|
||||
<parent link="lbr_iiwa_link_0"/>
|
||||
<child link="lbr_iiwa_link_1"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.1575"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.03 0.12"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.09" iyz="0" izz="0.02"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_1.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_1.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_1 and link_2 -->
|
||||
<joint name="lbr_iiwa_joint_2" type="revolute">
|
||||
<parent link="lbr_iiwa_link_1"/>
|
||||
<child link="lbr_iiwa_link_2"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 0.2025"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_2">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0003 0.059 0.042"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.044"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_2.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_2.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_2 and link_3 -->
|
||||
<joint name="lbr_iiwa_joint_3" type="revolute">
|
||||
<parent link="lbr_iiwa_link_2"/>
|
||||
<child link="lbr_iiwa_link_3"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0.2045 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_3">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.03 0.13"/>
|
||||
<mass value="3"/>
|
||||
<inertia ixx="0.08" ixy="0" ixz="0" iyy="0.075" iyz="0" izz="0.01"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_3.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_3.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_3 and link_4 -->
|
||||
<joint name="lbr_iiwa_joint_4" type="revolute">
|
||||
<parent link="lbr_iiwa_link_3"/>
|
||||
<child link="lbr_iiwa_link_4"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_4">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.067 0.034"/>
|
||||
<mass value="2.7"/>
|
||||
<inertia ixx="0.03" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.029"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_4.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_4.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_4 and link_5 -->
|
||||
<joint name="lbr_iiwa_joint_5" type="revolute">
|
||||
<parent link="lbr_iiwa_link_4"/>
|
||||
<child link="lbr_iiwa_link_5"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.1845 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_5">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0001 0.021 0.076"/>
|
||||
<mass value="1.7"/>
|
||||
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.005"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_5.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_5.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_5 and link_6 -->
|
||||
<joint name="lbr_iiwa_joint_6" type="revolute">
|
||||
<parent link="lbr_iiwa_link_5"/>
|
||||
<child link="lbr_iiwa_link_6"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_6">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.0006 0.0004"/>
|
||||
<mass value="1.8"/>
|
||||
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.0036" iyz="0" izz="0.0047"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_6.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_6.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_6 and link_7 -->
|
||||
<joint name="lbr_iiwa_joint_7" type="revolute">
|
||||
<parent link="lbr_iiwa_link_6"/>
|
||||
<child link="lbr_iiwa_link_7"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.081 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-3.05432619099" upper="3.05432619099" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_7">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.02"/>
|
||||
<mass value="0.3"/>
|
||||
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_7.stl"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_7.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
</robot>
|
||||
|
||||
@@ -0,0 +1,289 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!-- ======================================================================= -->
|
||||
<!-- | This document was autogenerated by xacro from lbr_iiwa.urdf.xacro | -->
|
||||
<!-- | Original xacro: https://github.com/rtkg/lbr_iiwa/archive/master.zip | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- | Changes (kohlhoff): | -->
|
||||
<!-- | * Removed gazebo tags. | -->
|
||||
<!-- | * Removed unused materials. | -->
|
||||
<!-- | * Made mesh paths relative. | -->
|
||||
<!-- | * Removed material fields from collision segments. | -->
|
||||
<!-- | * Removed the self_collision_checking segment. | -->
|
||||
<!-- | * Removed transmission segments, since they didn't match the | -->
|
||||
<!-- | convention, will have to added back later. | -->
|
||||
<!-- ======================================================================= -->
|
||||
<!--LICENSE: -->
|
||||
<!--Copyright (c) 2015, Robert Krug & Todor Stoyanov, AASS Research Center, -->
|
||||
<!--Orebro University, Sweden -->
|
||||
<!--All rights reserved. -->
|
||||
<!-- -->
|
||||
<!--Redistribution and use in source and binary forms, with or without -->
|
||||
<!--modification, are permitted provided that the following conditions are -->
|
||||
<!--met: -->
|
||||
<!-- -->
|
||||
<!--1. Redistributions of source code must retain the above copyright notice,-->
|
||||
<!-- this list of conditions and the following disclaimer. -->
|
||||
<!-- -->
|
||||
<!--2. 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. -->
|
||||
<!-- -->
|
||||
<!--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. -->
|
||||
<robot name="lbr_iiwa" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<!-- Import Rviz colors -->
|
||||
<material name="Grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="Orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="Blue">
|
||||
<color rgba="0.5 0.7 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<!--Import the lbr iiwa macro -->
|
||||
<!--Import Transmissions -->
|
||||
<!--Include Utilities -->
|
||||
<!--The following macros are adapted from the LWR 4 definitions of the RCPRG - https://github.com/RCPRG-ros-pkg/lwr_robot -->
|
||||
<!--Little helper macros to define the inertia matrix needed for links.-->
|
||||
<!--Cuboid-->
|
||||
<!--Cylinder: length is along the y-axis! -->
|
||||
<!--lbr-->
|
||||
<link name="lbr_iiwa_link_0">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.1 0 0.07"/>
|
||||
<!--Increase mass from 5 Kg original to provide a stable base to carry the
|
||||
arm.-->
|
||||
<mass value="0.0"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.06" iyz="0" izz="0.03"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_0.stl"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_0.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_0 and link_1 -->
|
||||
<joint name="lbr_iiwa_joint_1" type="revolute">
|
||||
<parent link="lbr_iiwa_link_0"/>
|
||||
<child link="lbr_iiwa_link_1"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.1575"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-.96705972839" upper="0.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.03 0.12"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.09" iyz="0" izz="0.02"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_1.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_1.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_1 and link_2 -->
|
||||
<joint name="lbr_iiwa_joint_2" type="revolute">
|
||||
<parent link="lbr_iiwa_link_1"/>
|
||||
<child link="lbr_iiwa_link_2"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 0.2025"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_2">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0003 0.059 0.042"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.044"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_2.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_2.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_2 and link_3 -->
|
||||
<joint name="lbr_iiwa_joint_3" type="revolute">
|
||||
<parent link="lbr_iiwa_link_2"/>
|
||||
<child link="lbr_iiwa_link_3"/>
|
||||
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0.2045 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_3">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.03 0.13"/>
|
||||
<mass value="3"/>
|
||||
<inertia ixx="0.08" ixy="0" ixz="0" iyy="0.075" iyz="0" izz="0.01"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_3.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_3.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_3 and link_4 -->
|
||||
<joint name="lbr_iiwa_joint_4" type="revolute">
|
||||
<parent link="lbr_iiwa_link_3"/>
|
||||
<child link="lbr_iiwa_link_4"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="0.19439510239" upper="2.29439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_4">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.067 0.034"/>
|
||||
<mass value="2.7"/>
|
||||
<inertia ixx="0.03" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.029"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_4.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_4.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_4 and link_5 -->
|
||||
<joint name="lbr_iiwa_joint_5" type="revolute">
|
||||
<parent link="lbr_iiwa_link_4"/>
|
||||
<child link="lbr_iiwa_link_5"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.1845 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_5">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0001 0.021 0.076"/>
|
||||
<mass value="1.7"/>
|
||||
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.005"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_5.stl"/>
|
||||
</geometry>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_5.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_5 and link_6 -->
|
||||
<joint name="lbr_iiwa_joint_6" type="revolute">
|
||||
<parent link="lbr_iiwa_link_5"/>
|
||||
<child link="lbr_iiwa_link_6"/>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_6">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.0006 0.0004"/>
|
||||
<mass value="1.8"/>
|
||||
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.0036" iyz="0" izz="0.0047"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_6.stl"/>
|
||||
</geometry>
|
||||
<material name="Orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_6.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- joint between link_6 and link_7 -->
|
||||
<joint name="lbr_iiwa_joint_7" type="revolute">
|
||||
<parent link="lbr_iiwa_link_6"/>
|
||||
<child link="lbr_iiwa_link_7"/>
|
||||
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.081 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="300" lower="-3.05432619099" upper="3.05432619099" velocity="10"/>
|
||||
<dynamics damping="0.5"/>
|
||||
</joint>
|
||||
<link name="lbr_iiwa_link_7">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.02"/>
|
||||
<mass value="0.3"/>
|
||||
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_7.stl"/>
|
||||
</geometry>
|
||||
<material name="Grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/link_7.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
</robot>
|
||||
|
||||
71
examples/pybullet/gym/pybullet_envs/data/mjcf/ant.xml
Normal file
71
examples/pybullet/gym/pybullet_envs/data/mjcf/ant.xml
Normal file
@@ -0,0 +1,71 @@
|
||||
<mujoco model="ant">
|
||||
<compiler angle="degree" coordinate="local" inertiafromgeom="true"/>
|
||||
<option integrator="RK4" timestep="0.01"/>
|
||||
<custom>
|
||||
<numeric data="0.0 0.0 0.55 1.0 0.0 0.0 0.0 0.0 1.0 0.0 -1.0 0.0 -1.0 0.0 1.0" name="init_qpos"/>
|
||||
</custom>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="0" condim="3" density="5.0" friction="1.5 0.1 0.1" margin="0.01" rgba="0.8 0.6 0.4 1"/>
|
||||
</default>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 0.75">
|
||||
<geom name="torso_geom" pos="0 0 0" size="0.25" type="sphere"/>
|
||||
<!--joint armature="0" damping="0" limited="false" margin="0.01" name="root" pos="0 0 0" type="free"/-->
|
||||
<body name="front_left_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 0.2 0.2 0.0" name="aux_1_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body name="aux_1" pos="0.2 0.2 0">
|
||||
<joint axis="0 0 1" name="hip_1" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.2 0.2 0.0" name="left_leg_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body pos="0.2 0.2 0" name="front_left_foot">
|
||||
<joint axis="-1 1 0" name="ankle_1" pos="0.0 0.0 0.0" range="30 100" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.4 0.4 0.0" name="left_ankle_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="front_right_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 0.2 0.0" name="aux_2_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_2" pos="-0.2 0.2 0">
|
||||
<joint axis="0 0 1" name="hip_2" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 0.2 0.0" name="right_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="-0.2 0.2 0" name="front_right_foot">
|
||||
<joint axis="1 1 0" name="ankle_2" pos="0.0 0.0 0.0" range="-100 -30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.4 0.4 0.0" name="right_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_back_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 -0.2 0.0" name="aux_3_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_3" pos="-0.2 -0.2 0">
|
||||
<joint axis="0 0 1" name="hip_3" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 -0.2 0.0" name="back_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="-0.2 -0.2 0" name="left_back_foot">
|
||||
<joint axis="-1 1 0" name="ankle_3" pos="0.0 0.0 0.0" range="-100 -30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.4 -0.4 0.0" name="third_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_back_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 0.2 -0.2 0.0" name="aux_4_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body name="aux_4" pos="0.2 -0.2 0">
|
||||
<joint axis="0 0 1" name="hip_4" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.2 -0.2 0.0" name="rightback_leg_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body pos="0.2 -0.2 0" name="right_back_foot">
|
||||
<joint axis="1 1 0" name="ankle_4" pos="0.0 0.0 0.0" range="30 100" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.4 -0.4 0.0" name="fourth_ankle_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_4" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_4" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_1" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_1" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_2" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_2" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_3" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_3" gear="150"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
13
examples/pybullet/gym/pybullet_envs/data/mjcf/capsule.xml
Normal file
13
examples/pybullet/gym/pybullet_envs/data/mjcf/capsule.xml
Normal file
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom name="aux_1_geom" size="0.05 0.1" type="capsule"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom fromto="-0.1 0.0 0.0 0.1 0.0 0.0" name="aux_1_geom" size="0.05" type="capsule"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom fromto="0.0 -0.1 0.0 0.0 0.1 0.0" name="aux_1_geom" size="0.05" type="capsule"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom fromto="0.0 0.0 -0.1 0.0 0.0 0.1" name="aux_1_geom" size="0.05" type="capsule"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
13
examples/pybullet/gym/pybullet_envs/data/mjcf/cylinder.xml
Normal file
13
examples/pybullet/gym/pybullet_envs/data/mjcf/cylinder.xml
Normal file
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom name="aux_1_geom" size="0.05 0.1" type="cylinder"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom fromto="-0.1 0.0 0.0 0.1 0.0 0.0" name="aux_1_geom" size="0.05" type="cylinder"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom fromto="0.0 -0.1 0.0 0.0 0.1 0.0" name="aux_1_geom" size="0.05" type="cylinder"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom fromto="0.0 0.0 -0.1 0.0 0.0 0.1" name="aux_1_geom" size="0.05" type="cylinder"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
57
examples/pybullet/gym/pybullet_envs/data/mjcf/ground.xml
Normal file
57
examples/pybullet/gym/pybullet_envs/data/mjcf/ground.xml
Normal file
@@ -0,0 +1,57 @@
|
||||
<mujoco model="humanoid">
|
||||
<compiler angle="degree" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" iterations="50" solver="PGS" timestep="0.003">
|
||||
<!-- <flags solverstat="enable" energy="enable"/>-->
|
||||
</option>
|
||||
<size nkey="5" nuser_geom="1"/>
|
||||
<visual>
|
||||
<map fogend="5" fogstart="3"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture builtin="gradient" height="100" rgb1=".4 .5 .6" rgb2="0 0 0" type="skybox" width="100"/>
|
||||
<!-- <texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/>-->
|
||||
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
||||
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>
|
||||
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="60 60" texture="texplane"/>
|
||||
<material name="geom" texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<!-- light cutoff="100" diffuse="1 1 1" dir="-0 0 -1.3" directional="true" exponent="1" pos="0 0 1.3" specular=".1 .1 .1"/-->
|
||||
<geom condim="3" friction="1 .1 .1" material="MatPlane" name="floor" pos="0 0 0" rgba="0.8 0.9 0.8 1" size="20 20 0.125" type="plane"/>
|
||||
|
||||
</worldbody>
|
||||
<tendon>
|
||||
<fixed name="left_hipknee">
|
||||
<joint coef="-1" joint="left_hip_y"/>
|
||||
<joint coef="1" joint="left_knee"/>
|
||||
</fixed>
|
||||
<fixed name="right_hipknee">
|
||||
<joint coef="-1" joint="right_hip_y"/>
|
||||
<joint coef="1" joint="right_knee"/>
|
||||
</fixed>
|
||||
</tendon>
|
||||
<actuator><!-- this section is not supported, same constants in code -->
|
||||
<motor gear="100" joint="abdomen_y" name="abdomen_y"/>
|
||||
<motor gear="100" joint="abdomen_z" name="abdomen_z"/>
|
||||
<motor gear="100" joint="abdomen_x" name="abdomen_x"/>
|
||||
<motor gear="100" joint="right_hip_x" name="right_hip_x"/>
|
||||
<motor gear="100" joint="right_hip_z" name="right_hip_z"/>
|
||||
<motor gear="300" joint="right_hip_y" name="right_hip_y"/>
|
||||
<motor gear="200" joint="right_knee" name="right_knee"/>
|
||||
<motor gear="100" joint="left_hip_x" name="left_hip_x"/>
|
||||
<motor gear="100" joint="left_hip_z" name="left_hip_z"/>
|
||||
<motor gear="300" joint="left_hip_y" name="left_hip_y"/>
|
||||
<motor gear="200" joint="left_knee" name="left_knee"/>
|
||||
<motor gear="25" joint="right_shoulder1" name="right_shoulder1"/>
|
||||
<motor gear="25" joint="right_shoulder2" name="right_shoulder2"/>
|
||||
<motor gear="25" joint="right_elbow" name="right_elbow"/>
|
||||
<motor gear="25" joint="left_shoulder1" name="left_shoulder1"/>
|
||||
<motor gear="25" joint="left_shoulder2" name="left_shoulder2"/>
|
||||
<motor gear="25" joint="left_elbow" name="left_elbow"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,5 @@
|
||||
<mujoco model="ground_plane">
|
||||
<worldbody>
|
||||
<geom conaffinity="1" condim="3" name="floor" friction="0.8 0.1 0.1" pos="0 0 0" type="plane"/>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,88 @@
|
||||
<!-- Cheetah Model
|
||||
|
||||
The state space is populated with joints in the order that they are
|
||||
defined in this file. The actuators also operate on joints.
|
||||
|
||||
State-Space (name/joint/parameter):
|
||||
- rootx slider position (m)
|
||||
- rootz slider position (m)
|
||||
- rooty hinge angle (rad)
|
||||
- bthigh hinge angle (rad)
|
||||
- bshin hinge angle (rad)
|
||||
- bfoot hinge angle (rad)
|
||||
- fthigh hinge angle (rad)
|
||||
- fshin hinge angle (rad)
|
||||
- ffoot hinge angle (rad)
|
||||
- rootx slider velocity (m/s)
|
||||
- rootz slider velocity (m/s)
|
||||
- rooty hinge angular velocity (rad/s)
|
||||
- bthigh hinge angular velocity (rad/s)
|
||||
- bshin hinge angular velocity (rad/s)
|
||||
- bfoot hinge angular velocity (rad/s)
|
||||
- fthigh hinge angular velocity (rad/s)
|
||||
- fshin hinge angular velocity (rad/s)
|
||||
- ffoot hinge angular velocity (rad/s)
|
||||
|
||||
Actuators (name/actuator/parameter):
|
||||
- bthigh hinge torque (N m)
|
||||
- bshin hinge torque (N m)
|
||||
- bfoot hinge torque (N m)
|
||||
- fthigh hinge torque (N m)
|
||||
- fshin hinge torque (N m)
|
||||
- ffoot hinge torque (N m)
|
||||
|
||||
-->
|
||||
<mujoco model="cheetah">
|
||||
<compiler angle="radian" coordinate="local" inertiafromgeom="true" settotalmass="14"/>
|
||||
<default>
|
||||
<joint armature=".1" damping=".01" limited="true" solimplimit="0 .8 .03" solreflimit=".02 1" stiffness="8"/>
|
||||
<geom conaffinity="0" condim="3" contype="1" friction="0.8 .1 .1" rgba="0.8 0.6 .4 1" solimp="0.0 0.8 0.01" solref="0.02 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1 1"/>
|
||||
</default>
|
||||
<size nstack="300000" nuser_geom="1"/>
|
||||
<option gravity="0 0 -9.81" timestep="0.01"/>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 .7">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="false" name="ignorex" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 0 1" damping="0" limited="false" name="ignorez" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="false" name="ignorey" pos="0 0 0" stiffness="0" type="hinge"/>
|
||||
<geom fromto="-.5 0 0 .5 0 0" name="torso" size="0.046" type="capsule"/>
|
||||
<geom axisangle="0 1 0 .87" name="head" pos=".6 0 .1" size="0.046 .15" type="capsule"/>
|
||||
<!-- <site name='tip' pos='.15 0 .11'/>-->
|
||||
<body name="bthigh" pos="-.5 0 0">
|
||||
<joint axis="0 1 0" damping="6" name="bthigh" pos="0 0 0" range="-.52 1.05" stiffness="240" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -3.8" name="bthigh" pos=".1 0 -.13" size="0.046 .145" type="capsule"/>
|
||||
<body name="bshin" pos=".16 0 -.25">
|
||||
<joint axis="0 1 0" damping="4.5" name="bshin" pos="0 0 0" range="-.785 .785" stiffness="180" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -2.03" name="bshin" pos="-.14 0 -.07" rgba="0.9 0.6 0.6 1" size="0.046 .15" type="capsule"/>
|
||||
<body name="bfoot" pos="-.28 0 -.14">
|
||||
<joint axis="0 1 0" damping="3" name="bfoot" pos="0 0 0" range="-.4 .785" stiffness="120" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -.27" name="bfoot" pos=".03 0 -.097" rgba="0.9 0.6 0.6 1" size="0.046 .094" type="capsule"/>
|
||||
<inertial mass="10"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="fthigh" pos=".5 0 0">
|
||||
<joint axis="0 1 0" damping="4.5" name="fthigh" pos="0 0 0" range="-1.5 0.8" stiffness="180" type="hinge"/>
|
||||
<geom axisangle="0 1 0 .52" name="fthigh" pos="-.07 0 -.12" size="0.046 .133" type="capsule"/>
|
||||
<body name="fshin" pos="-.14 0 -.24">
|
||||
<joint axis="0 1 0" damping="3" name="fshin" pos="0 0 0" range="-1.2 1.1" stiffness="120" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -.6" name="fshin" pos=".065 0 -.09" rgba="0.9 0.6 0.6 1" size="0.046 .106" type="capsule"/>
|
||||
<body name="ffoot" pos=".13 0 -.18">
|
||||
<joint axis="0 1 0" damping="1.5" name="ffoot" pos="0 0 0" range="-3.1 -0.3" stiffness="60" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -.6" name="ffoot" pos=".045 0 -.07" rgba="0.9 0.6 0.6 1" size="0.046 .07" type="capsule"/>
|
||||
<inertial mass="10"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor gear="120" joint="bthigh" name="bthigh"/>
|
||||
<motor gear="90" joint="bshin" name="bshin"/>
|
||||
<motor gear="60" joint="bfoot" name="bfoot"/>
|
||||
<motor gear="120" joint="fthigh" name="fthigh"/>
|
||||
<motor gear="60" joint="fshin" name="fshin"/>
|
||||
<motor gear="30" joint="ffoot" name="ffoot"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
13
examples/pybullet/gym/pybullet_envs/data/mjcf/hello_mjcf.xml
Normal file
13
examples/pybullet/gym/pybullet_envs/data/mjcf/hello_mjcf.xml
Normal file
@@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom type="box" size=".1 .2 .3" rgba="0 .9 0 1"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
39
examples/pybullet/gym/pybullet_envs/data/mjcf/hopper.xml
Normal file
39
examples/pybullet/gym/pybullet_envs/data/mjcf/hopper.xml
Normal file
@@ -0,0 +1,39 @@
|
||||
<mujoco model="hopper">
|
||||
<compiler angle="degree" coordinate="global" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="1" contype="1" margin="0.001" friction="0.8 .1 .1" material="geom" rgba="0.8 0.6 .4 1" solimp=".8 .8 .01" solref=".02 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" timestep="0.002"/>
|
||||
<worldbody>
|
||||
<!-- CHANGE: body pos="" deleted for all bodies (you can also set pos="0 0 0", it works)
|
||||
Interpretation of body pos="" depends on coordinate="global" above.
|
||||
Bullet doesn't support global coordinates in bodies, little motivation to fix this, as long as it works without pos="" as well.
|
||||
After this change, Hopper still loads and works in MuJoCo simulator.
|
||||
-->
|
||||
<body name="torso">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="false" name="ignore1" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 0 1" damping="0" limited="false" name="ignore2" pos="0 0 0" ref="1.25" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="false" name="ignore3" pos="0 0 0" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0 0 1.45 0 0 1.05" name="torso_geom" size="0.05" type="capsule"/>
|
||||
<body name="thigh">
|
||||
<joint axis="0 -1 0" name="thigh_joint" pos="0 0 1.05" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 1.05 0 0 0.6" name="thigh_geom" size="0.05" type="capsule"/>
|
||||
<body name="leg">
|
||||
<joint axis="0 -1 0" name="leg_joint" pos="0 0 0.6" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 0.6 0 0 0.1" name="leg_geom" size="0.04" type="capsule"/>
|
||||
<body name="foot">
|
||||
<joint axis="0 -1 0" name="foot_joint" pos="0 0 0.1" range="-45 45" type="hinge"/>
|
||||
<geom fromto="-0.13 0 0.1 0.26 0 0.1" name="foot_geom" size="0.06" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="thigh_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="leg_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="foot_joint"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
130
examples/pybullet/gym/pybullet_envs/data/mjcf/humanoid.xml
Normal file
130
examples/pybullet/gym/pybullet_envs/data/mjcf/humanoid.xml
Normal file
@@ -0,0 +1,130 @@
|
||||
<mujoco model='humanoid'>
|
||||
<compiler inertiafromgeom='true' angle='degree'/>
|
||||
|
||||
<default>
|
||||
<joint limited='true' damping='1' armature='0' />
|
||||
<geom contype='1' conaffinity='1' condim='1' rgba='0.8 0.6 .4 1'
|
||||
margin="0.001" solref=".02 1" solimp=".8 .8 .01" material="geom"/>
|
||||
<motor ctrlrange='-.4 .4' ctrllimited='true'/>
|
||||
</default>
|
||||
|
||||
<option timestep='0.002' iterations="50" solver="PGS">
|
||||
<flag energy="enable"/>
|
||||
</option>
|
||||
|
||||
<visual>
|
||||
<map fogstart="3" fogend="5" force="0.1"/>
|
||||
<quality shadowsize="2048"/>
|
||||
</visual>
|
||||
|
||||
<asset>
|
||||
<texture type="skybox" builtin="gradient" width="100" height="100" rgb1=".4 .6 .8"
|
||||
rgb2="0 0 0"/>
|
||||
<texture name="texgeom" type="cube" builtin="flat" mark="cross" width="127" height="1278"
|
||||
rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" random="0.01"/>
|
||||
<texture name="texplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2"
|
||||
width="100" height="100"/>
|
||||
|
||||
<material name='MatPlane' reflectance='0.5' texture="texplane" texrepeat="1 1" texuniform="true"/>
|
||||
<material name='geom' texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<geom name='floor' pos='0 0 0' size='10 10 0.125' type='plane' material="MatPlane" condim='3'/>
|
||||
|
||||
<body name='torso' pos='0 0 1.4'>
|
||||
<light mode='trackcom' directional='false' diffuse='.8 .8 .8' specular='0.3 0.3 0.3' pos='0 0 4.0' dir='0 0 -1'/>
|
||||
|
||||
|
||||
<geom name='torso1' type='capsule' fromto='0 -.07 0 0 .07 0' size='0.07' />
|
||||
<geom name='head' type='sphere' pos='0 0 .19' size='.09'/>
|
||||
<geom name='uwaist' type='capsule' fromto='-.01 -.06 -.12 -.01 .06 -.12' size='0.06'/>
|
||||
<body name='lwaist' pos='-.01 0 -0.260' quat='1.000 0 -0.002 0' >
|
||||
<geom name='lwaist' type='capsule' fromto='0 -.06 0 0 .06 0' size='0.06' />
|
||||
<joint name='abdomen_z' type='hinge' pos='0 0 0.065' axis='0 0 1' range='-45 45' damping='5' stiffness='20' armature='0.02' />
|
||||
<joint name='abdomen_y' type='hinge' pos='0 0 0.065' axis='0 1 0' range='-75 30' damping='5' stiffness='10' armature='0.02' />
|
||||
<body name='pelvis' pos='0 0 -0.165' quat='1.000 0 -0.002 0' >
|
||||
<joint name='abdomen_x' type='hinge' pos='0 0 0.1' axis='1 0 0' range='-35 35' damping='5' stiffness='10' armature='0.02' />
|
||||
<geom name='butt' type='capsule' fromto='-.02 -.07 0 -.02 .07 0' size='0.09' />
|
||||
<body name='right_thigh' pos='0 -0.1 -0.04' >
|
||||
<joint name='right_hip_x' type='hinge' pos='0 0 0' axis='1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='right_hip_z' type='hinge' pos='0 0 0' axis='0 0 1' range='-60 35' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='right_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-110 20' damping='5' stiffness='20' armature='0.0080' />
|
||||
<geom name='right_thigh1' type='capsule' fromto='0 0 0 0 0.01 -.34' size='0.06' />
|
||||
<body name='right_shin' pos='0 0.01 -0.403' >
|
||||
<joint name='right_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' armature='0.0060' />
|
||||
<geom name='right_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' />
|
||||
<body name='right_foot' pos='0 0 -.39' >
|
||||
<joint name='right_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' />
|
||||
<joint name='right_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' />
|
||||
<geom name='right_foot_cap1' type='capsule' fromto='-.07 -0.02 0 0.14 -0.04 0' size='0.027' />
|
||||
<geom name='right_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 0.02 0' size='0.027' />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name='left_thigh' pos='0 0.1 -0.04' >
|
||||
<joint name='left_hip_x' type='hinge' pos='0 0 0' axis='-1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='left_hip_z' type='hinge' pos='0 0 0' axis='0 0 -1' range='-60 35' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='left_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-120 20' damping='5' stiffness='20' armature='0.01' />
|
||||
<geom name='left_thigh1' type='capsule' fromto='0 0 0 0 -0.01 -.34' size='0.06' />
|
||||
<body name='left_shin' pos='0 -0.01 -0.403' >
|
||||
<joint name='left_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' stiffness='1' armature='0.0060' />
|
||||
<geom name='left_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' />
|
||||
<body name='left_foot' pos='0 0 -.39' >
|
||||
<joint name='left_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' />
|
||||
<joint name='left_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' />
|
||||
<geom name='left_foot_cap1' type='capsule' fromto='-.07 0.02 0 0.14 0.04 0' size='0.027' />
|
||||
<geom name='left_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 -0.02 0' size='0.027' />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name='right_upper_arm' pos='0 -0.17 0.06' >
|
||||
<joint name='right_shoulder1' type='hinge' pos='0 0 0' axis='2 1 1' range='-85 60' stiffness='1' armature='0.0068' />
|
||||
<joint name='right_shoulder2' type='hinge' pos='0 0 0' axis='0 -1 1' range='-85 60' stiffness='1' armature='0.0051' />
|
||||
<geom name='right_uarm1' type='capsule' fromto='0 0 0 .16 -.16 -.16' size='0.04 0.16' />
|
||||
<body name='right_lower_arm' pos='.18 -.18 -.18' >
|
||||
<joint name='right_elbow' type='hinge' pos='0 0 0' axis='0 -1 1' range='-90 50' stiffness='0' armature='0.0028' />
|
||||
<geom name='right_larm' type='capsule' fromto='0.01 0.01 0.01 .17 .17 .17' size='0.031' />
|
||||
<geom name='right_hand' type='sphere' pos='.18 .18 .18' size='0.04'/>
|
||||
</body>
|
||||
</body>
|
||||
<body name='left_upper_arm' pos='0 0.17 0.06' >
|
||||
<joint name='left_shoulder1' type='hinge' pos='0 0 0' axis='2 -1 1' range='-60 85' stiffness='1' armature='0.0068' />
|
||||
<joint name='left_shoulder2' type='hinge' pos='0 0 0' axis='0 1 1' range='-60 85' stiffness='1' armature='0.0051' />
|
||||
<geom name='left_uarm1' type='capsule' fromto='0 0 0 .16 .16 -.16' size='0.04 0.16' />
|
||||
<body name='left_lower_arm' pos='.18 .18 -.18' >
|
||||
<joint name='left_elbow' type='hinge' pos='0 0 0' axis='0 -1 -1' range='-90 50' stiffness='0' armature='0.0028' />
|
||||
<geom name='left_larm' type='capsule' fromto='0.01 -0.01 0.01 .17 -.17 .17' size='0.031' />
|
||||
<geom name='left_hand' type='sphere' pos='.18 -.18 .18' size='0.04'/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor name='abdomen_y' gear='200' joint='abdomen_y' />
|
||||
<motor name='abdomen_z' gear='200' joint='abdomen_z' />
|
||||
<motor name='abdomen_x' gear='200' joint='abdomen_x' />
|
||||
<motor name='right_hip_x' gear='200' joint='right_hip_x' />
|
||||
<motor name='right_hip_z' gear='200' joint='right_hip_z' />
|
||||
<motor name='right_hip_y' gear='600' joint='right_hip_y' />
|
||||
<motor name='right_knee' gear='400' joint='right_knee' />
|
||||
<motor name='right_ankle_x' gear='100' joint='right_ankle_x' />
|
||||
<motor name='right_ankle_y' gear='100' joint='right_ankle_y' />
|
||||
<motor name='left_hip_x' gear='200' joint='left_hip_x' />
|
||||
<motor name='left_hip_z' gear='200' joint='left_hip_z' />
|
||||
<motor name='left_hip_y' gear='600' joint='left_hip_y' />
|
||||
<motor name='left_knee' gear='400' joint='left_knee' />
|
||||
<motor name='left_ankle_x' gear='100' joint='left_ankle_x' />
|
||||
<motor name='left_ankle_y' gear='100' joint='left_ankle_y' />
|
||||
<motor name='right_shoulder1' gear='100' joint='right_shoulder1' />
|
||||
<motor name='right_shoulder2' gear='100' joint='right_shoulder2' />
|
||||
<motor name='right_elbow' gear='200' joint='right_elbow' />
|
||||
<motor name='left_shoulder1' gear='100' joint='left_shoulder1' />
|
||||
<motor name='left_shoulder2' gear='100' joint='left_shoulder2' />
|
||||
<motor name='left_elbow' gear='200' joint='left_elbow' />
|
||||
</actuator>
|
||||
|
||||
</mujoco>
|
||||
115
examples/pybullet/gym/pybullet_envs/data/mjcf/humanoid_fixed.xml
Normal file
115
examples/pybullet/gym/pybullet_envs/data/mjcf/humanoid_fixed.xml
Normal file
@@ -0,0 +1,115 @@
|
||||
<mujoco model="humanoid">
|
||||
<compiler angle="degree" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" iterations="50" solver="PGS" timestep="0.003">
|
||||
<!-- <flags solverstat="enable" energy="enable"/>-->
|
||||
</option>
|
||||
<size nkey="5" nuser_geom="1"/>
|
||||
<visual>
|
||||
<map fogend="5" fogstart="3"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture builtin="gradient" height="100" rgb1=".4 .5 .6" rgb2="0 0 0" type="skybox" width="100"/>
|
||||
<!-- <texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/>-->
|
||||
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
||||
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>
|
||||
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="60 60" texture="texplane"/>
|
||||
<material name="geom" texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 1.4">
|
||||
<joint armature="0" damping="0" limited="false" name="root" pos="0 0 0" stiffness="0" type="fixed"/>
|
||||
<geom fromto="0 -.07 0 0 .07 0" name="torso1" size="0.07" type="capsule"/>
|
||||
<geom name="head" pos="0 0 .19" size=".09" type="sphere" user="258"/>
|
||||
<geom fromto="-.01 -.06 -.12 -.01 .06 -.12" name="uwaist" size="0.06" type="capsule"/>
|
||||
<body name="lwaist" pos="-.01 0 -0.260" quat="1.000 0 -0.002 0">
|
||||
<geom fromto="0 -.06 0 0 .06 0" name="lwaist" size="0.06" type="capsule"/>
|
||||
<joint armature="0.02" axis="0 0 1" damping="5" name="abdomen_z" pos="0 0 0.065" range="-45 45" stiffness="20" type="hinge"/>
|
||||
<joint armature="0.02" axis="0 1 0" damping="5" name="abdomen_y" pos="0 0 0.065" range="-75 30" stiffness="10" type="hinge"/>
|
||||
<body name="pelvis" pos="0 0 -0.165" quat="1.000 0 -0.002 0">
|
||||
<joint armature="0.02" axis="1 0 0" damping="5" name="abdomen_x" pos="0 0 0.1" range="-35 35" stiffness="10" type="hinge"/>
|
||||
<geom fromto="-.02 -.07 0 -.02 .07 0" name="butt" size="0.09" type="capsule"/>
|
||||
<body name="right_thigh" pos="0 -0.1 -0.04">
|
||||
<joint armature="0.01" axis="1 0 0" damping="5" name="right_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 1" damping="5" name="right_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="right_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0.01 -.34" name="right_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="right_shin" pos="0 0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="right_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="right_shin1" size="0.049" type="capsule"/>
|
||||
<body name="right_foot" pos="0 0 -0.45">
|
||||
<geom name="right_foot" pos="0 0 0.1" size="0.075" type="sphere" user="0"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_thigh" pos="0 0.1 -0.04">
|
||||
<joint armature="0.01" axis="-1 0 0" damping="5" name="left_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 -1" damping="5" name="left_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="left_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 -0.01 -.34" name="left_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="left_shin" pos="0 -0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="left_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="left_shin1" size="0.049" type="capsule"/>
|
||||
<body name="left_foot" pos="0 0 -0.45">
|
||||
<geom name="left_foot" type="sphere" size="0.075" pos="0 0 0.1" user="0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_upper_arm" pos="0 -0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 1 1" name="right_shoulder1" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 -1 1" name="right_shoulder2" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 -.16 -.16" name="right_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="right_lower_arm" pos=".18 -.18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 1" name="right_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 0.01 0.01 .17 .17 .17" name="right_larm" size="0.031" type="capsule"/>
|
||||
<geom name="right_hand" pos=".18 .18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_upper_arm" pos="0 0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 -1 1" name="left_shoulder1" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 1 1" name="left_shoulder2" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 .16 -.16" name="left_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="left_lower_arm" pos=".18 .18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 -1" name="left_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 -0.01 0.01 .17 -.17 .17" name="left_larm" size="0.031" type="capsule"/>
|
||||
<geom name="left_hand" pos=".18 -.18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<tendon>
|
||||
<fixed name="left_hipknee">
|
||||
<joint coef="-1" joint="left_hip_y"/>
|
||||
<joint coef="1" joint="left_knee"/>
|
||||
</fixed>
|
||||
<fixed name="right_hipknee">
|
||||
<joint coef="-1" joint="right_hip_y"/>
|
||||
<joint coef="1" joint="right_knee"/>
|
||||
</fixed>
|
||||
</tendon>
|
||||
<actuator><!-- this section is not supported, same constants in code -->
|
||||
<motor gear="100" joint="abdomen_y" name="abdomen_y"/>
|
||||
<motor gear="100" joint="abdomen_z" name="abdomen_z"/>
|
||||
<motor gear="100" joint="abdomen_x" name="abdomen_x"/>
|
||||
<motor gear="100" joint="right_hip_x" name="right_hip_x"/>
|
||||
<motor gear="100" joint="right_hip_z" name="right_hip_z"/>
|
||||
<motor gear="300" joint="right_hip_y" name="right_hip_y"/>
|
||||
<motor gear="200" joint="right_knee" name="right_knee"/>
|
||||
<motor gear="100" joint="left_hip_x" name="left_hip_x"/>
|
||||
<motor gear="100" joint="left_hip_z" name="left_hip_z"/>
|
||||
<motor gear="300" joint="left_hip_y" name="left_hip_y"/>
|
||||
<motor gear="200" joint="left_knee" name="left_knee"/>
|
||||
<motor gear="25" joint="right_shoulder1" name="right_shoulder1"/>
|
||||
<motor gear="25" joint="right_shoulder2" name="right_shoulder2"/>
|
||||
<motor gear="25" joint="right_elbow" name="right_elbow"/>
|
||||
<motor gear="25" joint="left_shoulder1" name="left_shoulder1"/>
|
||||
<motor gear="25" joint="left_shoulder2" name="left_shoulder2"/>
|
||||
<motor gear="25" joint="left_elbow" name="left_elbow"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,107 @@
|
||||
<mujoco model="humanoid">
|
||||
<compiler angle="degree" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="3" friction="0.8 0.1 0.1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" iterations="50" solver="PGS" timestep="0.003">
|
||||
<!-- <flags solverstat="enable" energy="enable"/>-->
|
||||
</option>
|
||||
<size nkey="5" nuser_geom="1"/>
|
||||
<visual>
|
||||
<map fogend="5" fogstart="3"/>
|
||||
</visual>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 1.4">
|
||||
<!--joint armature="0" damping="0" limited="false" name="root" pos="0 0 0" stiffness="0" type="free"/-->
|
||||
<geom fromto="0 -.07 0 0 .07 0" name="torso1" size="0.07" type="capsule"/>
|
||||
<geom name="head" pos="0 0 .19" size=".09" type="sphere" user="258"/>
|
||||
<geom fromto="-.01 -.06 -.12 -.01 .06 -.12" name="uwaist" size="0.06" type="capsule"/>
|
||||
<body name="lwaist" pos="-.01 0 -0.260" quat="1.000 0 -0.002 0">
|
||||
<geom fromto="0 -.06 0 0 .06 0" name="lwaist" size="0.06" type="capsule"/>
|
||||
<joint armature="0.02" axis="0 0 1" damping="5" name="abdomen_z" pos="0 0 0.065" range="-45 45" stiffness="20" type="hinge"/>
|
||||
<joint armature="0.02" axis="0 1 0" damping="5" name="abdomen_y" pos="0 0 0.065" range="-75 30" stiffness="10" type="hinge"/>
|
||||
<body name="pelvis" pos="0 0 -0.165" quat="1.000 0 -0.002 0">
|
||||
<joint armature="0.02" axis="1 0 0" damping="5" name="abdomen_x" pos="0 0 0.1" range="-35 35" stiffness="10" type="hinge"/>
|
||||
<geom fromto="-.02 -.07 0 -.02 .07 0" name="butt" size="0.09" type="capsule"/>
|
||||
<body name="right_thigh" pos="0 -0.1 -0.04">
|
||||
<joint armature="0.01" axis="1 0 0" damping="5" name="right_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 1" damping="5" name="right_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="right_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0.01 -.34" name="right_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="right_shin" pos="0 0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="right_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="right_shin1" size="0.049" type="capsule"/>
|
||||
<body name="right_foot" pos="0 0 -0.45">
|
||||
<geom name="right_foot" pos="0 0 0.1" size="0.075" type="sphere" user="0"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_thigh" pos="0 0.1 -0.04">
|
||||
<joint armature="0.01" axis="-1 0 0" damping="5" name="left_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 -1" damping="5" name="left_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="left_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 -0.01 -.34" name="left_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="left_shin" pos="0 -0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="left_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="left_shin1" size="0.049" type="capsule"/>
|
||||
<body name="left_foot" pos="0 0 -0.45">
|
||||
<geom name="left_foot" type="sphere" size="0.075" pos="0 0 0.1" user="0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_upper_arm" pos="0 -0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 1 1" name="right_shoulder1" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 -1 1" name="right_shoulder2" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 -.16 -.16" name="right_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="right_lower_arm" pos=".18 -.18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 1" name="right_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 0.01 0.01 .17 .17 .17" name="right_larm" size="0.031" type="capsule"/>
|
||||
<geom name="right_hand" pos=".18 .18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_upper_arm" pos="0 0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 -1 1" name="left_shoulder1" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 1 1" name="left_shoulder2" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 .16 -.16" name="left_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="left_lower_arm" pos=".18 .18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 -1" name="left_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 -0.01 0.01 .17 -.17 .17" name="left_larm" size="0.031" type="capsule"/>
|
||||
<geom name="left_hand" pos=".18 -.18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<tendon>
|
||||
<fixed name="left_hipknee">
|
||||
<joint coef="-1" joint="left_hip_y"/>
|
||||
<joint coef="1" joint="left_knee"/>
|
||||
</fixed>
|
||||
<fixed name="right_hipknee">
|
||||
<joint coef="-1" joint="right_hip_y"/>
|
||||
<joint coef="1" joint="right_knee"/>
|
||||
</fixed>
|
||||
</tendon>
|
||||
<actuator><!-- this section is not supported, same constants in code -->
|
||||
<motor gear="100" joint="abdomen_y" name="abdomen_y"/>
|
||||
<motor gear="100" joint="abdomen_z" name="abdomen_z"/>
|
||||
<motor gear="100" joint="abdomen_x" name="abdomen_x"/>
|
||||
<motor gear="100" joint="right_hip_x" name="right_hip_x"/>
|
||||
<motor gear="100" joint="right_hip_z" name="right_hip_z"/>
|
||||
<motor gear="300" joint="right_hip_y" name="right_hip_y"/>
|
||||
<motor gear="200" joint="right_knee" name="right_knee"/>
|
||||
<motor gear="100" joint="left_hip_x" name="left_hip_x"/>
|
||||
<motor gear="100" joint="left_hip_z" name="left_hip_z"/>
|
||||
<motor gear="300" joint="left_hip_y" name="left_hip_y"/>
|
||||
<motor gear="200" joint="left_knee" name="left_knee"/>
|
||||
<motor gear="25" joint="right_shoulder1" name="right_shoulder1"/>
|
||||
<motor gear="25" joint="right_shoulder2" name="right_shoulder2"/>
|
||||
<motor gear="25" joint="right_elbow" name="right_elbow"/>
|
||||
<motor gear="25" joint="left_shoulder1" name="left_shoulder1"/>
|
||||
<motor gear="25" joint="left_shoulder2" name="left_shoulder2"/>
|
||||
<motor gear="25" joint="left_elbow" name="left_elbow"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,115 @@
|
||||
<mujoco model="humanoid">
|
||||
<compiler angle="degree" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" iterations="50" solver="PGS" timestep="0.003">
|
||||
<!-- <flags solverstat="enable" energy="enable"/>-->
|
||||
</option>
|
||||
<size nkey="5" nuser_geom="1"/>
|
||||
<visual>
|
||||
<map fogend="5" fogstart="3"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture builtin="gradient" height="100" rgb1=".4 .5 .6" rgb2="0 0 0" type="skybox" width="100"/>
|
||||
<!-- <texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/>-->
|
||||
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
||||
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>
|
||||
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="60 60" texture="texplane"/>
|
||||
<material name="geom" texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 1.4">
|
||||
<!--joint armature="0" damping="0" limited="false" name="root" pos="0 0 0" stiffness="0" type="free"/-->
|
||||
<geom fromto="0 -.07 0 0 .07 0" name="torso1" size="0.07" type="capsule"/>
|
||||
<geom name="head" pos="0 0 .19" size=".09" type="sphere" user="258"/>
|
||||
<geom fromto="-.01 -.06 -.12 -.01 .06 -.12" name="uwaist" size="0.06" type="capsule"/>
|
||||
<body name="lwaist" pos="-.01 0 -0.260" quat="1.000 0 -0.002 0">
|
||||
<geom fromto="0 -.06 0 0 .06 0" name="lwaist" size="0.06" type="capsule"/>
|
||||
<joint armature="0.02" axis="0 0 1" damping="5" name="abdomen_z" pos="0 0 0.065" range="-45 45" stiffness="20" type="hinge"/>
|
||||
<joint armature="0.02" axis="0 1 0" damping="5" name="abdomen_y" pos="0 0 0.065" range="-75 30" stiffness="10" type="hinge"/>
|
||||
<body name="pelvis" pos="0 0 -0.165" quat="1.000 0 -0.002 0">
|
||||
<joint armature="0.02" axis="1 0 0" damping="5" name="abdomen_x" pos="0 0 0.1" range="-35 35" stiffness="10" type="hinge"/>
|
||||
<geom fromto="-.02 -.07 0 -.02 .07 0" name="butt" size="0.09" type="capsule"/>
|
||||
<body name="right_thigh" pos="0 -0.1 -0.04">
|
||||
<joint armature="0.01" axis="1 0 0" damping="5" name="right_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 1" damping="5" name="right_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="right_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0.01 -.34" name="right_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="right_shin" pos="0 0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="right_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="right_shin1" size="0.049" type="capsule"/>
|
||||
<body name="right_foot" pos="0 0 -0.45">
|
||||
<geom name="right_foot" pos="0 0 0.1" size="0.075" type="sphere" user="0"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_thigh" pos="0 0.1 -0.04">
|
||||
<joint armature="0.01" axis="-1 0 0" damping="5" name="left_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 -1" damping="5" name="left_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="left_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 -0.01 -.34" name="left_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="left_shin" pos="0 -0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="left_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="left_shin1" size="0.049" type="capsule"/>
|
||||
<body name="left_foot" pos="0 0 -0.45">
|
||||
<geom name="left_foot" type="sphere" size="0.075" pos="0 0 0.1" user="0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_upper_arm" pos="0 -0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 1 1" name="right_shoulder1" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 -1 1" name="right_shoulder2" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 -.16 -.16" name="right_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="right_lower_arm" pos=".18 -.18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 1" name="right_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 0.01 0.01 .17 .17 .17" name="right_larm" size="0.031" type="capsule"/>
|
||||
<geom name="right_hand" pos=".18 .18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_upper_arm" pos="0 0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 -1 1" name="left_shoulder1" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 1 1" name="left_shoulder2" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 .16 -.16" name="left_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="left_lower_arm" pos=".18 .18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 -1" name="left_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 -0.01 0.01 .17 -.17 .17" name="left_larm" size="0.031" type="capsule"/>
|
||||
<geom name="left_hand" pos=".18 -.18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<tendon>
|
||||
<fixed name="left_hipknee">
|
||||
<joint coef="-1" joint="left_hip_y"/>
|
||||
<joint coef="1" joint="left_knee"/>
|
||||
</fixed>
|
||||
<fixed name="right_hipknee">
|
||||
<joint coef="-1" joint="right_hip_y"/>
|
||||
<joint coef="1" joint="right_knee"/>
|
||||
</fixed>
|
||||
</tendon>
|
||||
<actuator><!-- this section is not supported, same constants in code -->
|
||||
<motor gear="100" joint="abdomen_y" name="abdomen_y"/>
|
||||
<motor gear="100" joint="abdomen_z" name="abdomen_z"/>
|
||||
<motor gear="100" joint="abdomen_x" name="abdomen_x"/>
|
||||
<motor gear="100" joint="right_hip_x" name="right_hip_x"/>
|
||||
<motor gear="100" joint="right_hip_z" name="right_hip_z"/>
|
||||
<motor gear="300" joint="right_hip_y" name="right_hip_y"/>
|
||||
<motor gear="200" joint="right_knee" name="right_knee"/>
|
||||
<motor gear="100" joint="left_hip_x" name="left_hip_x"/>
|
||||
<motor gear="100" joint="left_hip_z" name="left_hip_z"/>
|
||||
<motor gear="300" joint="left_hip_y" name="left_hip_y"/>
|
||||
<motor gear="200" joint="left_knee" name="left_knee"/>
|
||||
<motor gear="25" joint="right_shoulder1" name="right_shoulder1"/>
|
||||
<motor gear="25" joint="right_shoulder2" name="right_shoulder2"/>
|
||||
<motor gear="25" joint="right_elbow" name="right_elbow"/>
|
||||
<motor gear="25" joint="left_shoulder1" name="left_shoulder1"/>
|
||||
<motor gear="25" joint="left_shoulder2" name="left_shoulder2"/>
|
||||
<motor gear="25" joint="left_elbow" name="left_elbow"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,47 @@
|
||||
<!-- Cartpole Model
|
||||
|
||||
The state space is populated with joints in the order that they are
|
||||
defined in this file. The actuators also operate on joints.
|
||||
|
||||
State-Space (name/joint/parameter):
|
||||
- cart slider position (m)
|
||||
- pole hinge angle (rad)
|
||||
- cart slider velocity (m/s)
|
||||
- pole hinge angular velocity (rad/s)
|
||||
|
||||
Actuators (name/actuator/parameter):
|
||||
- cart motor force x (N)
|
||||
|
||||
-->
|
||||
<mujoco model="cartpole">
|
||||
<compiler coordinate="local" inertiafromgeom="true"/>
|
||||
<custom>
|
||||
<numeric data="2" name="frame_skip"/>
|
||||
</custom>
|
||||
<default>
|
||||
<joint damping="0.05"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
</default>
|
||||
<option gravity="1e-5 0 -9.81" integrator="RK4" timestep="0.01"/>
|
||||
<size nstack="3000"/>
|
||||
<worldbody>
|
||||
<geom name="floor" pos="0 0 -3.0" rgba="0.8 0.9 0.8 1" size="40 40 40" type="plane"/>
|
||||
<geom name="rail" pos="0 0 0" quat="0.707 0 0.707 0" rgba="0.3 0.3 0.7 1" size="0.02 1" type="capsule"/>
|
||||
<body name="cart" pos="0 0 0">
|
||||
<joint axis="1 0 0" limited="true" margin="0.01" name="slider" pos="0 0 0" range="-1 1" type="slide"/>
|
||||
<geom name="cart" pos="0 0 0" quat="0.707 0 0.707 0" size="0.1 0.1" type="capsule"/>
|
||||
<body name="pole" pos="0 0 0">
|
||||
<joint axis="0 1 0" name="hinge" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 0.6" name="cpole" rgba="0 0.7 0.7 1" size="0.045 0.3" type="capsule"/>
|
||||
<body name="pole2" pos="0 0 0.6">
|
||||
<joint axis="0 1 0" name="hinge2" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 0.6" name="cpole2" rgba="0 0.7 0.7 1" size="0.045 0.3" type="capsule"/>
|
||||
<!--site name="tip" pos="0 0 .6" size="0.01 0.01"/-->
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1 1" gear="500" joint="slider" name="slide"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,27 @@
|
||||
<mujoco model="inverted pendulum">
|
||||
<compiler inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="0" damping="1" limited="true"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
<tendon/>
|
||||
<motor ctrlrange="-3 3"/>
|
||||
</default>
|
||||
<option gravity="0 0 -9.81" integrator="RK4" timestep="0.02"/>
|
||||
<size nstack="3000"/>
|
||||
<worldbody>
|
||||
<!--geom name="ground" type="plane" pos="0 0 0" /-->
|
||||
<geom name="rail" pos="0 0 0" quat="0.707 0 0.707 0" rgba="0.3 0.3 0.7 1" size="0.02 1" type="capsule"/>
|
||||
<body name="cart" pos="0 0 0">
|
||||
<joint axis="1 0 0" limited="true" name="slider" pos="0 0 0" range="-1 1" type="slide"/>
|
||||
<geom name="cart" pos="0 0 0" quat="0.707 0 0.707 0" size="0.1 0.1" type="capsule"/>
|
||||
<body name="pole" pos="0 0 0">
|
||||
<joint axis="0 1 0" name="hinge" pos="0 0 0" limited="false" range="-90 90" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.001 0 0.6" name="cpole" rgba="0 0.7 0.7 1" size="0.049 0.3" type="capsule"/>
|
||||
<!-- <body name="pole2" pos="0.001 0 0.6"><joint name="hinge2" type="hinge" pos="0 0 0" axis="0 1 0"/><geom name="cpole2" type="capsule" fromto="0 0 0 0 0 0.6" size="0.05 0.3" rgba="0.7 0 0.7 1"/><site name="tip2" pos="0 0 .6"/></body>-->
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor gear="100" joint="slider" name="slide"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
90
examples/pybullet/gym/pybullet_envs/data/mjcf/pusher.xml
Normal file
90
examples/pybullet/gym/pybullet_envs/data/mjcf/pusher.xml
Normal file
@@ -0,0 +1,90 @@
|
||||
<mujoco model="pusher">
|
||||
<compiler inertiafromgeom="true" angle="radian" coordinate="local"/>
|
||||
<default>
|
||||
<joint armature='0.04' damping="0" limited="true"/>
|
||||
<geom friction=".8 .1 .1" density="300" margin="0.002" condim="1" contype="0" conaffinity="0"/>
|
||||
</default>
|
||||
<option timestep="0.01" gravity="0 0 0" integrator="RK4" />
|
||||
<worldbody>
|
||||
<!--Arena-->
|
||||
<geom name="table" type="plane" pos="0 0.5 -0.325" size="1 1 0.1" contype="1" conaffinity="1"/>
|
||||
<!--Arm-->
|
||||
<body name="shoulder_pan_link" pos="0 -0.6 0">
|
||||
<geom name="e1" type="sphere" rgba="0.6 0.6 0.6 1" pos="-0.06 0.05 0.2" size="0.05" />
|
||||
<geom name="e2" type="sphere" rgba="0.6 0.6 0.6 1" pos=" 0.06 0.05 0.2" size="0.05" />
|
||||
<geom name="e1p" type="sphere" rgba="0.1 0.1 0.1 1" pos="-0.06 0.09 0.2" size="0.03" />
|
||||
<geom name="e2p" type="sphere" rgba="0.1 0.1 0.1 1" pos=" 0.06 0.09 0.2" size="0.03" />
|
||||
<geom name="sp" type="capsule" fromto="0 0 -0.4 0 0 0.2" size="0.1" />
|
||||
<joint name="shoulder_pan_joint" type="hinge" pos="0 0 0" axis="0 0 1" range="-2.2854 1.714602" damping="0" />
|
||||
|
||||
<body name="shoulder_lift_link" pos="0.1 0 0">
|
||||
<geom name="sl" type="capsule" fromto="0 -0.1 0 0 0.1 0" size="0.1" />
|
||||
<joint name="shoulder_lift_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.5236 1.3963" damping="0" />
|
||||
|
||||
<body name="upper_arm_roll_link" pos="0 0 0">
|
||||
<geom name="uar" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
|
||||
<joint name="upper_arm_roll_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.5 1.7" damping="0" />
|
||||
|
||||
<body name="upper_arm_link" pos="0 0 0">
|
||||
<geom name="ua" type="capsule" fromto="0 0 0 0.4 0 0" size="0.06" />
|
||||
|
||||
<body name="elbow_flex_link" pos="0.4 0 0">
|
||||
<geom name="ef" type="capsule" fromto="0 -0.02 0 0.0 0.02 0" size="0.06" />
|
||||
<joint name="elbow_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.3213 0" damping="0" />
|
||||
|
||||
<body name="forearm_roll_link" pos="0 0 0">
|
||||
<geom name="fr" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
|
||||
<joint name="forearm_roll_joint" type="hinge" limited="true" pos="0 0 0" axis="1 0 0" damping="0" range="-1.5 1.5"/>
|
||||
|
||||
<body name="forearm_link" pos="0 0 0">
|
||||
<geom name="fa" type="capsule" fromto="0 0 0 0.291 0 0" size="0.05" />
|
||||
|
||||
<body name="wrist_flex_link" pos="0.321 0 0">
|
||||
<geom name="wf" type="capsule" fromto="0 -0.02 0 0 0.02 0" size="0.01" />
|
||||
<joint name="wrist_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-1.094 0" damping="0" />
|
||||
|
||||
<body name="wrist_roll_link" pos="0 0 0">
|
||||
<joint name="wrist_roll_joint" type="hinge" pos="0 0 0" limited="true" axis="1 0 0" damping="0" range="-1.5 1.5"/>
|
||||
<body name="fingertip" pos="0 0 0">
|
||||
<geom name="tip_arml" type="sphere" pos="0.1 -0.1 0." size="0.01" />
|
||||
<geom name="tip_armr" type="sphere" pos="0.1 0.1 0." size="0.01" />
|
||||
</body>
|
||||
<geom type="capsule" fromto="0 -0.1 0. 0.0 +0.1 0" size="0.02" contype="1" conaffinity="1" />
|
||||
<geom type="capsule" fromto="0 -0.1 0. 0.1 -0.1 0" size="0.02" contype="1" conaffinity="1" />
|
||||
<geom type="capsule" fromto="0 +0.1 0. 0.1 +0.1 0." size="0.02" contype="1" conaffinity="1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
||||
<!--Object-->
|
||||
<body name="object" pos="0.45 -0.05 -0.275" >
|
||||
<geom rgba="1 1 1 0" type="sphere" size="0.05 0.05 0.05" density="0.00001" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="cylinder" size="0.05 0.05 0.05" density="0.00001" contype="1" conaffinity="0"/>
|
||||
<joint name="object_x" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="0"/>
|
||||
<joint name="object_y" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="0"/>
|
||||
</body>
|
||||
|
||||
<!--Target-->
|
||||
<body name="target" pos="0.45 -0.05 -0.3230">
|
||||
<geom rgba="1 0 0 1" type="cylinder" size="0.08 0.001 0.1" density='0.00001' contype="0" conaffinity="0"/>
|
||||
<joint name="target_x" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="0"/>
|
||||
<joint name="target_y" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="0"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor joint="shoulder_pan_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="shoulder_lift_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="upper_arm_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="elbow_flex_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="forearm_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="wrist_flex_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="wrist_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
39
examples/pybullet/gym/pybullet_envs/data/mjcf/reacher.xml
Normal file
39
examples/pybullet/gym/pybullet_envs/data/mjcf/reacher.xml
Normal file
@@ -0,0 +1,39 @@
|
||||
<mujoco model="reacher">
|
||||
<compiler angle="radian" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
</default>
|
||||
<option gravity="0 0 -9.81" integrator="RK4" timestep="0.01"/>
|
||||
<worldbody>
|
||||
<!-- Arena -->
|
||||
<geom conaffinity="0" contype="0" name="ground" pos="0 0 0" rgba="0.9 0.9 0.9 1" size="1 1 10" type="plane"/>
|
||||
<geom conaffinity="0" fromto="-.3 -.3 .01 .3 -.3 .01" name="sideS" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto=" .3 -.3 .01 .3 .3 .01" name="sideE" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.3 .3 .01 .3 .3 .01" name="sideN" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.3 -.3 .01 -.3 .3 .01" name="sideW" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<!-- Arm -->
|
||||
<geom conaffinity="0" contype="0" fromto="0 0 0 0 0 0.02" name="root" rgba="0.9 0.4 0.6 1" size=".011" type="cylinder"/>
|
||||
<body name="body0" pos="0 0 .01">
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link0" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<joint axis="0 0 1" limited="false" name="joint0" pos="0 0 0" type="hinge"/>
|
||||
<body name="body1" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="true" name="joint1" pos="0 0 0" range="-3.0 3.0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link1" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<body name="fingertip" pos="0.11 0 0">
|
||||
<geom contype="0" name="fingertip" pos="0 0 0" rgba="0.0 0.8 0.6 1" size=".01" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<!-- Target -->
|
||||
<body name="target" pos="0 0 .01">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="true" name="target_x" pos="0 0 0" range="-.27 .27" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="true" name="target_y" pos="0 0 0" range="-.27 .27" stiffness="0" type="slide"/>
|
||||
<geom conaffinity="0" contype="0" name="target" pos="0 0 0" rgba="0.9 0.2 0.2 1" size=".009" type="sphere"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint0"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint1"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user