ros-simulation / gazebo_ros_pkgs

Wrappers, tools and additional API's for using ROS with Gazebo
http://wiki.ros.org/gazebo_ros_pkgs
773 stars 772 forks source link

Spawning a light takes 10 seconds #300

Open lguyot opened 9 years ago

lguyot commented 9 years ago

Spawning a light by means of the service /gazebo/spawn_sdf_model takes always 10 seconds.

The reason is the following: GazeboRosApiPlugin::spawnSDFModel calls in turn GazeboRosApiPlugin::spawnAndConform which makes the following verification:

while (ros::ok())
  {
    if (ros::Time::now() > timeout)
    {
      res.success = false;
      res.status_message = std::string("SpawnModel: Model pushed to spawn queue, but spawn service")
        + std::string(" timed out waiting for model to appear in simulation under the name ")
        + model_name;
      return true;
    }

    {
      //boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
      if (world_->GetModel(model_name))
        break;
    }

    ROS_DEBUG_STREAM_ONCE_NAMED("api_plugin","Waiting for " << timeout - ros::Time::now()
      << " for model " << model_name << " to spawn");

    usleep(2000);
  }

Since world_->GetModel(model_name) is always false for a light (unless some model bears the same name as the light!), we exit the while loop only after timeout, i.e. 10 seconds after entering it.

The fix would be something like this (close to what is already done in gazebo/test/ServerFixture.cc):

while (ros::ok())
  {
    if (ros::Time::now() > timeout)
    {
      res.success = false;
      res.status_message = std::string("SpawnModel: Model pushed to spawn queue, but spawn service")
        + std::string(" timed out waiting for model to appear in simulation under the name ")
        + model_name;
      return true;
    }

    {
      if (isLight) {
        const msgs::Scene &sceneMsg = world_->GetSceneMsg();
        const int size = sceneMsg.light_size();
        bool success = false;
        // Check if the light was actually spawned
        for (unsigned int i = 0; i < size; ++i) 
        {
          if (sceneMsg.light(i).name().compare(model_name) == 0) 
          {
            success = true;
            break;
          }
        }
        if (success) 
        {
          break;
        }
      } else {
        // Check if the model was actually spawned
        if (world_->GetModel(model_name))
          break;
      }
    }

The isLight variable above would be an extra argument of the GazeboRosApiPlugin::spawnAndConform method indicating that a light should be spawned. With the above snippet, we assume that a new service, say /gazebo/spawn_sdf_light, is created and it triggers a new method, say GazeboRosApiPlugin::spawnSDFLight which in turn calls GazeboRosApiPlugin::spawnAndConform with its new argument or a custom method that checks light spawning properly.

cgnarendiran commented 6 years ago

Is anyone working on this issue? Creation of this new service in gazebo _/gazebo/spawn_sdflight would be very helpful to spawn a light and to distinguish from existing services (spawn_urdf_model, spawn_sdf_model, spawn_gazebo_model) which serve different purposes

kev-the-dev commented 6 years ago

Can you give me an example of a current service call you use to do this so I can look into it?

kev-the-dev commented 6 years ago

Actually looks like this was added in #511. It should no longer have this issue in kinetic and later.