Gazebo Sim

API Reference

8.7.0
Entity creation

This tutorial gives an introduction to Gazebo Sim's service /world/<world name>/create. This service allows creating entities in the scene such us spheres, lights, etc.

Gazebo creates many services depending on the plugins that are specified in the SDF. In this case we need to load the UserCommands plugin, which will offer the create service. You can include the UserCommands system plugin including these lines in your SDF:

<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>

You can check if this service is available typing:

In one terminal

gz sim -r -v 4 <your_world>.sdf

In another terminal, see if the create service is listed:

gz service --list
/gazebo/resource_paths/add
/gazebo/resource_paths/get
/gazebo/worlds
/gui/follow
/gui/move_to
/gui/move_to/pose
/gui/record_video
/gui/transform_mode
/gui/view_angle
/marker
/marker/list
/marker_array
/server_control
/world/world_name/control
/world/world_name/create
/world/world_name/create_multiple
/world/world_name/generate_world_sdf
/world/world_name/gui/info
/world/world_name/level/set_performer
/world/world_name/light_config
/world/world_name/playback/control
/world/world_name/remove
/world/world_name/scene/graph
/world/world_name/scene/info
/world/world_name/set_pose
/world/world_name/state
/world/world_name/state_async

Factory message

To create new entities in the world we need to use the gz::msgs::EntityFactory message to send a request to the create service. This message allows us to create entities from strings, files, Models, Lights or even clone models. This tutorial introduces how to create entities from SDF strings and light messages.

Insert an entity based on a string

We will open an empty Gazebo world, let's start creating a sphere in the world. In the next snippet you can see how to create models based on strings.

auto sphereStr = R"(
<?xml version="1.0" ?>
<sdf version='1.7'>
<model name='sphere'>
<link name='link'>
<pose>0 0 0.5 0 0 0</pose>
<visual name='visual'>
<geometry><sphere><radius>1</radius></sphere></geometry>
</visual>
<collision name='collision'>
<geometry><sphere><radius>1</radius></sphere></geometry>
</collision>
</link>
</model>
</sdf>)";

The variable sphereStr contains the SDF of the model that we want to create in the world. In this case we are creating a sphere of 1 meter of radius in the position: x: 0 y: 0 z: 0.5 roll: 0 pitch: 0 yaw: 0.

NOTE: You can insert here all kinds of models that can be described using an SDF string.

Then we need to call the service /world/<world_name>/create:

bool result;
gz::msgs::EntityFactory req;
gz::msgs::Boolean res;
req.set_sdf(modelStr);
bool executed = node.Request("/world/empty/create",
req, timeout, res, result);
if (executed)
{
if (result)
std::cout << "Entity was created : [" << res.data() << "]" << std::endl;
else
{
std::cout << "Service call failed" << std::endl;
return;
}
}
else
std::cerr << "Service call timed out" << std::endl;

NOTE: By default, if the entity name does not exist then the entity will be created in the world. On the other hand, if that entity name already exists, then nothing will happen. You may see some traces in the console showing this information. There is an option to create a new entity every time that the message is sent by setting allow_renaming to true (you can use the method set_allow_renaming()).

Insert a light

To insert a light in the world we have two options:

  • Fill the string inside the gz::msgs::EntityFactory message like in the section above.
  • Fill the field light inside the gz::msgs::EntityFactory message.

In the following snippet you can see how the light's field is filled.

gz::msgs::EntityFactory entityFactoryRequest;
entityFactoryRequest.mutable_light()->set_name("point");
entityFactoryRequest.mutable_light()->set_range(4);
entityFactoryRequest.mutable_light()->set_attenuation_linear(0.5);
entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2);
entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01);
entityFactoryRequest.mutable_light()->set_cast_shadows(false);
entityFactoryRequest.mutable_light()->set_type(gz::msgs::Light::POINT);
entityFactoryRequest.mutable_light()->mutable_direction(),
gz::math::Vector3d(0.5, 0.2, -0.9));
gz::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(),
gz::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0));

Or we can create an SDF string:

std::string lightStr = std::string("<sdf version='1.7'>") +
"<light type='" + light_type + "' name='" + name + "'> " +
"<cast_shadows>" + std::to_string(cast_shadows) + "</cast_shadows>" +
"<pose>" +
std::to_string(pose.Pos().X()) + " " +
std::to_string(pose.Pos().Y()) + " " +
std::to_string(pose.Pos().Z()) + " " +
std::to_string(pose.Rot().Roll()) + " " +
std::to_string(pose.Rot().Pitch()) + " " +
std::to_string(pose.Rot().Yaw()) +
"</pose>" +
"<diffuse>" +
std::to_string(diffuse.R()) + " " +
std::to_string(diffuse.G()) + " " +
std::to_string(diffuse.B()) + " " +
std::to_string(diffuse.A()) +
"</diffuse>" +
"<specular>" +
std::to_string(specular.R()) + " " +
std::to_string(specular.G()) + " " +
std::to_string(specular.B()) + " " +
std::to_string(specular.A()) +
"</specular>" +
"<attenuation>" +
"<range>" + std::to_string(attRange) + "</range>" +
"<constant>" + std::to_string(attConstant) + "</constant>" +
"<linear>" + std::to_string(attLinear) + "</linear>" +
"<quadratic>" + std::to_string(attQuadratic) + "</quadratic>" +
"</attenuation>" +
"<direction>" +
std::to_string(direction.X()) + " " +
std::to_string(direction.Y()) + " " +
std::to_string(direction.Z()) +
"</direction>" +
"<spot>" +
"<inner_angle>" + std::to_string(spot_inner_angle) + "</inner_angle>" +
"<outer_angle>" + std::to_string(spot_outer_angle) + "</outer_angle>" +
"<falloff>" + std::to_string(spot_falloff) + "</falloff>" +
"</spot>" +
"</light></sdf>";

Please check the API to know which fields are available in the Light message. There are three types of lights: Point, Directional and Spot.

Finally we should call the same service /world/<world_name>/create:

bool executedEntityFactory = node.Request("/world/empty/create",
entityFactoryRequest, timeout, rep, result);
if (executedEntityFactory)
{
if (result)
std::cout << "Light was created : [" << rep.data() << "]" << std::endl;
else
{
std::cout << "Service call failed" << std::endl;
return;
}
}
else
std::cerr << "Service call timed out" << std::endl;