Skip to content

Commit

Permalink
add context helpers for sensors
Browse files Browse the repository at this point in the history
  • Loading branch information
diegoferigo committed Nov 8, 2020
1 parent 1d89f60 commit 8059726
Show file tree
Hide file tree
Showing 3 changed files with 99 additions and 0 deletions.
2 changes: 2 additions & 0 deletions python/gym_ignition/context/gazebo/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,6 @@
# GNU Lesser General Public License v2.1 or any later version.

from . import plugin
from . import shapes
from . import sensors
from . import controllers
59 changes: 59 additions & 0 deletions python/gym_ignition/context/gazebo/sensors.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
# Copyright (C) 2020 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.

from dataclasses import dataclass
from gym_ignition.context import plugin


@dataclass
class DepthCamera(plugin.Plugin): # TODO: this is not a plugin, make a sensor template?

name: str
width: int = 256
height: int = 256
fov: float = 1.05

topic: str = ""
# TODO: static

def to_xml(self) -> str: # .sdf()?
xml = f"""
<model name="{self.model_name}">
<static>true</static>
<link name="{self.name}_link">
<sensor name="{self.name}" type="depth_camera">
<always_on>1</always_on>
<visualize>true</visualize>
<topic>{self.topic}</topic>
<camera>
<horizontal_fov>{self.fov}</horizontal_fov>
<image>
<width>{self.width}</width>
<height>{self.height}</height>
<format>R_FLOAT32</format>
</image>
<clip>
<near>0.1</near>
<far>10.0</far>
</clip>
</camera>
</sensor>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
</link>
</model>
"""

return DepthCamera.wrap_in_sdf(xml)

@property
def model_name(self) -> str:
return f"{self.name}_model"
38 changes: 38 additions & 0 deletions python/gym_ignition/context/gazebo/shapes.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
from dataclasses import dataclass
# TODO: urdf or sdf? Urdf for iDynTree, otherwise SDF.


@dataclass
class BoxURDF:

mass: float = 5.0
edge: float = 0.2
name: str = "cube_robot"

def urdf(self) -> str:

i = 1.0 / 12 * self.mass * (self.edge ** 2 + self.edge ** 2)
urdf = f"""
<robot name="{self.name}" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="cube">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="{self.mass}"/>
<inertia ixx="{i}" ixy="0" ixz="0" iyy="{i}" iyz="0" izz="{i}"/>
</inertial>
<visual>
<geometry>
<box size="{self.edge} {self.edge} {self.edge}"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</visual>
<collision>
<geometry>
<box size="{self.edge} {self.edge} {self.edge}"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
</robot>"""

return urdf

0 comments on commit 8059726

Please sign in to comment.