Loading...
Searching...
No Matches
Public Member Functions | List of all members
sdf::SDF_VERSION_NAMESPACE::Root Class Reference

Root class that acts as an entry point to the SDF document model. More...

#include <Root.hh>

Public Member Functions

 Root ()
 Default constructor.
 
const sdf::ActorActor () const
 Get a pointer to the actor object if it exists.
 
Errors AddWorld (const World &_world)
 Add a world to the root.
 
void ClearActorLightModel ()
 Remove the actor, light, or model if one of them exists.
 
void ClearWorlds ()
 Remove all worlds.
 
sdf::Root Clone () const
 Deep copy this Root object and return the new Root object.
 
sdf::ElementPtr Element () const
 Get a pointer to the SDF element that was generated during load.
 
const sdf::LightLight () const
 Get a pointer to the light object if it exists.
 
Errors Load (const SDFPtr _sdf)
 Parse the given SDF pointer, and generate objects based on types specified in the SDF file.
 
Errors Load (const SDFPtr _sdf, const ParserConfig &_config)
 Parse the given SDF pointer, and generate objects based on types specified in the SDF file.
 
Errors Load (const std::string &_filename)
 Parse the given SDF file, and generate objects based on types specified in the SDF file.
 
Errors Load (const std::string &_filename, const ParserConfig &_config)
 Parse the given SDF file, and generate objects based on types specified in the SDF file.
 
Errors LoadSdfString (const std::string &_sdf)
 Parse the given SDF string, and generate objects based on types specified in the SDF file.
 
Errors LoadSdfString (const std::string &_sdf, const ParserConfig &_config)
 Parse the given SDF string, and generate objects based on types specified in the SDF file.
 
const sdf::ModelModel () const
 Get a pointer to the model object if it exists.
 
void ResolveAutoInertials (sdf::Errors &_errors, const ParserConfig &_config)
 Calculate & set the inertial properties (mass, mass matrix and inertial pose) for all the worlds & models that are children of this Root object.
 
void SetActor (const sdf::Actor &_actor)
 Set the actor object.
 
void SetLight (const sdf::Light &_light)
 Set the light object.
 
void SetModel (const sdf::Model &_model)
 Set the model object.
 
void SetVersion (const std::string &_version)
 Set the SDF version string.
 
sdf::ElementPtr ToElement (const OutputConfig &_config=OutputConfig::GlobalConfig()) const
 Create and return an SDF element filled with data from this root.
 
Errors UpdateGraphs ()
 Recreate the frame and pose graphs for the worlds and model that are children of this Root object.
 
std::string Version () const
 Get the SDF version specified in the parsed file or SDF pointer.
 
WorldWorldByIndex (const uint64_t _index)
 Get a mutable world based on an index.
 
const WorldWorldByIndex (const uint64_t _index) const
 Get a world based on an index.
 
WorldWorldByName (const std::string &_name)
 Get a world based on a name.
 
const WorldWorldByName (const std::string &_name) const
 Get a world based on a name.
 
uint64_t WorldCount () const
 Get the number of worlds.
 
bool WorldNameExists (const std::string &_name) const
 Get whether a world name exists.
 
Errors WorldNamesFromFile (const std::string &_filename, std::vector< std::string > &_worldNames)
 Get the name of the world without loading the entire world Users shouldn't normally need to use this API.
 

Detailed Description

Root class that acts as an entry point to the SDF document model.

Multiple worlds can exist in a single SDF file. A user of multiple worlds could run parallel instances of simulation, or offer selection of a world at runtime.

Usage

In this example, a root object is loaded from a file specified in the first command line argument to a program.

sdf::Root root;
sdf::Errors errors = root.Load(argv[1]);
if (errors.empty())
{
std::cerr << "Valid SDF file.\n";
return 0;
}
else
{
std::cerr << "Errors encountered: \n";
for (auto const &e : errors)
{
std::cout << e << std::endl;
}
}
Root class that acts as an entry point to the SDF document model.
Definition Root.hh:58
Errors Load(const std::string &_filename)
Parse the given SDF file, and generate objects based on types specified in the SDF file.
std::vector< Error > Errors
A vector of Error.
Definition Types.hh:81

Constructor & Destructor Documentation

◆ Root()

