KITcar Simulation
2020.12

Tutorials

  • Installation
  • Getting Started
  • master.launch
  • Drive in Simulation
  • Roads
  • Road Sections
  • Models and Sensors
  • Simulated Rosbags
  • Datasets
  • Cycle GAN
  • How to Write Tests Using the Simulation

ROS Packages

  • gazebo_simulation
  • simulation_brain_link
  • simulation_evaluation
  • simulation_groundtruth

Python Packages

  • simulation.utils.basics package
  • simulation.utils.geometry package
  • simulation.utils.machine_learning package
  • simulation.utils.ros_base package
  • simulation.utils.road package
  • simulation.utils.urdf package
    • simulation.utils.urdf.camera module
    • simulation.utils.urdf.core module
    • simulation.utils.urdf.gazebo module
    • simulation.utils.urdf.joint module
    • simulation.utils.urdf.link module
      • Summary
      • Reference
    • Summary

Docker Images

  • Docker Images

Mini - Talks

  • Names and Values in Python
  • Inheritance in Python
  • Continuous Integration using the Simulation
  • Just Use Tmux
  • Onboarding
KITcar Simulation
  • »
  • simulation.utils.urdf package »
  • simulation.utils.urdf.link module
  • View page source

simulation.utils.urdf.link module¶

Class definitions making up the <link>.

Example

A simple link with the shape of a rectangular box can be defined as follows:

>>> from simulation.utils.geometry import Vector
>>> from simulation.utils.urdf import Geometry, Box, Material, Link, Collision, Visual
>>> box = Geometry(Box(Vector(2, 2, 2)))
>>> material = Material("mat", color=Vector(1, 1, 1))
>>> link = Link(
...     "link",
...     collision=Collision(geometry=box),
...     visual=Visual(geometry=box, material=material),
... )
>>> link.use_inertial_from_collision(mass=1.0)
...  # Calculate inertial tensor from simulation.utils.geometry and mass

Summary¶

Classes:

Box

Collision

Color

Cylinder

Geometry

Inertia

Inertial

Link

Material

Mesh

Sphere

Visual

Reference¶

_origin_default_list()[source]¶
class Color(xyz: simulation.utils.urdf.core.Attribute = <factory>)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'color'¶
xyz: simulation.utils.urdf.core.Attribute¶
class Inertia(ixx: simulation.utils.urdf.core.Attribute = 0, ixy: simulation.utils.urdf.core.Attribute = 0, ixz: simulation.utils.urdf.core.Attribute = 0, iyx: simulation.utils.urdf.core.Attribute = 0, iyy: simulation.utils.urdf.core.Attribute = 0, iyz: simulation.utils.urdf.core.Attribute = 0, izx: simulation.utils.urdf.core.Attribute = 0, izy: simulation.utils.urdf.core.Attribute = 0, izz: simulation.utils.urdf.core.Attribute = 0)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'inertia'¶
ixx: simulation.utils.urdf.core.Attribute = 0¶
ixy: simulation.utils.urdf.core.Attribute = 0¶
ixz: simulation.utils.urdf.core.Attribute = 0¶
iyx: simulation.utils.urdf.core.Attribute = 0¶
iyy: simulation.utils.urdf.core.Attribute = 0¶
iyz: simulation.utils.urdf.core.Attribute = 0¶
izx: simulation.utils.urdf.core.Attribute = 0¶
izy: simulation.utils.urdf.core.Attribute = 0¶
izz: simulation.utils.urdf.core.Attribute = 0¶
class Inertial(mass: float, inertia: simulation.utils.urdf.link.Inertia, origin: simulation.utils.urdf.core.Origin = None)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'inertial'¶
mass: float¶
inertia: simulation.utils.urdf.link.Inertia¶
origin: simulation.utils.urdf.core.Origin = None¶
create_xml(root_el=None)[source]¶

Convert this instance into a xml element.

  • If the class of this instance does not define a tag, new xml elements from this instance are appended to the root_el. Otherwise, a sub element is created and returned.

  • Additionally to all instance attributes, a dictionary parameters can be used to define sub elements.

  • A Attribute type annotation for any of the object`s attributes, will result in a xml attribute.

Parameters

root_el – Optional element that is used a parent xml element when provided.

class Geometry(value: simulation.utils.urdf.core.XmlObject)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'geometry'¶
value: simulation.utils.urdf.core.XmlObject¶
class Box(size: simulation.utils.urdf.core.Attribute)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'box'¶
size: simulation.utils.urdf.core.Attribute¶
calculate_inertia(mass) → simulation.utils.urdf.link.Inertia[source]¶
class Sphere(radius: simulation.utils.urdf.core.Attribute)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'sphere'¶
radius: simulation.utils.urdf.core.Attribute¶
calculate_inertia(mass) → simulation.utils.urdf.link.Inertia[source]¶
class Cylinder(radius: simulation.utils.urdf.core.Attribute, length: simulation.utils.urdf.core.Attribute)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'cylinder'¶
radius: simulation.utils.urdf.core.Attribute¶
length: simulation.utils.urdf.core.Attribute¶
calculate_inertia(mass) → simulation.utils.urdf.link.Inertia[source]¶
class Mesh(filename: simulation.utils.urdf.core.Attribute, scale: simulation.utils.geometry.vector.Vector = None)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'mesh'¶
filename: simulation.utils.urdf.core.Attribute¶
scale: simulation.utils.geometry.vector.Vector = None¶
class Collision(origin: simulation.utils.urdf.core.Origin = None, geometry: simulation.utils.urdf.link.Geometry = None)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'collision'¶
origin: simulation.utils.urdf.core.Origin = None¶
geometry: simulation.utils.urdf.link.Geometry = None¶
class Material(name: simulation.utils.urdf.core.Attribute = None, color: simulation.utils.geometry.vector.Vector = None, texture: str = None)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'material'¶
name: simulation.utils.urdf.core.Attribute = None¶
color: simulation.utils.geometry.vector.Vector = None¶
texture: str = None¶
class Visual(origin: Tuple = None, geometry: simulation.utils.urdf.link.Geometry = None, material: simulation.utils.urdf.link.Material = None)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'visual'¶
origin: Tuple = None¶
geometry: simulation.utils.urdf.link.Geometry = None¶
material: simulation.utils.urdf.link.Material = None¶
class Link(name: simulation.utils.urdf.core.Attribute, collision: simulation.utils.urdf.link.Collision = None, visual: simulation.utils.urdf.link.Collision = None, inertial: simulation.utils.urdf.link.Inertial = None)[source]¶

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'link'¶
name: simulation.utils.urdf.core.Attribute¶
collision: simulation.utils.urdf.link.Collision = None¶
visual: simulation.utils.urdf.link.Collision = None¶
inertial: simulation.utils.urdf.link.Inertial = None¶
use_inertial_from_collision(mass: float)[source]¶
Next Previous

© Copyright 2020, KITcar

Built with Sphinx using a theme provided by Read the Docs.