Open 3D Engine ROS2 Gem API Reference 23.10.0
O3DE is an open-source, fully-featured, high-fidelity, modular 3D engine for building games and simulations, available to every industry.
ROS2::UrdfParser::ParseResult Struct Reference

Functions for parsing URDF/SDF data. More...

#include <UrdfParser.h>

Public Member Functions

sdf::Root & GetRoot () &
 
const sdf::Root & GetRoot () const &
 
sdf::Root && GetRoot () &&
 
const AZStd::string & GetParseMessages () const &
 
AZStd::string && GetParseMessages () &&
 
const sdf::Errors & GetSdfErrors () const &
 
sdf::Errors && GetSdfErrors () &&
 
 operator bool () const
 
bool UrdfParsedWithModifiedContent () const
 Returns if the URDF content was modified during parsing.
 

Public Attributes

sdf::Root m_root
 Root SDF object containing parsed SDF XML content if successful.
 
AZStd::string m_parseMessages
 
sdf::Errors m_sdfErrors { sdf::Error{ O3DESdfErrorParseNotStarted, std::string{ "No Parsing has occurred yet" } } }
 
std::string m_modifiedURDFContent
 Stores the modified URDF content after parsing, empty if no modification occurred.
 
Utils::UrdfModifications m_urdfModifications
 Stores description of URDF modifications, empty if no modification occurred.
 

Static Public Attributes

static constexpr auto O3DESdfErrorParseNotStarted = static_cast<sdf::ErrorCode>(static_cast<int>(O3DESdfErrorCodeStart) + 1)
 

Detailed Description

Functions for parsing URDF/SDF data.

Stores the result of parsing URDF/SDF data The operator bool returns true if the sdf::Errors vector is empty

Member Function Documentation

◆ GetParseMessages()

const AZStd::string & ROS2::UrdfParser::ParseResult::GetParseMessages ( ) const &

Property getters for retrieving parsing messages logged during libsdformat parsing of the URDF content This does not support a non-const lvalue overload As modification the result structure parser messages have no need to be modified inplace

◆ GetRoot()

sdf::Root & ROS2::UrdfParser::ParseResult::GetRoot ( ) &

Ref qualifier overloads for retrieving sdf::Root it supports a non-const lvalue overload to allow modification of the sdf::Root object directly

◆ GetSdfErrors()

const sdf::Errors & ROS2::UrdfParser::ParseResult::GetSdfErrors ( ) const &

Returns the sdf::Error vector containing any parser errors This does not support a non-const lvalue overload As modification the result structure sdf Errors have no need to be modified inplace

◆ operator bool()

ROS2::UrdfParser::ParseResult::operator bool ( ) const
explicit

Returns if the parsing of the SDF file has succeeded This will return false if the sdf::Errors vector is non-empty

Member Data Documentation

◆ m_parseMessages

AZStd::string ROS2::UrdfParser::ParseResult::m_parseMessages

Contains any messages that are output to the sdf::Console during parsing These messages are captured and provided to the caller to allow outputting in any manner they choose

◆ m_sdfErrors

sdf::Errors ROS2::UrdfParser::ParseResult::m_sdfErrors { sdf::Error{ O3DESdfErrorParseNotStarted, std::string{ "No Parsing has occurred yet" } } }

Vector structure populated with sdf::Error objects indicating that parsing of the .sdf/.urdf file has failed with an error


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