The main namespace for STDR GUI XML parser. More...
Classes | |
struct | ElSpecs |
An element of Specs - represents a valid tag. More... | |
class | MessageCreator |
Creates STDR messages from a STDR tree. More... | |
class | Node |
Implements the main functionalities of the stdr parser tree. More... | |
class | Parser |
Implements the main functionalities of the high-level parser. More... | |
class | ParserException |
Provides a parser exception. Publicly inherits from std::runtime_error. Used in robot handler. More... | |
struct | Specs |
The STDR parser specifications. More... | |
class | Validator |
class | XmlFileWriter |
class | XmlParser |
class | YamlFileWriter |
class | YamlParser |
Functions | |
std::set< std::string > | explodeString (std::string s, char delimiter) |
Explodes a string based on a delimiter. | |
std::string | extractDirname (std::string s) |
Extracts the directory from an absolute path. It does the same functionality as libgen's dirname but for std::string objects. | |
std::string | extractFilename (std::string s) |
Extracts the filename from an absolute path. | |
template<class T > | |
YAML::Emitter & | operator<< (YAML::Emitter &out, const T &msg) |
Creates a yaml node from a msg - template member function. | |
template<> | |
YAML::Emitter & | operator<< < geometry_msgs::Pose2D > (YAML::Emitter &out, const geometry_msgs::Pose2D &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::CO2SensorMsg > (YAML::Emitter &out, const stdr_msgs::CO2SensorMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::FootprintMsg > (YAML::Emitter &out, const stdr_msgs::FootprintMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::KinematicMsg > (YAML::Emitter &out, const stdr_msgs::KinematicMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::LaserSensorMsg > (YAML::Emitter &out, const stdr_msgs::LaserSensorMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::Noise > (YAML::Emitter &out, const stdr_msgs::Noise &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::RfidSensorMsg > (YAML::Emitter &out, const stdr_msgs::RfidSensorMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::RobotMsg > (YAML::Emitter &out, const stdr_msgs::RobotMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::SonarSensorMsg > (YAML::Emitter &out, const stdr_msgs::SonarSensorMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::SoundSensorMsg > (YAML::Emitter &out, const stdr_msgs::SoundSensorMsg &msg) |
template<> | |
YAML::Emitter & | operator<< < stdr_msgs::ThermalSensorMsg > (YAML::Emitter &out, const stdr_msgs::ThermalSensorMsg &msg) |
template<> | |
void | XmlFileWriter::messageToXmlElement< geometry_msgs::Pose2D > (geometry_msgs::Pose2D msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::CO2SensorMsg > (stdr_msgs::CO2SensorMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::FootprintMsg > (stdr_msgs::FootprintMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::KinematicMsg > (stdr_msgs::KinematicMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::LaserSensorMsg > (stdr_msgs::LaserSensorMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::Noise > (stdr_msgs::Noise msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::RfidSensorMsg > (stdr_msgs::RfidSensorMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::RobotMsg > (stdr_msgs::RobotMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::SonarSensorMsg > (stdr_msgs::SonarSensorMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::SoundSensorMsg > (stdr_msgs::SoundSensorMsg msg, TiXmlNode *base) |
template<> | |
void | XmlFileWriter::messageToXmlElement< stdr_msgs::ThermalSensorMsg > (stdr_msgs::ThermalSensorMsg msg, TiXmlNode *base) |
The main namespace for STDR GUI XML parser.
The main namespace for STDR parser.
std::set< std::string > stdr_parser::explodeString | ( | std::string | s, |
char | delimiter | ||
) |
Explodes a string based on a delimiter.
s | [std::string] The input string |
delimiter | [char] The delimiter |
Definition at line 32 of file stdr_parser_tools.cpp.
std::string stdr_parser::extractDirname | ( | std::string | s | ) |
Extracts the directory from an absolute path. It does the same functionality as libgen's dirname but for std::string objects.
s | [std::string] The input string |
Definition at line 64 of file stdr_parser_tools.cpp.
std::string stdr_parser::extractFilename | ( | std::string | s | ) |
Extracts the filename from an absolute path.
s | [std::string] The input string |
Definition at line 52 of file stdr_parser_tools.cpp.
YAML::Emitter& stdr_parser::operator<< | ( | YAML::Emitter & | out, |
const T & | msg | ||
) |
Creates a yaml node from a msg - template member function.
msg | [T] The message |
base | [YAML::Emitter*] The yaml emitter to write the message |
YAML::Emitter& stdr_parser::operator<< < geometry_msgs::Pose2D > | ( | YAML::Emitter & | out, |
const geometry_msgs::Pose2D & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::KinematicMsg
Definition at line 108 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::CO2SensorMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::CO2SensorMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::ThermalSensorMsg
Definition at line 300 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::FootprintMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::FootprintMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for geometry_msgs::Pose2D
Definition at line 69 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::KinematicMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::KinematicMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::LaserSensorMsg
Definition at line 130 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::LaserSensorMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::LaserSensorMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::SonarSensorMsg
Definition at line 171 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::Noise > | ( | YAML::Emitter & | out, |
const stdr_msgs::Noise & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::FootprintMsg
Definition at line 44 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::RfidSensorMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::RfidSensorMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::CO2SensorMsg
Definition at line 266 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::RobotMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::RobotMsg & | msg | ||
) |
----------------------------------------------------------------
Definition at line 401 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::SonarSensorMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::SonarSensorMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::RfidSensorMsg
Definition at line 220 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::SoundSensorMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::SoundSensorMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::RobotMsg
Definition at line 367 of file stdr_parser_yaml_file_writer.cpp.
YAML::Emitter& stdr_parser::operator<< < stdr_msgs::ThermalSensorMsg > | ( | YAML::Emitter & | out, |
const stdr_msgs::ThermalSensorMsg & | msg | ||
) |
---------------------------------------------------------------- Template declaration for stdr_msgs::SoundSensorMsg
Definition at line 334 of file stdr_parser_yaml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< geometry_msgs::Pose2D > | ( | geometry_msgs::Pose2D | msg, |
TiXmlNode * | base | ||
) |
------------------------------------------------------------------ Template specialization for geometry_msgs::Pose2D
< Create pose
< Create x
< Create y
< Create theta
Definition at line 128 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::CO2SensorMsg > | ( | stdr_msgs::CO2SensorMsg | msg, |
TiXmlNode * | base | ||
) |
< Create sensor
< Create sensor specifications
< Create max_range
< Create angleSpan
< Create signalCutoff
< Create frequency
< Create frame id
< Create pose
Definition at line 340 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::FootprintMsg > | ( | stdr_msgs::FootprintMsg | msg, |
TiXmlNode * | base | ||
) |
< Create noise
< Create footprint specifications
< Create footprint radius
< Create footprint radius
Definition at line 81 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::KinematicMsg > | ( | stdr_msgs::KinematicMsg | msg, |
TiXmlNode * | base | ||
) |
< Create kinematic
< Create kinematic specifications
< Create kinematic model
< Create kinematic parameters
Definition at line 497 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::LaserSensorMsg > | ( | stdr_msgs::LaserSensorMsg | msg, |
TiXmlNode * | base | ||
) |
< Create laser
< Create laser specifications
< Create max_angle
< Create min_angle
< Create max_range
< Create min_range
< Create num rays
< Create frequency
< Create frame id
< Create pose
< Create noise
Definition at line 164 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::Noise > | ( | stdr_msgs::Noise | msg, |
TiXmlNode * | base | ||
) |
< Create noise
< Create noise specifications
< Create noise mean
< Create noise std
Definition at line 44 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::RfidSensorMsg > | ( | stdr_msgs::RfidSensorMsg | msg, |
TiXmlNode * | base | ||
) |
< Create rfid reader
< Create rfid reader specifications
< Create max_range
< Create angleSpan
< Create signalCutoff
< Create frequency
< Create frame id
< Create pose
Definition at line 288 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::RobotMsg > | ( | stdr_msgs::RobotMsg | msg, |
TiXmlNode * | base | ||
) |
-----------------------------------------------------------------
< Create robot
< Create robot specifications
< Create initial pose
< Create x
< Create y
< Create theta
< Create footprint
Create Kinematic model
< Create lasers
Definition at line 591 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::SonarSensorMsg > | ( | stdr_msgs::SonarSensorMsg | msg, |
TiXmlNode * | base | ||
) |
< Create sonar
< Create sonar specifications
< Create cone_angle
< Create max_range
< Create min_range
< Create frequency
< Create frame id
< Create pose
< Create noise
Definition at line 232 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::SoundSensorMsg > | ( | stdr_msgs::SoundSensorMsg | msg, |
TiXmlNode * | base | ||
) |
< Create sensor
< Create sensor specifications
< Create max_range
< Create angleSpan
< Create signalCutoff
< Create frequency
< Create frame id
< Create pose
Definition at line 444 of file stdr_parser_xml_file_writer.cpp.
void stdr_parser::XmlFileWriter::messageToXmlElement< stdr_msgs::ThermalSensorMsg > | ( | stdr_msgs::ThermalSensorMsg | msg, |
TiXmlNode * | base | ||
) |
< Create sensor
< Create sensor specifications
< Create max_range
< Create angleSpan
< Create signalCutoff
< Create frequency
< Create frame id
< Create pose
Definition at line 392 of file stdr_parser_xml_file_writer.cpp.