simulation.utils.urdf package
Submodules
simulation.utils.urdf.camera module
Class definitions of tags used to define cameras.
Classes:
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
- class CameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None)[source]
Bases:
objectAttributes:
- horizontal_fov: float
- update_rate: float
- image_width: float
- image_height: float
- image_format: float
- clip_near: float
- clip_far: float
- image_topic: str
- info_topic: str
- frame_name: str
- optical_center_x: float = None
- optical_center_y: float = None
- class DepthCameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None, point_cloud_cutoff: float = None, point_cloud_topic_name: str = None)[source]
Bases:
CameraPropertiesAttributes:
- point_cloud_cutoff: float = None
- point_cloud_topic_name: str = None
- horizontal_fov: float
- update_rate: float
- image_width: float
- image_height: float
- image_format: float
- clip_near: float
- clip_far: float
- image_topic: str
- info_topic: str
- frame_name: str
- class CameraPlugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute, alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None)[source]
Bases:
PluginAttributes:
- alwaysOn: float = 1
- updateRate: float = 0
- frameName: str = None
- cameraName: str = None
- CxPrime: float = None
- Cx: float = None
- Cy: float = None
- class MonoCameraPlugin(name: simulation.utils.urdf.core.Attribute = 'camera_plugin', filename: simulation.utils.urdf.core.Attribute = 'libgazebo_ros_camera.so', alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None, imageTopicName: str = None, cameraInfoTopicName: str = None)[source]
Bases:
CameraPluginAttributes:
- imageTopicName: str = None
- cameraInfoTopicName: str = None
- class DepthCameraPlugin(name: simulation.utils.urdf.core.Attribute = 'camera_plugin', filename: simulation.utils.urdf.core.Attribute = 'libgazebo_ros_openni_kinect.so', alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None, depthImageTopicName: str = None, depthImageCameraInfoTopicName: str = None, pointCloudTopicName: str = None, pointCloudCutoff: float = None)[source]
Bases:
CameraPluginAttributes:
- depthImageTopicName: str = None
- depthImageCameraInfoTopicName: str = None
- pointCloudTopicName: str = None
- pointCloudCutoff: float = None
- class CameraImage(width: int, height: int, format: str)[source]
Bases:
XmlObjectAttributes:
- TAG = 'image'
- width: int
- height: int
- format: str
- class CameraClip(near: float, far: float)[source]
Bases:
XmlObjectAttributes:
- TAG = 'clip'
- near: float
- far: float
- class CameraDefinition(horizontal_fov: float, image: simulation.utils.urdf.camera.CameraImage, clip: simulation.utils.urdf.camera.CameraClip = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'camera'
- horizontal_fov: float
- image: CameraImage
- clip: CameraClip = None
- class CameraSensor(name: simulation.utils.urdf.core.Attribute, type: simulation.utils.urdf.core.Attribute, plugin: simulation.utils.urdf.camera.CameraPlugin, update_rate: float, camera: simulation.utils.urdf.camera.CameraDefinition)[source]
Bases:
SensorAttributes:
- plugin: CameraPlugin
- update_rate: float
- camera: CameraDefinition
- class _Camera(name: str, origin: simulation.utils.urdf.core.Origin, size: kitcar_utils.geometry.vector.Vector, mass: float, chassis_link: simulation.utils.urdf.link.Link)[source]
Bases:
XmlObjectAttributes:
- sensor: CameraSensor
- class MonoCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: kitcar_utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.CameraProperties, chassis_link: simulation.utils.urdf.link.Link)[source]
Bases:
_CameraAttributes:
- sensor: CameraSensor
- class DepthCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: kitcar_utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.DepthCameraProperties, chassis_link: simulation.utils.urdf.link.Link)[source]
Bases:
_CameraAttributes:
- sensor: CameraSensor
simulation.utils.urdf.core module
Class definitions of core building blocks of the package.
Classes:
|
Basic class that will be converted into a xml attribute. |
Base class for all urdf xml objects. |
|
|
|
|
Functions:
- class Attribute(val: str, name: str | None = None)[source]
Bases:
strBasic class that will be converted into a xml attribute.
Important: Within a subclass of
XmlObjectan attribute can be defined by simply annotating a class variable with py:class:Attribute!Example
>>> from dataclasses import dataclass >>> from simulation.utils.urdf.core import XmlObject, Attribute >>> @dataclass ... class Example(XmlObject): ... TAG = "example" ... name: Attribute ... value1: str ... value2: float = None >>> ex = Example("example_name",value1="I'm an example.")
The code block defines a simple example class that results in the xml string:
<example name="example_name"> <value1>I'm an example.</value1> </example>
- Parameters:
val – Attribute value.
name – Optionally the name of the can be provided. By default the name of the Attribute instance defines the name of the resulting xml attribute.
- class XmlObject[source]
Bases:
objectBase class for all urdf xml objects.
Attributes:
Methods:
_get_val(val)Convert a value to a string that is included into the xml.
create_xml([root_el])Convert this instance into a xml element.
save(file_path)Save this instance as a xml string to a file.
- TAG = None
- create_xml(root_el: Element | None = None) Element[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
parameterscan be used to define sub elements.A
Attributetype 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.
simulation.utils.urdf.gazebo module
Class definitions of tags used only for gazebo.
Classes:
|
|
|
|
|
- class Plugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
- TAG = 'plugin'
- class Gazebo(inner: simulation.utils.urdf.core.XmlObject, material: str = None, reference: simulation.utils.urdf.core.Attribute = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'gazebo'
- material: str = None
simulation.utils.urdf.joint module
Class definitions making up the <joint>.
Example
A simple joint connecting link2 to
link1 with a revolute joint that can rotate along the z-axis:
>>> from simulation.utils.urdf import (
... Origin, Link, Joint, Parent, Child, Axis, JointLimit, JointDynamics
... )
>>> link1 = Link("link_1")
>>> link2 = Link("link_2")
>>> simple_joint = Joint(
... name="simple_joint",
... parent=Parent(link1.name),
... child=Child(link2.name),
... type=Joint.REVOLUTE,
... origin=Origin([1,3,2]),
... axis=Axis([0, 0, 1]),
... limit=JointLimit(effort=1000, lower=-10, upper=10),
... dynamics=JointDynamics(damping=1, friction=1),
... )
Classes:
|
|
|
|
|
|
|
|
|
- class JointDynamics(damping: simulation.utils.urdf.core.Attribute = None, friction: simulation.utils.urdf.core.Attribute = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'dynamics'
- class JointLimit(effort: simulation.utils.urdf.core.Attribute = None, lower: simulation.utils.urdf.core.Attribute = None, upper: simulation.utils.urdf.core.Attribute = None, velocity: simulation.utils.urdf.core.Attribute = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'limit'
- class Parent(link: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
- TAG = 'parent'
- class Child(link: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
- TAG = 'child'
- class Joint(name: simulation.utils.urdf.core.Attribute, parent: simulation.utils.urdf.joint.Parent, child: simulation.utils.urdf.joint.Child, type: simulation.utils.urdf.core.Attribute = 'fixed', axis: kitcar_utils.geometry.vector.Vector = None, limit: simulation.utils.urdf.joint.JointLimit = None, dynamics: simulation.utils.urdf.joint.JointDynamics = None, origin: simulation.utils.urdf.core.Origin = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'joint'
- FIXED = 'fixed'
- REVOLUTE = 'revolute'
- CONTINUOUS = 'continuous'
- axis: Vector = None
- limit: JointLimit = None
- dynamics: JointDynamics = None
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 kitcar_utils.geometry import Vector
>>> from simulation.utils.urdf import (Geometry, Box, Link, Collision, Visual, Gazebo)
>>> box = Geometry(Box(Vector(2, 2, 2)))
>>> link = Link(
... "link",
... collision=Collision(geometry=box),
... visual=Visual(geometry=box),
... )
>>> # Calculate inertial tensor from kitcar_utils.geometry and mass
>>> link.use_inertial_from_collision(mass=1.0)
>>> # Add a gazebo material script
>>> gazebo_material = Gazebo(
... material="Gazebo/Gray", reference="link", inner=None
... )
Functions:
Classes:
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
- class Color(xyz: simulation.utils.urdf.core.Attribute = <factory>)[source]
Bases:
XmlObjectAttributes:
- TAG = 'color'
- 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:
XmlObjectAttributes:
- TAG = 'inertia'
- class Inertial(mass: float, inertia: simulation.utils.urdf.link.Inertia, origin: simulation.utils.urdf.core.Origin = None)[source]
Bases:
XmlObjectAttributes:
Methods:
create_xml([root_el])Convert this instance into a xml element.
- TAG = 'inertial'
- mass: float
- 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
parameterscan be used to define sub elements.A
Attributetype 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:
XmlObjectAttributes:
- TAG = 'geometry'
- class Box(size: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
Methods:
calculate_inertia(mass)- TAG = 'box'
- class Sphere(radius: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
Methods:
calculate_inertia(mass)- TAG = 'sphere'
- class Cylinder(radius: simulation.utils.urdf.core.Attribute, length: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
Methods:
calculate_inertia(mass)- TAG = 'cylinder'
- class Mesh(filename: simulation.utils.urdf.core.Attribute, scale: kitcar_utils.geometry.vector.Vector = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'mesh'
- scale: Vector = None
- class Collision(origin: simulation.utils.urdf.core.Origin = None, geometry: simulation.utils.urdf.link.Geometry = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'collision'
- class Visual(origin: Tuple = None, geometry: simulation.utils.urdf.link.Geometry = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'visual'
- origin: Tuple = 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:
XmlObjectAttributes:
Methods:
- TAG = 'link'
Module contents
Module package to create .urdf model definitions.
The package contains a number of classes that enable to define urdf robots through python.
For what? The urdf is very repetetive to write and requires prior knowledge on available tags and how they can be combined to a fully specified robot. Additionally, the commonly used xacro is less powerful than python and, again, another tool.
The basic idea used throughout the package is the inheritance from XmlObject.
XmlObject.create_xml() creates a xml.etree.ElementTree.Element
from the class instance.
It does so by converting all instance attributes into xml attributes and sub elements.
If a class attribute is an instance of a subclass of XmlObject,
the objects XmlObject.create_xml() is called recursively.
The XmlObject in combination with
dataclasses
allows to create lightweight classes that define urdf components when converted to xml.
Classes:
|
Basic class that will be converted into a xml attribute. |
Base class for all urdf xml objects. |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
- class Attribute(val: str, name: str | None = None)[source]
Bases:
strBasic class that will be converted into a xml attribute.
Important: Within a subclass of
XmlObjectan attribute can be defined by simply annotating a class variable with py:class:Attribute!Example
>>> from dataclasses import dataclass >>> from simulation.utils.urdf.core import XmlObject, Attribute >>> @dataclass ... class Example(XmlObject): ... TAG = "example" ... name: Attribute ... value1: str ... value2: float = None >>> ex = Example("example_name",value1="I'm an example.")
The code block defines a simple example class that results in the xml string:
<example name="example_name"> <value1>I'm an example.</value1> </example>
- Parameters:
val – Attribute value.
name – Optionally the name of the can be provided. By default the name of the Attribute instance defines the name of the resulting xml attribute.
- class XmlObject[source]
Bases:
objectBase class for all urdf xml objects.
Attributes:
Methods:
_get_val(val)Convert a value to a string that is included into the xml.
create_xml([root_el])Convert this instance into a xml element.
save(file_path)Save this instance as a xml string to a file.
- TAG = None
- create_xml(root_el: Element | None = None) Element[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
parameterscan be used to define sub elements.A
Attributetype 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 Origin(xyz: simulation.utils.urdf.core.Attribute = <factory>, rpy: simulation.utils.urdf.core.Attribute = <factory>)[source]
Bases:
XmlObjectAttributes:
Methods:
from_vector(vector)from_list(lst)- TAG = 'origin'
- class Axis(xyz: simulation.utils.urdf.core.Attribute = <factory>)[source]
Bases:
XmlObjectAttributes:
- TAG = 'axis'
- class Color(xyz: simulation.utils.urdf.core.Attribute = <factory>)[source]
Bases:
XmlObjectAttributes:
- TAG = 'color'
- 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:
XmlObjectAttributes:
- TAG = 'inertia'
- class Inertial(mass: float, inertia: simulation.utils.urdf.link.Inertia, origin: simulation.utils.urdf.core.Origin = None)[source]
Bases:
XmlObjectAttributes:
Methods:
create_xml([root_el])Convert this instance into a xml element.
- TAG = 'inertial'
- mass: float
- 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
parameterscan be used to define sub elements.A
Attributetype 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 Box(size: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
Methods:
calculate_inertia(mass)- TAG = 'box'
- class Sphere(radius: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
Methods:
calculate_inertia(mass)- TAG = 'sphere'
- class Cylinder(radius: simulation.utils.urdf.core.Attribute, length: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
Methods:
calculate_inertia(mass)- TAG = 'cylinder'
- class Geometry(value: simulation.utils.urdf.core.XmlObject)[source]
Bases:
XmlObjectAttributes:
- TAG = 'geometry'
- class Mesh(filename: simulation.utils.urdf.core.Attribute, scale: kitcar_utils.geometry.vector.Vector = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'mesh'
- scale: Vector = None
- class Visual(origin: Tuple = None, geometry: simulation.utils.urdf.link.Geometry = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'visual'
- origin: Tuple = None
- class Collision(origin: simulation.utils.urdf.core.Origin = None, geometry: simulation.utils.urdf.link.Geometry = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'collision'
- 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:
XmlObjectAttributes:
Methods:
- TAG = 'link'
- class JointDynamics(damping: simulation.utils.urdf.core.Attribute = None, friction: simulation.utils.urdf.core.Attribute = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'dynamics'
- class JointLimit(effort: simulation.utils.urdf.core.Attribute = None, lower: simulation.utils.urdf.core.Attribute = None, upper: simulation.utils.urdf.core.Attribute = None, velocity: simulation.utils.urdf.core.Attribute = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'limit'
- class Parent(link: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
- TAG = 'parent'
- class Child(link: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
- TAG = 'child'
- class Joint(name: simulation.utils.urdf.core.Attribute, parent: simulation.utils.urdf.joint.Parent, child: simulation.utils.urdf.joint.Child, type: simulation.utils.urdf.core.Attribute = 'fixed', axis: kitcar_utils.geometry.vector.Vector = None, limit: simulation.utils.urdf.joint.JointLimit = None, dynamics: simulation.utils.urdf.joint.JointDynamics = None, origin: simulation.utils.urdf.core.Origin = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'joint'
- FIXED = 'fixed'
- REVOLUTE = 'revolute'
- CONTINUOUS = 'continuous'
- axis: Vector = None
- limit: JointLimit = None
- dynamics: JointDynamics = None
- class Plugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
- TAG = 'plugin'
- class Gazebo(inner: simulation.utils.urdf.core.XmlObject, material: str = None, reference: simulation.utils.urdf.core.Attribute = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'gazebo'
- material: str = None
- class Sensor(name: simulation.utils.urdf.core.Attribute, type: simulation.utils.urdf.core.Attribute)[source]
Bases:
XmlObjectAttributes:
- TAG = 'sensor'
- class MonoCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: kitcar_utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.CameraProperties, chassis_link: simulation.utils.urdf.link.Link)[source]
Bases:
_CameraAttributes:
- sensor: CameraSensor
- class DepthCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: kitcar_utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.DepthCameraProperties, chassis_link: simulation.utils.urdf.link.Link)[source]
Bases:
_CameraAttributes:
- sensor: CameraSensor
- class CameraClip(near: float, far: float)[source]
Bases:
XmlObjectAttributes:
- TAG = 'clip'
- near: float
- far: float
- class CameraDefinition(horizontal_fov: float, image: simulation.utils.urdf.camera.CameraImage, clip: simulation.utils.urdf.camera.CameraClip = None)[source]
Bases:
XmlObjectAttributes:
- TAG = 'camera'
- horizontal_fov: float
- image: CameraImage
- clip: CameraClip = None
- class CameraImage(width: int, height: int, format: str)[source]
Bases:
XmlObjectAttributes:
- TAG = 'image'
- width: int
- height: int
- format: str
- class CameraPlugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute, alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None)[source]
Bases:
PluginAttributes:
- alwaysOn: float = 1
- updateRate: float = 0
- frameName: str = None
- cameraName: str = None
- CxPrime: float = None
- Cx: float = None
- Cy: float = None
- class DepthCameraPlugin(name: simulation.utils.urdf.core.Attribute = 'camera_plugin', filename: simulation.utils.urdf.core.Attribute = 'libgazebo_ros_openni_kinect.so', alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None, depthImageTopicName: str = None, depthImageCameraInfoTopicName: str = None, pointCloudTopicName: str = None, pointCloudCutoff: float = None)[source]
Bases:
CameraPluginAttributes:
- depthImageTopicName: str = None
- depthImageCameraInfoTopicName: str = None
- pointCloudTopicName: str = None
- pointCloudCutoff: float = None
- class CameraSensor(name: simulation.utils.urdf.core.Attribute, type: simulation.utils.urdf.core.Attribute, plugin: simulation.utils.urdf.camera.CameraPlugin, update_rate: float, camera: simulation.utils.urdf.camera.CameraDefinition)[source]
Bases:
SensorAttributes:
- plugin: CameraPlugin
- update_rate: float
- camera: CameraDefinition
- class CameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None)[source]
Bases:
objectAttributes:
- horizontal_fov: float
- update_rate: float
- image_width: float
- image_height: float
- image_format: float
- clip_near: float
- clip_far: float
- image_topic: str
- info_topic: str
- frame_name: str
- optical_center_x: float = None
- optical_center_y: float = None
- class DepthCameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None, point_cloud_cutoff: float = None, point_cloud_topic_name: str = None)[source]
Bases:
CameraPropertiesAttributes:
- point_cloud_cutoff: float = None
- point_cloud_topic_name: str = None
- horizontal_fov: float
- update_rate: float
- image_width: float
- image_height: float
- image_format: float
- clip_near: float
- clip_far: float
- image_topic: str
- info_topic: str
- frame_name: str