Gazebo Gazebo

API Reference

6.16.0
ModelPhotoShoot Class Reference

This plugin is a port of the old ModelPropShop plugin from gazebo classic. It generates 5 pictures of a model: perspective, top, front, side and back. It can do it using the default position or moving the joint to random positions. It allows saving the camera and joint poses so it can be replicated in other systems. More...

#include <ModelPhotoShoot.hh>

Public Member Functions

 ModelPhotoShoot ()
 Constructor. More...
 
 ~ModelPhotoShoot () override=default
 Destructor. More...
 
void Configure (const ignition::gazebo::Entity &_id, const std::shared_ptr< const sdf::Element > &_sdf, ignition::gazebo::EntityComponentManager &_ecm, ignition::gazebo::EventManager &_eventMgr) override
 Configure the system. More...
 
void PreUpdate (const ignition::gazebo::UpdateInfo &_info, ignition::gazebo::EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()=default
 Constructor. More...
 
virtual ~System ()=default
 Destructor. More...
 

Detailed Description

This plugin is a port of the old ModelPropShop plugin from gazebo classic. It generates 5 pictures of a model: perspective, top, front, side and back. It can do it using the default position or moving the joint to random positions. It allows saving the camera and joint poses so it can be replicated in other systems.

System Parameters

  • <translation_data_file> - Location to save the camera and joint poses. [Optional]
  • <random_joints_pose> - Set to true to take pictures with the joints in random poses instead of the default ones. This option only supports single axis joints. [Optional]
  • A camera sensor must be set in the SDF file as it will be used by the plugin to take the pictures. This allows the plugin user to set the camera parameters as needed. [Required]

Example

An example configuration is installed with Gazebo. The example uses the Ogre2 rendering plugin to set the background color of the pictures. It also includes the camera sensor that will be used along with the corresponding parameters so they can be easily tunned.

To run the example:

ign gazebo model_photo_shoot.sdf -s -r --iterations 50

This will start gazebo, load the model take the pictures and shutdown after 50 iterations. You will find the pictures in the same location you run the command.

System that takes snapshots of an sdf model

Constructor & Destructor Documentation

◆ ModelPhotoShoot()

Constructor.

◆ ~ModelPhotoShoot()

~ModelPhotoShoot ( )
overridedefault

Destructor.

Member Function Documentation

◆ Configure()

void Configure ( const ignition::gazebo::Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
ignition::gazebo::EntityComponentManager _ecm,
ignition::gazebo::EventManager _eventMgr 
)
overridevirtual

Configure the system.

Parameters
[in]_entityThe entity this plugin is attached to.
[in]_sdfThe SDF Element associated with this system plugin.
[in]_ecmThe EntityComponentManager of the given simulation instance.
[in]_eventMgrThe EventManager of the given simulation instance.

Implements ISystemConfigure.

◆ PreUpdate()

void PreUpdate ( const ignition::gazebo::UpdateInfo _info,
ignition::gazebo::EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


The documentation for this class was generated from the following file: