Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Ignition Gazebo Fortress: Spawning entities from within a plugin

Dear Gazebo Community,

is it possible to spawn / create an entity from within a plugin in Ignition gazebo fortress?

I would like to create an initial entity in a plugin, which behaves such as a WorldPlugin in the "old" Gazebo world and is responsible for this entity, may additional entities during simulation runtime.

Therefore, the callback cpp public: void Configure(const ignition::gazebo::Entity &_entity, const std::shared_ptr<const sdf::Element> &_sdf, ignition::gazebo::EntityComponentManager &_ecm, ignition::gazebo::EventManager &_eventMgr) final; should be the appropriate step.

I would guess, that using a service request, such as in ros_ign_gazebo's create.cpp


   std::string service{"/world/" + FLAGS_world + "/create"};

  // Request message
  ignition::msgs::EntityFactory req;

  // File
  if (!FLAGS_file.empty())
  {
    req.set_sdf_filename(FLAGS_file);
  }
  // Param
  else if (!FLAGS_param.empty())
  {
    std::string xmlStr;
    if (nh.getParam(FLAGS_param, xmlStr))
    {
      req.set_sdf(xmlStr);
    }
    else
    {
      ROS_ERROR("Failed to get XML from param [%s].", FLAGS_param.c_str());
      return -1;
    }
  }
  // string
  else if (!FLAGS_string.empty())
  {
    req.set_sdf(FLAGS_string);
  }
  else
  {
    ROS_ERROR("Must specify either -file, -param or -stdin");
    return -1;
  }

  // Pose
  ignition::math::Pose3d pose
  {
    FLAGS_x,
    FLAGS_y,
    FLAGS_z,
    FLAGS_R,
    FLAGS_P,
    FLAGS_Y
  };
  ignition::msgs::Set(req.mutable_pose(), pose);

  // Name
  if (!FLAGS_name.empty())
  {
    req.set_name(FLAGS_name);
  }

  if (FLAGS_allow_renaming)
  {
    req.set_allow_renaming(FLAGS_allow_renaming);
  }

  // Request
  ignition::transport::Node node;
  ignition::msgs::Boolean rep;
  bool result;
  unsigned int timeout = 5000;
  bool executed = node.Request(service, req, timeout, rep, result);

  if (executed)
  {
    if (result && rep.data())
      ROS_INFO("Requested creation of entity.");
    else
      ROS_ERROR("Failed request to create entity.\n %s", req.DebugString().c_str());
  }
  else
  {
    ROS_ERROR("Request to create entity from service [%s] timed out..\n %s",
        service.c_str(), req.DebugString().c_str());
  }
[...]

maybe causes a blocking simulation. Is there another way of accessing the spawning mechanism directly via ign API?

BR and thx.

Ignition Gazebo Fortress: Spawning entities from within a plugin

Dear Gazebo Community,

is it possible to spawn / create an entity from within a plugin in Ignition gazebo fortress?

I would like to create an initial entity in a plugin, which behaves such as a WorldPlugin in the "old" Gazebo world and is responsible for this entity, may additional entities during simulation runtime.

Therefore, the callback cpp public: void Configure(const ignition::gazebo::Entity &_entity, const std::shared_ptr<const sdf::Element> &_sdf, ignition::gazebo::EntityComponentManager &_ecm, ignition::gazebo::EventManager &_eventMgr) final; should be the appropriate step.

I would guess, that using a service request, request via ignition transport, such as in ros_ign_gazebo's create.cpp


   std::string service{"/world/" + FLAGS_world + "/create"};

  // Request message
  ignition::msgs::EntityFactory req;

  // File
  if (!FLAGS_file.empty())
  {
    req.set_sdf_filename(FLAGS_file);
  }
  // Param
  else if (!FLAGS_param.empty())
  {
    std::string xmlStr;
    if (nh.getParam(FLAGS_param, xmlStr))
    {
      req.set_sdf(xmlStr);
    }
    else
    {
      ROS_ERROR("Failed to get XML from param [%s].", FLAGS_param.c_str());
      return -1;
    }
  }
  // string
  else if (!FLAGS_string.empty())
  {
    req.set_sdf(FLAGS_string);
  }
  else
  {
    ROS_ERROR("Must specify either -file, -param or -stdin");
    return -1;
  }

  // Pose
  ignition::math::Pose3d pose
  {
    FLAGS_x,
    FLAGS_y,
    FLAGS_z,
    FLAGS_R,
    FLAGS_P,
    FLAGS_Y
  };
  ignition::msgs::Set(req.mutable_pose(), pose);

  // Name
  if (!FLAGS_name.empty())
  {
    req.set_name(FLAGS_name);
  }

  if (FLAGS_allow_renaming)
  {
    req.set_allow_renaming(FLAGS_allow_renaming);
  }

  // Request
  ignition::transport::Node node;
  ignition::msgs::Boolean rep;
  bool result;
  unsigned int timeout = 5000;
  bool executed = node.Request(service, req, timeout, rep, result);

  if (executed)
  {
    if (result && rep.data())
      ROS_INFO("Requested creation of entity.");
    else
      ROS_ERROR("Failed request to create entity.\n %s", req.DebugString().c_str());
  }
  else
  {
    ROS_ERROR("Request to create entity from service [%s] timed out..\n %s",
        service.c_str(), req.DebugString().c_str());
  }
[...]

maybe is the way to go from external applications and might causes a blocking simulation. simulation being used from inside within a plugin. Is there another way of accessing the spawning mechanism for SDFs directly via ign API?

BR and thx.