Root class that acts as an entry point to the SDF document model. More...
#include <Root.hh>
Public Member Functions | |
Root () | |
Default constructor. More... | |
const sdf::Actor * | Actor () const |
Get a pointer to the actor object if it exists. More... | |
Errors | AddWorld (const World &_world) |
Add a world to the root. More... | |
void | ClearWorlds () |
Remove all worlds. More... | |
sdf::Root | Clone () const |
Deep copy this Root object and return the new Root object. More... | |
sdf::ElementPtr | Element () const |
Get a pointer to the SDF element that was generated during load. More... | |
const sdf::Light * | Light () const |
Get a pointer to the light object if it exists. More... | |
Errors | Load (const SDFPtr _sdf) |
Parse the given SDF pointer, and generate objects based on types specified in the SDF file. More... | |
Errors | Load (const SDFPtr _sdf, const ParserConfig &_config) |
Parse the given SDF pointer, and generate objects based on types specified in the SDF file. More... | |
Errors | Load (const std::string &_filename) |
Parse the given SDF file, and generate objects based on types specified in the SDF file. More... | |
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. More... | |
Errors | LoadSdfString (const std::string &_sdf) |
Parse the given SDF string, and generate objects based on types specified in the SDF file. More... | |
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. More... | |
const sdf::Model * | Model () const |
Get a pointer to the model object if it exists. More... | |
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. More... | |
void | SetActor (const sdf::Actor &_actor) |
Set the actor object. More... | |
void | SetLight (const sdf::Light &_light) |
Set the light object. More... | |
void | SetModel (const sdf::Model &_model) |
Set the model object. More... | |
void | SetVersion (const std::string &_version) |
Set the SDF version string. More... | |
sdf::ElementPtr | ToElement (const OutputConfig &_config=OutputConfig::GlobalConfig()) const |
Create and return an SDF element filled with data from this root. More... | |
Errors | UpdateGraphs () |
Recreate the frame and pose graphs for the worlds and model that are children of this Root object. More... | |
std::string | Version () const |
Get the SDF version specified in the parsed file or SDF pointer. More... | |
World * | WorldByIndex (const uint64_t _index) |
Get a mutable world based on an index. More... | |
const World * | WorldByIndex (const uint64_t _index) const |
Get a world based on an index. More... | |
World * | WorldByName (const std::string &_name) |
Get a world based on a name. More... | |
const World * | WorldByName (const std::string &_name) const |
Get a world based on a name. More... | |
uint64_t | WorldCount () const |
Get the number of worlds. More... | |
bool | WorldNameExists (const std::string &_name) const |
Get whether a world name exists. More... | |
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. More... | |
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.
In this example, a root object is loaded from a file specified in the first command line argument to a program.
sdf::SDF_VERSION_NAMESPACE::Root::Root | ( | ) |
Default constructor.
const sdf::Actor* sdf::SDF_VERSION_NAMESPACE::Root::Actor | ( | ) | const |
Get a pointer to the actor object if it exists.
void sdf::SDF_VERSION_NAMESPACE::Root::ClearWorlds | ( | ) |
Remove all worlds.
sdf::Root sdf::SDF_VERSION_NAMESPACE::Root::Clone | ( | ) | const |
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Root::Element | ( | ) | const |
const sdf::Light* sdf::SDF_VERSION_NAMESPACE::Root::Light | ( | ) | const |
Get a pointer to the light object if it exists.
Errors sdf::SDF_VERSION_NAMESPACE::Root::Load | ( | const SDFPtr | _sdf, |
const ParserConfig & | _config | ||
) |
Errors sdf::SDF_VERSION_NAMESPACE::Root::Load | ( | const std::string & | _filename | ) |
Errors sdf::SDF_VERSION_NAMESPACE::Root::Load | ( | const std::string & | _filename, |
const ParserConfig & | _config | ||
) |
Errors sdf::SDF_VERSION_NAMESPACE::Root::LoadSdfString | ( | const std::string & | _sdf | ) |
Errors sdf::SDF_VERSION_NAMESPACE::Root::LoadSdfString | ( | const std::string & | _sdf, |
const ParserConfig & | _config | ||
) |
const sdf::Model* sdf::SDF_VERSION_NAMESPACE::Root::Model | ( | ) | const |
Get a pointer to the model object if it exists.
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
[out] | _errors | A vector of Errors objects. Each errors contains an Error code and a message. An empty errors vector indicates no errors |
[in] | _config | Custom parser configuration |
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.
[in] | _actor | The actor to use. |
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.
[in] | _light | The light to use. |
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.
[in] | _model | The model to use. |
void sdf::SDF_VERSION_NAMESPACE::Root::SetVersion | ( | const std::string & | _version | ) |
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Root::ToElement | ( | const OutputConfig & | _config = OutputConfig::GlobalConfig() | ) | const |
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.
std::string sdf::SDF_VERSION_NAMESPACE::Root::Version | ( | ) | const |
Get the SDF version specified in the parsed file or SDF pointer.
World* sdf::SDF_VERSION_NAMESPACE::Root::WorldByIndex | ( | const uint64_t | _index | ) |
Get a mutable world based on an index.
[in] | _index | Index of the world. The index should be in the range [0..WorldCount()). |
const World* sdf::SDF_VERSION_NAMESPACE::Root::WorldByIndex | ( | const uint64_t | _index | ) | const |
Get a world based on an index.
[in] | _index | Index of the world. The index should be in the range [0..WorldCount()). |
World* sdf::SDF_VERSION_NAMESPACE::Root::WorldByName | ( | const std::string & | _name | ) |
Get a world based on a name.
[in] | _name | Name of the world. |
const World* sdf::SDF_VERSION_NAMESPACE::Root::WorldByName | ( | const std::string & | _name | ) | const |
Get a world based on a name.
[in] | _name | Name of the world. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Root::WorldCount | ( | ) | const |
Get the number of worlds.
bool sdf::SDF_VERSION_NAMESPACE::Root::WorldNameExists | ( | const std::string & | _name | ) | const |
Get whether a world name exists.
[in] | _name | Name of the world to check. |
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.
[in] | _filename | Name of the SDF file to parse. |
[out] | _worldNames | A vector with world names |