Architecture¶
Software architecture of simtrans is shown below. Reader and writer for each formats will read and write the common data structure.
Common data structure¶
simtrans.model¶
Common data structure for model converter
-
class
simtrans.model.AxisData[ソース]¶ ベースクラス:
objectJoint axis data
-
axis= None¶ Joint axis (relative to parent link)
-
damping= None¶ Damping factor
-
friction= None¶ Friction factor
-
limit= [inf, -inf]¶
-
velocitylimit= [inf, -inf]¶ Joint limits (upper and lower limits in 2-dim array)
-
-
class
simtrans.model.BodyModel[ソース]¶ ベースクラス:
simtrans.model.TransformationModelBody model
-
joints= []¶ List of joints
-
links= []¶ List of links
-
materials= []¶ List of materials
-
name= None¶ Name of the body
-
sensors= []¶ List of sensors
-
-
class
simtrans.model.BoxData[ソース]¶ ベースクラス:
objectBox shape data
-
material= None¶ Name of material
-
x= None¶ Width
-
y= None¶ Height
-
z= None¶ Depth
-
-
class
simtrans.model.CameraData[ソース]¶ ベースクラス:
objectCamera sensor data
-
CS_COLOR= 'color'¶
-
CS_DEPTH= 'depth'¶
-
CS_MONO= 'mono'¶
-
CS_RGBD= 'rgbd'¶
-
cameraType= None¶ Camera type
-
far= 50.0¶ Far clip distance
-
fov= 1.5708¶ Field of view (horizontal)
-
height= 480¶ Height
-
near= 0.01¶ Near clip distance
-
width= 640¶ Width
-
-
class
simtrans.model.CylinderData[ソース]¶ ベースクラス:
objectCylinder shape data
-
height= None¶ Height
-
material= None¶ Name of material
-
radius= None¶ Radius
-
-
class
simtrans.model.JointModel[ソース]¶ ベースクラス:
simtrans.model.TransformationModelJoint model
-
J_CONTINUOUS= 'continuous'¶ Continuous type
-
J_CRAWLER= 'crawler'¶ Crawler type
-
J_FIXED= 'fixed'¶ Fixed type
-
J_PRISMATIC= 'prismatic'¶ Prismatic type
-
J_REVOLUTE= 'revolute'¶ Revolute type
-
J_REVOLUTE2= 'revolute2'¶ Revolute (2-axis) type
-
J_SCREW= 'screw'¶ Screw type
-
axis= None¶ Joint axis (relative to parent link)
-
axis2= None¶ Joint axis (used the joint type is revolute2)
-
child= None¶ Name of child link
-
jointId= -1¶ Numeric ID of the joint (used in VRML model)
-
jointType= None¶ Joint type
-
name= None¶ Joint name
-
offsetPosition= False¶ Whether offset joint position or not
-
parent= None¶ Name of parent link
-
-
class
simtrans.model.LinkModel[ソース]¶ ベースクラス:
simtrans.model.TransformationModelLink model
-
centerofmass= None¶ Center of mass (3-dim array)
-
collisions= []¶ List of shape information used for collision detection
-
inertia= None¶ Inertia (3x3 numpy matrix)
-
mass= 0¶ Mass of the link
-
name= None¶ Name of the link
-
visuals= []¶ List of shape information used for rendering
-
-
class
simtrans.model.MaterialModel[ソース]¶ ベースクラス:
objectMaterial model
-
ambient= None¶ [r,g,b,a] array
-
diffuse= None¶ [r,g,b,a] array
-
emission= None¶ [r,g,b,a] array
-
name= None¶ Name of the material
-
shininess= None¶ float value or path string of texture image
-
specular= None¶ [r,g,b,a] array
-
texture= None¶ path string of texture image
-
transparency= None¶ float value or path string of texture image
-
-
class
simtrans.model.MeshData[ソース]¶ ベースクラス:
objectMesh data
-
color= None¶ Color ([R,G,B,A] * N numpy matrix)
-
color_index= None¶ Color index ([p1,p2,p3] * N numpy matrix)
-
material= None¶ Name of material
-
normal= None¶ Normal direction ([x,y,z] * N numpy matrix)
-
normal_index= None¶ Normal index ([p1,p2,p3] * N numpy matrix)
-
uvmap= None¶ UV mapping ([u,v] * N numpy matrix)
-
uvmap_index= None¶ Vertex index ([p1,p2,p3] * N numpy matrix)
-
vertex= []¶ Vertex position ([x,y,z] * N numpy matrix)
-
vertex_index= []¶ Vertex index ([p1,p2,p3] * N numpy matrix)
-
-
class
simtrans.model.MeshTransformData[ソース]¶ ベースクラス:
simtrans.model.TransformationModelMesh transform data
Intended to store scenegraph structure inside collada or vrml
-
children= []¶ Children (store MeshData or MeshTransformData)
-
-
class
simtrans.model.ProjectModel[ソース]¶ ベースクラス:
objectProject model
-
bodies= []¶ List of body models
-
name= None¶ Name of the simulation
-
-
class
simtrans.model.RayData[ソース]¶ ベースクラス:
objectRay sensor data
-
max_angle= 0¶
-
max_range= 0¶
-
min_angle= 0¶
-
min_range= 0¶
-
-
class
simtrans.model.SensorModel[ソース]¶ ベースクラス:
simtrans.model.TransformationModelSensor model
-
SS_CAMERA= 'camera'¶ Camera (color, mono, depth)
-
SS_IMU= 'imu'¶ IMU sensor
-
SS_RAY= 'ray'¶ Laser range finder
-
data= None¶
-
name= None¶ Name
-
parent= None¶ Name of parent link
-
rate= 20¶ Update rate of sensor
-
sensorType= None¶ Type of sensor
-
-
class
simtrans.model.ShapeModel[ソース]¶ ベースクラス:
simtrans.model.TransformationModelShape model
-
SP_BOX= 'box'¶ Box shape
-
SP_CYLINDER= 'cylinder'¶ Cylinder shape
-
SP_MESH= 'mesh'¶ Mesh shape
-
SP_SPHERE= 'sphere'¶ Sphere shape
-
data= None¶ Store properties for each specific type of shape
-
name= None¶ Shape name
-
shapeType= None¶ Shape type
-
-
class
simtrans.model.SphereData[ソース]¶ ベースクラス:
objectSphere shape data
-
material= None¶ Name of material
-
radius= None¶ Radius
-
-
class
simtrans.model.TransformationModel[ソース]¶ ベースクラス:
objectTransformation model with utility methods
Used as a base class for each models
>>> m = TransformationModel() >>> numpy.allclose(m.gettranslation(), [0, 0, 0]) True >>> numpy.allclose(m.getscale(), [1, 1, 1]) True >>> numpy.allclose(m.getrpy(), [0, 0, 0]) True >>> numpy.allclose(m.getangle()[0], [0, 1, 0]) True >>> numpy.allclose(m.getangle()[1], 0) True
-
matrix= None¶ Transformation matrix (4x4 numpy matrix)
-
rot= None¶ Rotation (4-dim numpy array in quaternion representation)
-
scale= None¶ Scale vector (3-dim numpy array)
-
trans= None¶ Translation vector (3-dim numpy array)
-
Command-line interface¶
simtrans.cli¶
simtrans command line interface
simtrans.catxml¶
Utility command to concatinate two or more xml files to one
Reader and writer¶
simtrans.collada¶
Reader and writer for collada format
| Organization: | AIST |
|---|
Requirements¶
- numpy
- lxml xml parser
- pycollada
simtrans.graphviz¶
Writer for graphviz dot format
| Organization: | MID |
|---|
Examples¶
Write simulation model in graphviz dot format
>>> from . import urdf
>>> r = urdf.URDFReader()
>>> m = r.read('package://atlas_description/urdf/atlas_v3.urdf')
>>> w = GraphvizWriter()
>>> w.write(m, '/tmp/atlas.dot')
>>> from . import sdf
>>> r = sdf.SDFReader()
>>> m = r.read('model://pr2/model.sdf')
>>> w = GraphvizWriter()
>>> w.write(m, '/tmp/pr2.dot')
>>> import os
>>> from . import vrml
>>> r = vrml.VRMLReader()
>>> m = r.read(os.path.expandvars('$OPENHRP_MODEL_PATH/PA10/pa10.main.wrl'))
>>> w = GraphvizWriter()
>>> w.write(m, '/tmp/pa10.dot')
simtrans.sdf¶
Reader and writer for SDF format
| Organization: | AIST |
|---|
Requirements¶
- numpy
- lxml xml parser
- jinja2 template engine
Examples¶
Read SDF model data given the model file
>>> r = SDFReader()
>>> m = r.read('model://pr2/model.sdf')
Write simulation model in SDF format
>>> from . import vrml
>>> r = vrml.VRMLReader()
>>> m = r.read(os.path.expandvars('$OPENHRP_MODEL_PATH/closed-link-sample.wrl'))
>>> w = SDFWriter()
>>> w.write(m, '/tmp/closed-link-sample.sdf')
>>> import subprocess
>>> subprocess.check_call('gz sdf -k /tmp/closed-link-sample.sdf'.split(' '))
0
simtrans.stl¶
Reader and writer for stl format
| Organization: | AIST |
|---|
simtrans.urdf¶
Reader and writer for URDF format
| Organization: | AIST |
|---|
Requirements¶
- numpy
- lxml xml parser
- jinja2 template engine
Examples¶
Read URDF model data given the model file
>>> r = URDFReader()
>>> m = r.read('package://atlas_description/urdf/atlas_v3.urdf')
Write simulation model in URDF format
>>> from . import vrml
>>> r = vrml.VRMLReader()
>>> m = r.read(os.path.expandvars('$OPENHRP_MODEL_PATH/closed-link-sample.wrl'))
>>> w = URDFWriter()
>>> w.write(m, '/tmp/closed-link-sample.urdf')
>>> import subprocess
>>> subprocess.check_call('check_urdf /tmp/closed-link-sample.urdf'.split(' '))
0
-
class
simtrans.urdf.URDFReader[ソース]¶ ベースクラス:
objectURDF reader class
-
read(fname, assethandler=None, options=None)[ソース]¶ Read simulation model in urdf format (internally convert to sdf using gz sdf utility)
-
read2(fname, assethandler=None, options=None)[ソース]¶ Read URDF model data given the model file
** [Deprecated] This function is currently broken but kept for historical reason ** ** (might be fixed if “gz sdf” command not work in some situation) **
パラメタ: - fname – path of the file to read
- assethandler – asset handler (optional)
戻り値: model data
戻り値の型: model.Model
-
simtrans.vrml¶
Reader and writer for VRML format
| Organization: | AIST |
|---|
Requirements¶
- numpy
- omniorb-python
- jinja2 template engine
Examples¶
Read vrml model data given the file path
>>> r = VRMLReader()
>>> m = r.read(os.path.expandvars('$OPENHRP_MODEL_PATH/closed-link-sample.wrl'))
Write simulation model in VRML format
>>> from . import urdf
>>> r = urdf.URDFReader()
>>> m = r.read('package://atlas_description/urdf/atlas_v3.urdf')
>>> w = VRMLWriter()
>>> w.write(m, '/tmp/atlas.wrl')
>>> from . import sdf
>>> r = sdf.SDFReader()
>>> m = r.read('model://pr2/model.sdf')
>>> w = VRMLWriter()
>>> w.write(m, '/tmp/pr2.wrl')
Utility functions¶
simtrans.utils¶
Miscellaneous utility functions
-
simtrans.utils.findchildren(mdata, linkname)[ソース]¶ Find child joints connected to specified link
>>> import subprocess >>> from . import urdf >>> subprocess.call('rosrun xacro xacro.py `rospack find atlas_description`/robots/atlas_v3.urdf.xacro > /tmp/atlas.urdf', shell=True) 0 >>> r = urdf.URDFReader() >>> m = r.read('/tmp/atlas.urdf') >>> [c.child for c in findchildren(m, 'pelvis')] ['ltorso', 'l_uglut', 'r_uglut']
-
simtrans.utils.findparent(mdata, linkname)[ソース]¶ Find parent joints connected to specified link
>>> import subprocess >>> from . import urdf >>> subprocess.call('rosrun xacro xacro.py `rospack find atlas_description`/robots/atlas_v3.urdf.xacro > /tmp/atlas.urdf', shell=True) 0 >>> r = urdf.URDFReader() >>> m = r.read('/tmp/atlas.urdf') >>> [p.parent for p in findparent(m, 'ltorso')] ['pelvis']
-
simtrans.utils.findroot(mdata)[ソース]¶ Find root link from parent to child relationships. Currently based on following simple principle: - Link with no parent will be the root. - Link should have at least one open connection with the other link
>>> import subprocess >>> from . import urdf >>> subprocess.call('rosrun xacro xacro.py `rospack find atlas_description`/robots/atlas_v3.urdf.xacro > /tmp/atlas.urdf', shell=True) 0 >>> r = urdf.URDFReader() >>> m = r.read('/tmp/atlas.urdf') >>> findroot(m) ['pelvis']
>>> from . import urdf >>> r = urdf.URDFReader() >>> m = r.read('package://ur_description/urdf/ur5_robot.urdf') >>> findroot(m) ['world']
>>> import subprocess >>> from . import urdf >>> subprocess.call('rosrun xacro xacro.py `rospack find pr2_description`/robots/pr2.urdf.xacro > /tmp/pr2.urdf', shell=True) 0 >>> r = urdf.URDFReader() >>> m = r.read('/tmp/pr2.urdf') >>> findroot(m) ['base_footprint']
>>> from . import sdf >>> r = sdf.SDFReader() >>> m = r.read('model://pr2/model.sdf') >>> findroot(m) ['base_footprint']
-
simtrans.utils.hasopenlink(mdata, linkname)[ソース]¶ Check if the link has open connection with neighboring links
>>> from . import sdf >>> r = sdf.SDFReader() >>> m = r.read('model://pr2/model.sdf') >>> hasopenlink(m, 'base_footprint') True >>> hasopenlink(m, 'l_gripper_l_parallel_link') False
-
simtrans.utils.resolveFile(f)[ソース]¶ Resolve file by replacing file path heading “package://” or “model://”
>>> resolveFile('package://atlas_description/package.xml') == os.path.expandvars('/opt/ros/$ROS_DISTRO/share/atlas_description/package.xml') True >>> resolveFile('package://atlas_description/urdf/atlas.urdf') == os.path.expandvars('/opt/ros/$ROS_DISTRO/share/atlas_description/urdf/atlas.urdf') True >>> resolveFile('model://pr2/model.sdf') == os.path.expanduser('~/.gazebo/models/pr2/model.sdf') True >>> resolveFile('model://PA10/pa10.main.wrl') == os.path.expandvars('$OPENHRP_MODEL_PATH/PA10/pa10.main.wrl') True