sdf::SDF_VERSION_NAMESPACE::Root::Root ( )

Default constructor.

Member Function Documentation

◆ Actor()

const sdf::Actor * sdf::SDF_VERSION_NAMESPACE::Root::Actor ( ) const

Get a pointer to the actor object if it exists.

Returns
A pointer to the actor, nullptr if it doesn't exist

◆ AddWorld()

Errors sdf::SDF_VERSION_NAMESPACE::Root::AddWorld ( const World _world)

Add a world to the root.

Parameters
[in]_wordWorld to add.
Returns
True if successful, false if a world with the name already exists.
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ ClearActorLightModel()

void sdf::SDF_VERSION_NAMESPACE::Root::ClearActorLightModel ( )

Remove the actor, light, or model if one of them exists.

The SDF Root object can only hold one, or none, from the set [Actor, Light, Model].

◆ ClearWorlds()

void sdf::SDF_VERSION_NAMESPACE::Root::ClearWorlds ( )

Remove all worlds.

◆ Clone()

sdf::Root sdf::SDF_VERSION_NAMESPACE::Root::Clone ( ) const

Deep copy this Root object and return the new Root object.

Returns
A clone of this Root object. Deprecate this function in SDF version 13, and use GZ_UTILS_IMPL_PTR instead.

◆ Element()

sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Root::Element ( ) const

Get a pointer to the SDF element that was generated during load.

Returns
SDF element pointer. The value will be nullptr if Load has not been called.

◆ Light()

const sdf::Light * sdf::SDF_VERSION_NAMESPACE::Root::Light ( ) const

Get a pointer to the light object if it exists.

Returns
A pointer to the light, nullptr if it doesn't exist

◆ Load() [1/4]

Errors sdf::SDF_VERSION_NAMESPACE::Root::Load ( const SDFPtr  _sdf)

Parse the given SDF pointer, and generate objects based on types specified in the SDF file.

Parameters
[in]_sdfSDF pointer to parse.
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Load() [2/4]

Errors sdf::SDF_VERSION_NAMESPACE::Root::Load ( const SDFPtr  _sdf,
const ParserConfig _config 
)

Parse the given SDF pointer, and generate objects based on types specified in the SDF file.

Parameters
[in]_sdfSDF pointer to parse.
[in]_configCustom parser configuration
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Load() [3/4]

Errors sdf::SDF_VERSION_NAMESPACE::Root::Load ( const std::string &  _filename)

Parse the given SDF file, and generate objects based on types specified in the SDF file.

Parameters
[in]_filenameName of the SDF file to parse.
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Load() [4/4]

Errors sdf::SDF_VERSION_NAMESPACE::Root::Load ( const std::string &  _filename,
const ParserConfig _config 
)

Parse the given SDF file, and generate objects based on types specified in the SDF file.

Parameters
[in]_filenameName of the SDF file to parse.
[in]_configCustom parser configuration
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ LoadSdfString() [1/2]

Errors sdf::SDF_VERSION_NAMESPACE::Root::LoadSdfString ( const std::string &  _sdf)

Parse the given SDF string, and generate objects based on types specified in the SDF file.

Parameters
[in]_sdfSDF string to parse.
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ LoadSdfString() [2/2]

Errors sdf::SDF_VERSION_NAMESPACE::Root::LoadSdfString ( const std::string &  _sdf,
const ParserConfig _config 
)

Parse the given SDF string, and generate objects based on types specified in the SDF file.

Parameters
[in]_sdfSDF string to parse.
[in]_configCustom parser configuration
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Model()

const sdf::Model * sdf::SDF_VERSION_NAMESPACE::Root::Model ( ) const

Get a pointer to the model object if it exists.

Returns
A pointer to the model, nullptr if it doesn't exist

◆ ResolveAutoInertials()

void sdf::SDF_VERSION_NAMESPACE::Root::ResolveAutoInertials ( sdf::Errors _errors,
const ParserConfig _config 
)

Calculate & set the inertial properties (mass, mass matrix and inertial pose) for all the worlds & models that are children of this Root object.

This function must be called after calling Root::Load() or UpdateGraphs() since it uses frame graphs to resolve inertial pose for links and they would be automatically built

Parameters
[out]_errorsA vector of Errors objects. Each errors contains an Error code and a message. An empty errors vector indicates no errors
[in]_configCustom parser configuration

