Code Monkey home page Code Monkey logo

gazebo_domain_randomization's Introduction

Gazebo Domain Randomization

Build Status

https://arxiv.org/abs/1703.06907

Double pendulum demo

result

Shadow hand demo

sr_hand

Run

roslaunch gazebo_domain_randomizer demo.launch

If you want to randomize with external trigger, execute with the following option.

roslaunch gazebo_domain_randomizer demo.launch event_mode:='trigger'

And please execute the following command on another console.

rostopic pub /randomizers/randomizer/trigger std_msgs/Empty "{}"  -r 1.0

Settings

To use the randamizers, you need to make the following two settings.

  1. For physics parameters randomization, set physics_plugin (WorldPlugin) in the world file.
<sdf version="1.6">
  <world name="default">
    <include>
      <uri>model://sun</uri>
    </include>
    <include>
      <uri>model://ground_plane</uri>
    </include>
    ...
    <plugin name="physics_plugin" filename="libgazebo_physics_plugin.so"/>
  </world>
</sdf>
  1. For visual randomization, you need to load scene_plugin (SystemPlugin) for gzclient. Therefore, please use the gzclient script in gazebo_domain_randomizer package. It configures to load the system plugin in the script.
<launch>
  ...
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="gui" value="false" />
  </include>
  <node name="gazebo_gui" pkg="gazebo_domain_randomizer" type="gzclient" respawn="false" output="screen" />
  ...
</launch>

Randomizers

Node name Randomized parameter
light_randomizer - light color
- attenuation
shape_randomizer - shape(sphere, box, cylinder)
- shape color
- position(x, y, z)
sky_randomizer - time of day
physics properties randomizer - gravity(x, y, z)
link_properties_randomizer - link mass
joint_properties_randomizer - joint damping
link_visual_properties_randomizer - link color
surface_params_randomizer - link mu1, mu2, mu_torsion
- link poisson ratio

gazebo_domain_randomization's People

Contributors

neka-nat avatar yurirocha15 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar

gazebo_domain_randomization's Issues

Error while building repo

Hi @neka-nat I am trying to build this repo but I get an error :

image

from what I could understand that you are trying to create a variable of type Color using gazebo::common:Color library, but that library is not included in the gazebo which is installed from binaries in Ubuntu.

I found a gazebo repo which had file gazebo/common/Color.h, the repo is here: https://github.com/arpg/Gazebo

Is this the exact gazebo that I need to build from source to be able to run your gazebo_domain_randomization repo?

Or is there another cause for this error?

Camera in Gazebo

Hi @neka-nat, thank you very much for the great package!

I started using it to change the visual properties of a robotic arm in Gazebo, with a camera in the same environment (using ros camera plugins) collecting images of it and publishing them on a rostopic.

However my image stream does not capture the randomized joint colors from your plugin. I imagine this may be an issue with the camera being ros-based rather than purely gazebo.
Have you ever dealt with this issue before?

Loading my own shapes in shape randomizer

If I'd like to add my own object (represented as collada files) how would I correctly do that in the plugin ? I've noticed you've left a _obj_sdf variable that contains an sdf, tried adding my models to that sdf but I haven't been able to figure out how to refer to the loaded objects later in the code.

Edit: define the _obj_sdf string as a template and pass a model_name variable to it for every model you need to load.

Does it support running on Ubuntu 20.04?

When I was building it in Ubuntu 20.04 and using the (Catkin_make) command to build my project, there was a problem displaying my (gazebo_physics_plugin) folder. Is it because I am using an Ubuntu system that is too high? Are there some dependencies that are not supported?

Python Plugin / Function Call

Hi @neka-nat , this looks fantastic.

I am looking to incorporate this into my own work, but I was wondering how your code actually gets triggered? Is there a way to only change the lights / colors by calling a function / service?

For context, I am using an RL set up, and am looking to only call this function after the reset of each environment.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.