ROS-Gazebo Configuration for Deterministic Simulation

asked 2016-04-14 12:22:04 -0500

JaredMoore gravatar image

I'm currently working on setting up my ROS-Gazebo environment and have encountered a problem that I can't seem to find the answer to. When running a test of dropping a sphere onto a box, the endpoint of the sphere after 4 seconds of simulation time has an element of randomness to it. This will prevent me from being able to use the simulation for my intended purpose (evolutionary robotics).

I've previously used the Open Dynamics Engine in my past research with it running deterministically after setting the random number seed. Accordingly, I am attempting to do the same with ROS-Gazebo and have found what I think are the appropriate settings. I detail them below.

First, I use a piece of code to step the Gazebo simulation in sync with ROS so there shouldn't be a desync issue between the two components. The code is:

#include <math.h>
#include <boost/thread.hpp>
#include <boost/algorithm/string.hpp>

#include <gazebo/gazebo.hh>
#include <gazebo/common/Plugin.hh>
#include <gazebo/msgs/msgs.hh>
#include <gazebo/transport/transport.hh>
#include <gazebo_msgs/LinkStates.h>

#include <ros/ros.h>
#include <ros/subscribe_options.h>

int main(int argc, char** argv)
{
  gazebo::setupClient(argc,argv);
  ros::init(argc, argv, "get_world_time_test");

  // Gazebo WorldControl Topic
  gazebo::transport::NodePtr node(new gazebo::transport::Node());
  node->Init();

  // Gazebo ServerControl Topic
  gazebo::transport::NodePtr serverNode(new gazebo::transport::Node());
  serverNode->Init();

  // Initialize the ROSNode
  ros::NodeHandle* rosnode = new ros::NodeHandle();

  // Gazebo Publishers
  gazebo::transport::PublisherPtr pub = node->Advertise<gazebo::msgs::WorldControl>("~/world_control");

  gazebo::transport::PublisherPtr serverPub = serverNode->Advertise<gazebo::msgs::ServerControl>("/gazebo/server/control");

  // Waits for simulation time update.
  ros::Time last_ros_time_;
  bool wait = true;
  while (wait)
  {
    last_ros_time_ = ros::Time::now();

    if (last_ros_time_.toSec() > 0) {
      if (last_ros_time_.toSec() >= 2.0) {
        //Removed code to print position of ball to the screen.
      }
    }    

    // Publish the step message for the simulation.
    gazebo::msgs::WorldControl msg;
    msg.set_step(1);
    pub->Publish(msg);

    // Wait for 1 second and allow ROS to complete as well.
    gazebo::common::Time::MSleep(5);
    ros::spinOnce();
  }

  // Send a server control shutdown message.
  gazebo::msgs::ServerControl serverMsg;
  serverMsg.set_stop(1);
  serverPub->Publish(serverMsg);

  return 0;
}

Second, I set the seed of Gazebo in my launch file to 1 so each simulation should be initialized with the same random number seed. In my previous experience, this was enough to have ODE run deterministically for the same robot and controller in multiple simulations. (The robot would move along the same path and the same distance provided it ran for the same amount of simulation time.) The launch file is as follows:

<launch>
  <arg name="paused" default="true"/>
  <arg name="use_sim_time" default="true"/>
  <arg name="gui" default="true"/>
  <arg name="headless" default="false"/>
  <arg name="debug" default="false"/>
  <arg name="world_name" default="$(find firstbot_gazebo)/worlds/firstbot_world.world"/> 

  <!-- set use_sim_time flag -->
  <group if="$(arg use_sim_time)">
    <param name="/use_sim_time" value="true" />
  </group>

  <!-- set command arguments -->
  <arg unless="$(arg paused)" name="command_arg1" value=""/>
  <arg     if="$(arg paused)" name="command_arg1" value="-u"/>
  <arg unless="$(arg headless)" name="command_arg2 ...
(more)
edit retag flag offensive close merge delete

Comments

1

Hi,

I know I am two years late but I am still interested in the topic since I am using ROS/Gazebo for some reinforcement learning simulation.

Were you able to run the simulator in a synchronous way in the end?

Many thanks!

pulver gravatar image pulver  ( 2019-02-08 10:33:31 -0500 )edit
1

I would suggest you post this over at the Gazebo Answers site, seeing as it's really about Gazebo configuration, not a ROS issue.

If you do, please post a comment here with a link to your Gazebo Answers question, so we can keep things connected.

gvdhoorn gravatar image gvdhoorn  ( 2019-02-08 10:41:55 -0500 )edit