◆ SetActor()

void sdf::SDF_VERSION_NAMESPACE::Root::SetActor ( const sdf::Actor _actor)

Set the actor object.

This will override any existing model, actor, and light object.

Parameters
[in]_actorThe actor to use.

◆ SetLight()

void sdf::SDF_VERSION_NAMESPACE::Root::SetLight ( const sdf::Light _light)

Set the light object.

This will override any existing model, actor, and light object.

Parameters
[in]_lightThe light to use.

◆ SetModel()

void sdf::SDF_VERSION_NAMESPACE::Root::SetModel ( const sdf::Model _model)

Set the model object.

This will override any existing model, actor, and light object.

Parameters
[in]_modelThe model to use.

◆ SetVersion()

void sdf::SDF_VERSION_NAMESPACE::Root::SetVersion ( const std::string &  _version)

Set the SDF version string.

Parameters
[in]_versionThe new SDF version.
See also
std::string Version()

◆ ToElement()

sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Root::ToElement ( const OutputConfig _config = OutputConfig::GlobalConfig()) const

Create and return an SDF element filled with data from this root.

Note that parameter passing functionality is not captured with this function.

Parameters
[in]_configCustom output configuration
Returns
SDF element pointer with updated root values.

◆ UpdateGraphs()

Errors sdf::SDF_VERSION_NAMESPACE::Root::UpdateGraphs ( )

Recreate the frame and pose graphs for the worlds and model that are children of this Root object.

You can call this function to build new graphs when the DOM was created programmatically, or if you want to regenerate the graphs after editing the DOM.

Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Version()

std::string sdf::SDF_VERSION_NAMESPACE::Root::Version ( ) const

Get the SDF version specified in the parsed file or SDF pointer.

Returns
SDF version string.
See also
void SetVersion(const std::string &_version)

◆ WorldByIndex() [1/2]

World * sdf::SDF_VERSION_NAMESPACE::Root::WorldByIndex ( const uint64_t  _index)

Get a mutable world based on an index.

Parameters
[in]_indexIndex of the world. The index should be in the range [0..WorldCount()).
Returns
Pointer to the world. Nullptr if the index does not exist.
See also
uint64_t WorldCount() const

◆ WorldByIndex() [2/2]

const World * sdf::SDF_VERSION_NAMESPACE::Root::WorldByIndex ( const uint64_t  _index) const

Get a world based on an index.

Parameters
[in]_indexIndex of the world. The index should be in the range [0..WorldCount()).
Returns
Pointer to the world. Nullptr if the index does not exist.
See also
uint64_t WorldCount() const

◆ WorldByName() [1/2]

World * sdf::SDF_VERSION_NAMESPACE::Root::WorldByName ( const std::string &  _name)

Get a world based on a name.

Parameters
[in]_nameName of the world.
Returns
Pointer to the world. Nullptr if a world with the given name does not exist.
See also
bool WorldNameExists(const std::string &_name) const

◆ WorldByName() [2/2]

const World * sdf::SDF_VERSION_NAMESPACE::Root::WorldByName ( const std::string &  _name) const

Get a world based on a name.

Parameters
[in]_nameName of the world.
Returns
Pointer to the world. Nullptr if a world with the given name does not exist.
See also
bool WorldNameExists(const std::string &_name) const

◆ WorldCount()

uint64_t sdf::SDF_VERSION_NAMESPACE::Root::WorldCount ( ) const

Get the number of worlds.

Returns
Number of worlds contained in this Root object.

◆ WorldNameExists()

bool sdf::SDF_VERSION_NAMESPACE::Root::WorldNameExists ( const std::string &  _name) const

Get whether a world name exists.

Parameters
[in]_nameName of the world to check.
Returns
True if there exists a world with the given name.

◆ WorldNamesFromFile()

Errors sdf::SDF_VERSION_NAMESPACE::Root::WorldNamesFromFile ( const std::string &  _filename,
std::vector< std::string > &  _worldNames 
)

Get the name of the world without loading the entire world Users shouldn't normally need to use this API.

This doesn't load the world, it might return the world name even if the file is not a valid SDFormat file.

Parameters
[in]_filenameName of the SDF file to parse.
[out]_worldNamesA vector with world names
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

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