Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
tesseract_common Namespace Reference

Namespaces

 serialization
 

Classes

class  ACMContactAllowedValidator
 
class  AllowedCollisionMatrix
 
struct  ambiguate
 
class  AnyInterface
 
class  AnyPoly
 
class  AnyWrapper
 
class  BytesResource
 
struct  CalibrationInfo
 The CalibrationInfo struct. More...
 
class  CloneCache
 Used to create a cache of objects. More...
 
class  CollisionMarginData
 Stores information about how the margins allowed between collision objects. More...
 
class  CollisionMarginPairData
 
class  CombinedContactAllowedValidator
 
class  ContactAllowedValidator
 Should return true if links are allowed to be in collision, otherwise false. More...
 
struct  ContactManagersPluginInfo
 The contact managers plugin information structure. More...
 
class  GeneralResourceLocator
 A general resource loaders using environment variable. More...
 
struct  got_type
 
struct  got_type< A >
 
struct  has_member
 
class  JointState
 
class  JointTrajectory
 Represents a joint trajectory. More...
 
struct  KinematicLimits
 Store kinematic limits. More...
 
struct  KinematicsPluginInfo
 The kinematics plugin information structure. More...
 
struct  ManipulatorInfo
 Contains information about a robot manipulator. More...
 
struct  PairHash
 
struct  PluginInfo
 The Plugin Information struct. More...
 
struct  PluginInfoContainer
 
class  Profile
 The Profile class. More...
 
class  ProfileDictionary
 This class is used to store profiles used by various tasks. More...
 
class  Resource
 Represents resource data available from a file or url. More...
 
class  ResourceLocator
 Abstract class for resource loaders. More...
 
struct  Serialization
 
struct  sig_check
 
class  SimpleLocatedResource
 Resource implementation for a local file. More...
 
class  Stopwatch
 A simple stopwatch class leveraging chrono high resolution clock. More...
 
struct  TaskComposerPluginInfo
 The task composer plugin information structure. More...
 
class  TestPluginBase
 
class  TestPluginMultiply
 
class  Timer
 A timer which calls a callback every interval on a separate thread. More...
 
struct  TypeErasureBase
 
struct  TypeErasureInstance
 
struct  TypeErasureInterface
 This is the interface that all type erasures interfaces must inherit from. More...
 

Typedefs

template<typename Key , typename Value >
using AlignedMap = std::map< Key, Value, std::less< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >>
 
template<typename Key , typename Value >
using AlignedUnorderedMap = std::unordered_map< Key, Value, std::hash< Key >, std::equal_to< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >>
 
template<typename T >
using AlignedVector = std::vector< T, Eigen::aligned_allocator< T > >
 
using AllowedCollisionEntries = std::unordered_map< tesseract_common::LinkNamesPair, std::string, tesseract_common::PairHash >
 
using BoolAnyPoly = AnyWrapper< bool >
 
using DoubleAnyPoly = AnyWrapper< double >
 
using FloatAnyPoly = AnyWrapper< float >
 
using IntAnyPoly = AnyWrapper< int >
 
using JointStateAnyPoly = AnyWrapper< JointState >
 
using JointStatePtrAnyPoly = AnyWrapper< std::shared_ptr< JointState > >
 
using LinkNamesPair = std::pair< std::string, std::string >
 
using ManipulatorInfoAnyPoly = AnyWrapper< ManipulatorInfo >
 
using PairsCollisionMarginData = std::unordered_map< tesseract_common::LinkNamesPair, double, tesseract_common::PairHash >
 
using PluginInfoMap = std::map< std::string, PluginInfo >
 A map of PluginInfo to user defined name. More...
 
using ProfileDictionaryPtrAnyPoly = tesseract_common::AnyWrapper< std::shared_ptr< ProfileDictionary > >
 
using SimpleResourceLocatorFn = std::function< std::string(const std::string &)>
 
using SizeTAnyPoly = AnyWrapper< std::size_t >
 
using StringAnyPoly = AnyWrapper< std::string >
 
using Toolpath = AlignedVector< VectorIsometry3d >
 
using TrajArray = Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor >
 
using TransformMap = AlignedMap< std::string, Eigen::Isometry3d >
 
using UMapStringBoolAnyPoly = AnyWrapper< std::unordered_map< std::string, bool > >
 
using UMapStringDoubleAnyPoly = AnyWrapper< std::unordered_map< std::string, double > >
 
using UMapStringFloatAnyPoly = AnyWrapper< std::unordered_map< std::string, float > >
 
using UMapStringIntAnyPoly = AnyWrapper< std::unordered_map< std::string, int > >
 
using UMapStringSizeTAnyPoly = AnyWrapper< std::unordered_map< std::string, std::size_t > >
 
using UMapStringStringAnyPoly = AnyWrapper< std::unordered_map< std::string, std::string > >
 
using UMapStringUnsignedAnyPoly = AnyWrapper< std::unordered_map< std::string, unsigned > >
 
using UnsignedAnyPoly = AnyWrapper< unsigned >
 
using VectorIsometry3d = AlignedVector< Eigen::Isometry3d >
 
using VectorVector2d = AlignedVector< Eigen::Vector2d >
 
using VectorVector3d = std::vector< Eigen::Vector3d >
 
using VectorVector4d = AlignedVector< Eigen::Vector4d >
 

Enumerations

enum  CollisionMarginPairOverrideType : std::uint8_t { CollisionMarginPairOverrideType::NONE, CollisionMarginPairOverrideType::REPLACE, CollisionMarginPairOverrideType::MODIFY }
 Identifies how the provided contact margin data should be applied. More...
 
enum  CombinedContactAllowedValidatorType : std::uint8_t { CombinedContactAllowedValidatorType::AND, CombinedContactAllowedValidatorType::OR }
 Identify how the two should be combined. More...
 

Functions

bool almostEqualRelativeAndAbs (const Eigen::Ref< const Eigen::VectorXd > &v1, const Eigen::Ref< const Eigen::VectorXd > &v2, const Eigen::Ref< const Eigen::VectorXd > &max_diff, const Eigen::Ref< const Eigen::VectorXd > &max_rel_diff)
 Check if two Eigen VectorXd are relatively and absolute equal. More...
 
bool almostEqualRelativeAndAbs (const Eigen::Ref< const Eigen::VectorXd > &v1, const Eigen::Ref< const Eigen::VectorXd > &v2, double max_diff=1e-6, double max_rel_diff=std::numeric_limits< double >::epsilon())
 Check if two Eigen VectorXd are relatively and absolute equal. More...
 
bool almostEqualRelativeAndAbs (double a, double b, double max_diff=1e-6, double max_rel_diff=std::numeric_limits< double >::epsilon())
 Check if two double are relatively equal. More...
 
Eigen::VectorXd calcJacobianTransformErrorDiff (const Eigen::Isometry3d &target, const Eigen::Isometry3d &source, const Eigen::Isometry3d &source_perturbed)
 Calculate jacobian transform error difference expressed in the target frame coordinate system. More...
 
Eigen::VectorXd calcJacobianTransformErrorDiff (const Eigen::Isometry3d &target, const Eigen::Isometry3d &target_perturbed, const Eigen::Isometry3d &source, const Eigen::Isometry3d &source_perturbed)
 Calculate jacobian transform error difference expressed in the target frame coordinate system. More...
 
Eigen::Vector3d calcRotationalError (const Eigen::Ref< const Eigen::Matrix3d > &R)
 Calculate the rotation error vector given a rotation error matrix where the angle is between [-pi, pi]. More...
 
std::pair< Eigen::Vector3d, double > calcRotationalErrorDecomposed (const Eigen::Ref< const Eigen::Matrix3d > &R)
 
Eigen::VectorXd calcTransformError (const Eigen::Isometry3d &t1, const Eigen::Isometry3d &t2)
 Calculate error between two transforms expressed in t1 coordinate system. More...
 
void checkForUnknownKeys (const YAML::Node &node, const std::set< std::string > &expected_keys)
 Check node map for unknown keys. More...
 
bool compareYAML (const YAML::Node &node1, const YAML::Node &node2)
 Checks if the YAML::Nodes are identical. More...
 
Eigen::Vector4d computeRandomColor ()
 This computes a random color RGBA [0, 1] with alpha set to 1. More...
 
Eigen::VectorXd concat (const Eigen::VectorXd &a, const Eigen::VectorXd &b)
 Concatenate two vector. More...
 
template<typename FloatType >
void enforceLimits (Eigen::Ref< Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> values, const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &limits)
 Enforce values to be within the provided limits. More...
 
template void enforceLimits< double > (Eigen::Ref< Eigen::Matrix< double, Eigen::Dynamic, 1 >> values, const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &limits)
 
template void enforceLimits< float > (Eigen::Ref< Eigen::Matrix< float, Eigen::Dynamic, 1 >> values, const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &limits)
 
std::string fileToString (const std::filesystem::path &filepath)
 Read in the contents of the file into a string. More...
 
std::size_t findSeparator (const std::string &str)
 
YAML::Node fromYAMLString (const std::string &string)
 Converts yaml string to a YAML::Node. More...
 
Eigen::VectorXd generateRandomNumber (const Eigen::Ref< const Eigen::MatrixX2d > &limits)
 Given a set of limits it will generate a vector of random numbers between the limit. More...
 
std::vector< std::string > getAllowedCollisions (const std::vector< std::string > &link_names, const AllowedCollisionEntries &acm_entries, bool remove_duplicates=true)
 Gets allowed collisions for a set of link names. More...
 
std::string getTempPath ()
 Get the host temp directory path. More...
 
std::string getTimestampString ()
 Get Timestamp string. More...
 
template<typename T >
bool isIdentical (const std::vector< T > &vec1, const std::vector< T > &vec2, bool ordered=true, const std::function< bool(const T &, const T &)> &equal_pred=[](const T &v1, const T &v2) { return v1==v2;}, const std::function< bool(const T &, const T &)> &comp=[](const T &v1, const T &v2) { return v1< v2;})
 Check if two vector of strings are identical. More...
 
template bool isIdentical< Eigen::Index > (const std::vector< Eigen::Index > &, const std::vector< Eigen::Index > &, bool, const std::function< bool(const Eigen::Index &, const Eigen::Index &)> &, const std::function< bool(const Eigen::Index &, const Eigen::Index &)> &)
 
template bool isIdentical< std::string > (const std::vector< std::string > &, const std::vector< std::string > &, bool, const std::function< bool(const std::string &, const std::string &)> &, const std::function< bool(const std::string &, const std::string &)> &)
 
template<typename ValueType , std::size_t Size>
bool isIdenticalArray (const std::array< ValueType, Size > &array_1, const std::array< ValueType, Size > &array_2, const std::function< bool(const ValueType &, const ValueType &)> &value_eq=[](const ValueType &v1, const ValueType &v2) { return v1==v2;})
 Checks if 2 arrays are identical. More...
 
template<typename KeyValueContainerType , typename ValueType >
bool isIdenticalMap (const KeyValueContainerType &map_1, const KeyValueContainerType &map_2, const std::function< bool(const ValueType &, const ValueType &)> &value_eq=[](const ValueType &v1, const ValueType &v2) { return v1==v2;})
 Checks if 2 maps are identical. More...
 
template<typename ValueType >
bool isIdenticalSet (const std::set< ValueType > &set_1, const std::set< ValueType > &set_2, const std::function< bool(const ValueType &, const ValueType &)> &value_eq=[](const ValueType &v1, const ValueType &v2) { return v1==v2;})
 Checks if 2 sets are identical. More...
 
bool isNumeric (const std::string &s)
 Determine if a string is a number. More...
 
bool isNumeric (const std::vector< std::string > &sv)
 Determine if each string in vector is a number. More...
 
bool isRelativePath (const std::string &url)
 
template<typename FloatType >
bool isWithinLimits (const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &limits)
 Check if within limits. More...
 
template bool isWithinLimits< double > (const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &limits)
 
template bool isWithinLimits< float > (const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &limits)
 
void jacobianChangeBase (Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Isometry3d &change_base)
 Change the base coordinate system of the jacobian. More...
 
void jacobianChangeRefPoint (Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Ref< const Eigen::Vector3d > &ref_point)
 Change the reference point of the jacobian. More...
 
YAML::Node loadYamlFile (const std::string &file_path, const ResourceLocator &locator)
 Loads a YAML file and processes !include directives recursively. More...
 
YAML::Node loadYamlString (const std::string &yaml_string, const ResourceLocator &locator)
 
void ltrim (std::string &s)
 Left trim string. More...
 
LinkNamesPair makeOrderedLinkPair (const std::string &link_name1, const std::string &link_name2)
 Create a pair of strings, where the pair.first is always <= pair.second. More...
 
void makeOrderedLinkPair (LinkNamesPair &pair, const std::string &link_name1, const std::string &link_name2)
 Populate a pair of strings, where the pair.first is always <= pair.second. More...
 
template<typename E >
std::enable_if_t<!std::is_polymorphic< E >::value > my_rethrow_if_nested (const E &)
 
template<typename E >
std::enable_if_t< std::is_polymorphic< E >::value > my_rethrow_if_nested (const E &e)
 
bool operator!= (const ProfileDictionary &lhs, const ProfileDictionary &rhs)
 
std::ostream & operator<< (std::ostream &os, const AllowedCollisionMatrix &acm)
 
bool operator== (const AllowedCollisionEntries &entries_1, const AllowedCollisionEntries &entries_2)
 
bool operator== (const ProfileDictionary &lhs, const ProfileDictionary &rhs)
 
template<typename T >
bool pointersComparison (const std::shared_ptr< T > &p1, const std::shared_ptr< T > &p2)
 Comparison operator for the objects 2 points point to. More...
 
template<typename T >
bool pointersEqual (const std::shared_ptr< T > &p1, const std::shared_ptr< T > &p2)
 Checks if 2 pointers point to objects that are ==. More...
 
void printNestedException (const std::exception &e, int level=0)
 Print a nested exception. More...
 
YAML::Node processYamlIncludeDirective (const YAML::Node &node, const ResourceLocator &locator)
 Recursively processes a YAML node to resolve !include directives. More...
 
int QueryDoubleAttributeRequired (const tinyxml2::XMLElement *xml_element, const char *name, double &value)
 Query a double attribute from an xml element and print error log. More...
 
int QueryIntAttributeRequired (const tinyxml2::XMLElement *xml_element, const char *name, int &value)
 Query a int attribute from an xml element and print error log. More...
 
int QueryStringAttribute (const tinyxml2::XMLElement *xml_element, const char *name, std::string &value)
 Query a string attribute from an xml element. More...
 
int QueryStringAttributeRequired (const tinyxml2::XMLElement *xml_element, const char *name, std::string &value)
 Query a string attribute from an xml element and print error log. More...
 
int QueryStringText (const tinyxml2::XMLElement *xml_element, std::string &text)
 Query a string Text from xml element. More...
 
int QueryStringValue (const tinyxml2::XMLAttribute *xml_attribute, std::string &value)
 Query a string value from xml attribute. More...
 
int QueryStringValue (const tinyxml2::XMLElement *xml_element, std::string &value)
 Query a string value from xml element. More...
 
void reorder (Eigen::Ref< Eigen::VectorXd > v, std::vector< Eigen::Index > order)
 Reorder Eigen::VectorXd implace given index list. More...
 
void rtrim (std::string &s)
 Right trim string. More...
 
template<typename FloatType >
bool satisfiesLimits (const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &limits, const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &max_diff, const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &max_rel_diff)
 Check if values are within bounds or relatively equal to a limit. More...
 
template<typename FloatType >
bool satisfiesLimits (const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &limits, FloatType max_diff=static_cast< FloatType >(1e-6), FloatType max_rel_diff=std::numeric_limits< FloatType >::epsilon())
 Check if values is within bounds or relatively equal to a limit. More...
 
template bool satisfiesLimits< double > (const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &limits, const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &max_diff, const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &max_rel_diff)
 
template bool satisfiesLimits< double > (const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &limits, double max_diff, double max_rel_diff)
 
template bool satisfiesLimits< float > (const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &limits, const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &max_diff, const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &max_rel_diff)
 
template bool satisfiesLimits< float > (const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &values, const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &limits, float max_diff, float max_rel_diff)
 
template<typename... Args>
std::string strFormat (const std::string &format, Args... args)
 
std::string StringAttribute (const tinyxml2::XMLElement *xml_element, const char *name, std::string default_value)
 Get string attribute if exist. If it does not exist it returns the default value. More...
 
template<typename SerializableType >
void testSerialization (const SerializableType &object, const std::string &typename_string)
 Tests Boost serialization for a serializable type. More...
 
template<typename SerializableTypeStored >
void testSerializationAnyPolyStoredSharedPtr (const tesseract_common::AnyPoly &object, const std::string &typename_string)
 Tests Boost serialization for a serializable any poly type. More...
 
template<typename SerializableTypeBase , typename SerializableTypeDerived >
void testSerializationDerivedClass (const std::shared_ptr< SerializableTypeBase > &object, const std::string &typename_string)
 Tests Boost serialization for a serializable derived type. More...
 
template<typename SerializableType >
void testSerializationPtr (const std::shared_ptr< SerializableType > &object, const std::string &typename_string)
 Tests Boost serialization of shared pointer for a serializable type. More...
 
template<typename FloatType >
bool toNumeric (const std::string &s, FloatType &value)
 Convert a string to a numeric value type. More...
 
template bool toNumeric< double > (const std::string &, double &)
 
template bool toNumeric< float > (const std::string &, float &)
 
template bool toNumeric< int > (const std::string &, int &)
 
template bool toNumeric< long > (const std::string &, long &)
 
std::string toYAMLString (const YAML::Node &node)
 Converts a YAML::Node to a yaml string. More...
 
void trim (std::string &s)
 Trim left and right of string. More...
 
void twistChangeBase (Eigen::Ref< Eigen::VectorXd > twist, const Eigen::Isometry3d &change_base)
 Change the base coordinate system of the Twist. More...
 
void twistChangeRefPoint (Eigen::Ref< Eigen::VectorXd > twist, const Eigen::Ref< const Eigen::Vector3d > &ref_point)
 Change the reference point of the provided Twist. More...
 
void writeYamlToFile (const YAML::Node &node, const std::string &file_path)
 Writes a YAML::Node to a file. More...
 

Variables

static std::mt19937 mersenne { static_cast<std::mt19937::result_type>(std::time(nullptr)) }
 Random number generator. More...
 

Typedef Documentation

◆ AlignedMap

template<typename Key , typename Value >
using tesseract_common::AlignedMap = typedef std::map<Key, Value, std::less<Key>, Eigen::aligned_allocator<std::pair<const Key, Value> >>

Definition at line 19 of file eigen_types.h.

◆ AlignedUnorderedMap

template<typename Key , typename Value >
using tesseract_common::AlignedUnorderedMap = typedef std::unordered_map<Key, Value, std::hash<Key>, std::equal_to<Key>, Eigen::aligned_allocator<std::pair<const Key, Value> >>

Definition at line 26 of file eigen_types.h.

◆ AlignedVector

template<typename T >
using tesseract_common::AlignedVector = typedef std::vector<T, Eigen::aligned_allocator<T> >

Definition at line 16 of file eigen_types.h.

◆ AllowedCollisionEntries

Definition at line 24 of file allowed_collision_matrix.h.

◆ BoolAnyPoly

Definition at line 237 of file any_poly.h.

◆ DoubleAnyPoly

Definition at line 240 of file any_poly.h.

◆ FloatAnyPoly

Definition at line 241 of file any_poly.h.

◆ IntAnyPoly

Definition at line 238 of file any_poly.h.

◆ JointStateAnyPoly

Definition at line 245 of file joint_state.h.

◆ JointStatePtrAnyPoly

using tesseract_common::JointStatePtrAnyPoly = typedef AnyWrapper<std::shared_ptr<JointState> >

Definition at line 246 of file joint_state.h.

◆ LinkNamesPair

using tesseract_common::LinkNamesPair = typedef std::pair<std::string, std::string>

Definition at line 37 of file types.h.

◆ ManipulatorInfoAnyPoly

Definition at line 103 of file manipulator_info.h.

◆ PairsCollisionMarginData

Definition at line 66 of file collision_margin_data.h.

◆ PluginInfoMap

using tesseract_common::PluginInfoMap = typedef std::map<std::string, PluginInfo>

A map of PluginInfo to user defined name.

Definition at line 79 of file plugin_info.h.

◆ ProfileDictionaryPtrAnyPoly

Definition at line 162 of file profile_dictionary.h.

◆ SimpleResourceLocatorFn

using tesseract_common::SimpleResourceLocatorFn = typedef std::function<std::string(const std::string&)>

Definition at line 198 of file resource_locator.h.

◆ SizeTAnyPoly

using tesseract_common::SizeTAnyPoly = typedef AnyWrapper<std::size_t>

Definition at line 243 of file any_poly.h.

◆ StringAnyPoly

using tesseract_common::StringAnyPoly = typedef AnyWrapper<std::string>

Definition at line 242 of file any_poly.h.

◆ Toolpath

Definition at line 33 of file eigen_types.h.

◆ TrajArray

using tesseract_common::TrajArray = typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>

Definition at line 34 of file eigen_types.h.

◆ TransformMap

using tesseract_common::TransformMap = typedef AlignedMap<std::string, Eigen::Isometry3d>

Definition at line 32 of file eigen_types.h.

◆ UMapStringBoolAnyPoly

using tesseract_common::UMapStringBoolAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, bool> >

Definition at line 246 of file any_poly.h.

◆ UMapStringDoubleAnyPoly

using tesseract_common::UMapStringDoubleAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, double> >

Definition at line 249 of file any_poly.h.

◆ UMapStringFloatAnyPoly

using tesseract_common::UMapStringFloatAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, float> >

Definition at line 250 of file any_poly.h.

◆ UMapStringIntAnyPoly

using tesseract_common::UMapStringIntAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, int> >

Definition at line 247 of file any_poly.h.

◆ UMapStringSizeTAnyPoly

using tesseract_common::UMapStringSizeTAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, std::size_t> >

Definition at line 251 of file any_poly.h.

◆ UMapStringStringAnyPoly

using tesseract_common::UMapStringStringAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, std::string> >

Definition at line 245 of file any_poly.h.

◆ UMapStringUnsignedAnyPoly

using tesseract_common::UMapStringUnsignedAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, unsigned> >

Definition at line 248 of file any_poly.h.

◆ UnsignedAnyPoly

using tesseract_common::UnsignedAnyPoly = typedef AnyWrapper<unsigned>

Definition at line 239 of file any_poly.h.

◆ VectorIsometry3d

using tesseract_common::VectorIsometry3d = typedef AlignedVector<Eigen::Isometry3d>

Definition at line 28 of file eigen_types.h.

◆ VectorVector2d

using tesseract_common::VectorVector2d = typedef AlignedVector<Eigen::Vector2d>

Definition at line 31 of file eigen_types.h.

◆ VectorVector3d

using tesseract_common::VectorVector3d = typedef std::vector<Eigen::Vector3d>

Definition at line 30 of file eigen_types.h.

◆ VectorVector4d

using tesseract_common::VectorVector4d = typedef AlignedVector<Eigen::Vector4d>

Definition at line 29 of file eigen_types.h.

Enumeration Type Documentation

◆ CollisionMarginPairOverrideType

Identifies how the provided contact margin data should be applied.

Enumerator
NONE 

Do not apply contact margin data.

REPLACE 

Replace the contact manager's CollisionMarginPairData.

MODIFY 

Modify the contact managers pair margins.

This will preserve existing pairs not being modified by the provided margin data. If a pair already exist it will be updated with the provided margin data.

Definition at line 51 of file collision_margin_data.h.

◆ CombinedContactAllowedValidatorType

Identify how the two should be combined.

Enumerator
AND 

Combines the two ContactAllowedValidator with AND operator.

OR 

Combines the two ContactAllowedValidator with OR operator.

Definition at line 82 of file contact_allowed_validator.h.

Function Documentation

◆ almostEqualRelativeAndAbs() [1/3]

bool tesseract_common::almostEqualRelativeAndAbs ( const Eigen::Ref< const Eigen::VectorXd > &  v1,
const Eigen::Ref< const Eigen::VectorXd > &  v2,
const Eigen::Ref< const Eigen::VectorXd > &  max_diff,
const Eigen::Ref< const Eigen::VectorXd > &  max_rel_diff 
)

Check if two Eigen VectorXd are relatively and absolute equal.

This is a vectorized implementation of the function above. The max_diff is for handling when comparing numbers near zero

Parameters
aA vector of double
bA vector of double
max_diffThe max diff when comparing max(abs(a - b)) <= max_diff, if true they are considered equal
max_rel_diffThe max relative diff abs(a - b) <= largest * max_rel_diff, if true considered equal. The largest is the largest of the absolute values of a and b.
Returns
True if they are relatively equal, otherwise false.

Definition at line 469 of file utils.cpp.

◆ almostEqualRelativeAndAbs() [2/3]

bool tesseract_common::almostEqualRelativeAndAbs ( const Eigen::Ref< const Eigen::VectorXd > &  v1,
const Eigen::Ref< const Eigen::VectorXd > &  v2,
double  max_diff = 1e-6,
double  max_rel_diff = std::numeric_limits<double>::epsilon() 
)

Check if two Eigen VectorXd are relatively and absolute equal.

This is a vectorized implementation of the function above. The max_diff is for handling when comparing numbers near zero

Parameters
aA vector of double
bA vector of double
max_diffThe max diff when comparing max(abs(a - b)) <= max_diff, if true they are considered equal
max_rel_diffThe max relative diff abs(a - b) <= largest * max_rel_diff, if true considered equal. The largest is the largest of the absolute values of a and b.
Returns
True if they are relatively equal, otherwise false.

Definition at line 458 of file utils.cpp.

◆ almostEqualRelativeAndAbs() [3/3]

bool tesseract_common::almostEqualRelativeAndAbs ( double  a,
double  b,
double  max_diff = 1e-6,
double  max_rel_diff = std::numeric_limits<double>::epsilon() 
)

Check if two double are relatively equal.

The max_diff is for handling when comparing numbers near zero

Parameters
aDouble
bDouble
max_diffThe max diff when comparing std::abs(a - b) <= max_diff, if true they are considered equal
max_rel_diffThe max relative diff std::abs(a - b) <= largest * max_rel_diff, if true considered equal. The largest is the largest of the absolute values of a and b.
Returns
True if they are relatively equal, otherwise false.

Definition at line 445 of file utils.cpp.

◆ calcJacobianTransformErrorDiff() [1/2]

Eigen::VectorXd tesseract_common::calcJacobianTransformErrorDiff ( const Eigen::Isometry3d &  target,
const Eigen::Isometry3d &  source,
const Eigen::Isometry3d &  source_perturbed 
)

Calculate jacobian transform error difference expressed in the target frame coordinate system.

This is used when the target is a fixed frame in the environment

Parameters
targetTarget The desired transform to express the transform error difference in
sourceThe current location of the source transform
source_perturbedThe perturbed location of the source transform
Returns
The change in error represented in the target frame

Definition at line 163 of file utils.cpp.

◆ calcJacobianTransformErrorDiff() [2/2]

Eigen::VectorXd tesseract_common::calcJacobianTransformErrorDiff ( const Eigen::Isometry3d &  target,
const Eigen::Isometry3d &  target_perturbed,
const Eigen::Isometry3d &  source,
const Eigen::Isometry3d &  source_perturbed 
)

Calculate jacobian transform error difference expressed in the target frame coordinate system.

This is used when the target and source are both dynamic links

Parameters
targetTarget The desired transform to express the transform error difference in
target_perturbedThe perturbed location of the target transform
sourceThe current location of the source transform
source_perturbedThe perturbed location of the source transform
Returns
The change in error represented in the target frame

Definition at line 197 of file utils.cpp.

◆ calcRotationalError()

Eigen::Vector3d tesseract_common::calcRotationalError ( const Eigen::Ref< const Eigen::Matrix3d > &  R)

Calculate the rotation error vector given a rotation error matrix where the angle is between [-pi, pi].

This should be used only for calculating the error. Do not use for numerically calculating jacobians because it breaks down a -PI and PI

Parameters
Rrotation error matrix
Returns
Rotation error vector = Eigen::AngleAxisd.axis() * Eigen::AngleAxisd.angle()

Definition at line 151 of file utils.cpp.

◆ calcRotationalErrorDecomposed()

std::pair<Eigen::Vector3d, double> tesseract_common::calcRotationalErrorDecomposed ( const Eigen::Ref< const Eigen::Matrix3d > &  R)

Definition at line 127 of file utils.cpp.

◆ calcTransformError()

Eigen::VectorXd tesseract_common::calcTransformError ( const Eigen::Isometry3d &  t1,
const Eigen::Isometry3d &  t2 
)

Calculate error between two transforms expressed in t1 coordinate system.

Warning
This should not be used to calculate numerical jacobian, see calcJacobianTransformErrorDiff
Parameters
t1Target Transform
t2Current Transform
Returns
error [Position, calcRotationalError(Angle Axis)]

Definition at line 157 of file utils.cpp.

◆ checkForUnknownKeys()

void tesseract_common::checkForUnknownKeys ( const YAML::Node &  node,
const std::set< std::string > &  expected_keys 
)

Check node map for unknown keys.

Parameters
nodeThe node to check
expected_keysThe expected keys

Definition at line 122 of file yaml_utils.cpp.

◆ compareYAML()

bool tesseract_common::compareYAML ( const YAML::Node &  node1,
const YAML::Node &  node2 
)

Checks if the YAML::Nodes are identical.

The == operator checks if they reference the same memory. This checks if they contain the same information

Parameters
node1Input YAML::Node
node2Input YAML::Node

Definition at line 144 of file yaml_utils.cpp.

◆ computeRandomColor()

Eigen::Vector4d tesseract_common::computeRandomColor ( )

This computes a random color RGBA [0, 1] with alpha set to 1.

Returns
A random RGBA color

Definition at line 231 of file utils.cpp.

◆ concat()

Eigen::VectorXd tesseract_common::concat ( const Eigen::VectorXd &  a,
const Eigen::VectorXd &  b 
)

Concatenate two vector.

Definition at line 119 of file utils.cpp.

◆ enforceLimits()

template<typename FloatType >
void tesseract_common::enforceLimits ( Eigen::Ref< Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >>  values,
const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &  limits 
)

Enforce values to be within the provided limits.

Parameters
valuesThe values to enforce bounds on
limitsThe limits to perform check

Definition at line 150 of file kinematic_limits.h.

◆ enforceLimits< double >()

template void tesseract_common::enforceLimits< double > ( Eigen::Ref< Eigen::Matrix< double, Eigen::Dynamic, 1 >>  values,
const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &  limits 
)

◆ enforceLimits< float >()

template void tesseract_common::enforceLimits< float > ( Eigen::Ref< Eigen::Matrix< float, Eigen::Dynamic, 1 >>  values,
const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &  limits 
)

◆ fileToString()

std::string tesseract_common::fileToString ( const std::filesystem::path &  filepath)

Read in the contents of the file into a string.

Parameters
filepathThe file to read
Returns
The contents of the file

Definition at line 75 of file utils.cpp.

◆ findSeparator()

std::size_t tesseract_common::findSeparator ( const std::string &  str)

Definition at line 152 of file resource_locator.cpp.

◆ fromYAMLString()

YAML::Node tesseract_common::fromYAMLString ( const std::string &  string)

Converts yaml string to a YAML::Node.

Parameters
stringInput string containing the yaml
Returns
Resulting YAML::Node

Definition at line 142 of file yaml_utils.cpp.

◆ generateRandomNumber()

Eigen::VectorXd tesseract_common::generateRandomNumber ( const Eigen::Ref< const Eigen::MatrixX2d > &  limits)

Given a set of limits it will generate a vector of random numbers between the limit.

Parameters
limitsThe limits to generated numbers based on.
Returns
A vector of random numbers between the provided limits.

Definition at line 288 of file utils.cpp.

◆ getAllowedCollisions()

std::vector< std::string > tesseract_common::getAllowedCollisions ( const std::vector< std::string > &  link_names,
const AllowedCollisionEntries acm_entries,
bool  remove_duplicates = true 
)

Gets allowed collisions for a set of link names.

Parameters
link_namesVector of link names for which we want the allowed collisions
acm_entriesEntries in the ACM. Get this with AllowedCollisionMatrix::getAllAllowedCollisions()
remove_duplicatesIf true, duplicates will be removed. Default: true
Returns
vector of links that are allowed to collide with links given

Definition at line 492 of file utils.cpp.

◆ getTempPath()

std::string tesseract_common::getTempPath ( )

Get the host temp directory path.

Returns
The host temp directory path

Definition at line 262 of file utils.cpp.

◆ getTimestampString()

std::string tesseract_common::getTimestampString ( )

Get Timestamp string.

Returns
Timestamp string

Definition at line 310 of file utils.cpp.

◆ isIdentical()

template<typename T >
bool tesseract_common::isIdentical ( const std::vector< T > &  vec1,
const std::vector< T > &  vec2,
bool  ordered = true,
const std::function< bool(const T &, const T &)> &  equal_pred = [](const T& v1, const T& v2) { return v1 == v2; },
const std::function< bool(const T &, const T &)> &  comp = [](const T& v1, const T& v2) { return v1 < v2; } 
)

Check if two vector of strings are identical.

Parameters
vec1Vector strings
vec2Vector strings
orderedIf true order is relavent, othwise if false order is not relavent
equal_predBinary predicate passed into std::equals to determine if an element is equal. Useful for vectors of pointers
compBinary function passed into std::sort. Only used it ordered == false. Useful for vectors of pointers

Definition at line 227 of file utils.h.

◆ isIdentical< Eigen::Index >()

template bool tesseract_common::isIdentical< Eigen::Index > ( const std::vector< Eigen::Index > &  ,
const std::vector< Eigen::Index > &  ,
bool  ,
const std::function< bool(const Eigen::Index &, const Eigen::Index &)> &  ,
const std::function< bool(const Eigen::Index &, const Eigen::Index &)> &   
)

◆ isIdentical< std::string >()

template bool tesseract_common::isIdentical< std::string > ( const std::vector< std::string > &  ,
const std::vector< std::string > &  ,
bool  ,
const std::function< bool(const std::string &, const std::string &)> &  ,
const std::function< bool(const std::string &, const std::string &)> &   
)

◆ isIdenticalArray()

template<typename ValueType , std::size_t Size>
bool tesseract_common::isIdenticalArray ( const std::array< ValueType, Size > &  array_1,
const std::array< ValueType, Size > &  array_2,
const std::function< bool(const ValueType &, const ValueType &)> &  value_eq = [](const ValueType& v1, const ValueType& v2) { return v1 == v2; } 
)

Checks if 2 arrays are identical.

Parameters
array_1First array
array_2Second array
Returns
True if they are identical

Definition at line 312 of file utils.h.

◆ isIdenticalMap()

template<typename KeyValueContainerType , typename ValueType >
bool tesseract_common::isIdenticalMap ( const KeyValueContainerType &  map_1,
const KeyValueContainerType &  map_2,
const std::function< bool(const ValueType &, const ValueType &)> &  value_eq = [](const ValueType& v1, const ValueType& v2) { return v1 == v2; } 
)

Checks if 2 maps are identical.

Parameters
map_1First map
map_2Second map
Returns
True if they are identical

Definition at line 254 of file utils.h.

◆ isIdenticalSet()

template<typename ValueType >
bool tesseract_common::isIdenticalSet ( const std::set< ValueType > &  set_1,
const std::set< ValueType > &  set_2,
const std::function< bool(const ValueType &, const ValueType &)> &  value_eq = [](const ValueType& v1, const ValueType& v2) { return v1 == v2; } 
)

Checks if 2 sets are identical.

Parameters
map_1First map
map_2Second map
Returns
True if they are identical

Definition at line 283 of file utils.h.

◆ isNumeric() [1/2]

bool tesseract_common::isNumeric ( const std::string &  s)

Determine if a string is a number.

Parameters
sThe string to evaluate
Returns
True if numeric, otherwise false.

Definition at line 267 of file utils.cpp.

◆ isNumeric() [2/2]

bool tesseract_common::isNumeric ( const std::vector< std::string > &  sv)

Determine if each string in vector is a number.

Parameters
svThe vector of strings to evaluate
Returns
True if all strings are numeric, otherwise false.

Definition at line 283 of file utils.cpp.

◆ isRelativePath()

bool tesseract_common::isRelativePath ( const std::string &  url)

Definition at line 46 of file resource_locator.cpp.

◆ isWithinLimits()

template<typename FloatType >
bool tesseract_common::isWithinLimits ( const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &  limits 
)

Check if within limits.

Parameters
joint_positionsThe values to check
position_limitsThe limits to perform check
Returns

Definition at line 78 of file kinematic_limits.h.

◆ isWithinLimits< double >()

template bool tesseract_common::isWithinLimits< double > ( const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &  limits 
)

◆ isWithinLimits< float >()

template bool tesseract_common::isWithinLimits< float > ( const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &  limits 
)

◆ jacobianChangeBase()

void tesseract_common::jacobianChangeBase ( Eigen::Ref< Eigen::MatrixXd >  jacobian,
const Eigen::Isometry3d &  change_base 
)

Change the base coordinate system of the jacobian.

Parameters
jacobianThe current Jacobian which gets modified in place
change_baseThe transform from the desired frame to the current base frame of the jacobian

Definition at line 104 of file utils.cpp.

◆ jacobianChangeRefPoint()

void tesseract_common::jacobianChangeRefPoint ( Eigen::Ref< Eigen::MatrixXd >  jacobian,
const Eigen::Ref< const Eigen::Vector3d > &  ref_point 
)

Change the reference point of the jacobian.

Parameters
jacobianThe current Jacobian which gets modified in place
ref_pointIs expressed in the same base frame of the jacobian and is a vector from the old point to the new point.

Definition at line 111 of file utils.cpp.

◆ loadYamlFile()

YAML::Node tesseract_common::loadYamlFile ( const std::string &  file_path,
const ResourceLocator locator 
)

Loads a YAML file and processes !include directives recursively.

This function loads a YAML file and replaces any node tagged with !include with the content of the specified file. It handles nested !include directives and works with both maps and sequences.

Parameters
file_pathThe path to the YAML file/url to be loaded.
locatorThe locator used to resolve urls and relative file paths.
Returns
A YAML::Node object containing the fully processed YAML structure.
Exceptions
std::runtime_errorif an !include tag is used improperly (e.g., not scalar), or if a file specified in an !include directive cannot be loaded.

Definition at line 93 of file yaml_utils.cpp.

◆ loadYamlString()

YAML::Node tesseract_common::loadYamlString ( const std::string &  yaml_string,
const ResourceLocator locator 
)

Definition at line 100 of file yaml_utils.cpp.

◆ ltrim()

void tesseract_common::ltrim ( std::string &  s)

Left trim string.

Parameters
sThe string to left trim

Definition at line 300 of file utils.cpp.

◆ makeOrderedLinkPair() [1/2]

LinkNamesPair tesseract_common::makeOrderedLinkPair ( const std::string &  link_name1,
const std::string &  link_name2 
)

Create a pair of strings, where the pair.first is always <= pair.second.

This is commonly used along with PairHash as the key to an unordered_map<LinkNamesPair, Type, PairHash>

Parameters
link_name1First link name
link_name2Second link name
Returns
LinkNamesPair a lexicographically sorted pair of strings

Definition at line 44 of file types.cpp.

◆ makeOrderedLinkPair() [2/2]

void tesseract_common::makeOrderedLinkPair ( LinkNamesPair pair,
const std::string &  link_name1,
const std::string &  link_name2 
)

Populate a pair of strings, where the pair.first is always <= pair.second.

This is used to avoid multiple memory application throughout the code base

This is commonly used along with PairHash as the key to an unordered_map<LinkNamesPair, Type, PairHash>

Parameters
pairThe link name pair to load a lexicographically sorted pair of strings
link_name1First link name
link_name2Second link nam

Definition at line 49 of file types.cpp.

◆ my_rethrow_if_nested() [1/2]

template<typename E >
std::enable_if_t<!std::is_polymorphic<E>::value> tesseract_common::my_rethrow_if_nested ( const E &  )

Definition at line 63 of file utils.cpp.

◆ my_rethrow_if_nested() [2/2]

template<typename E >
std::enable_if_t<std::is_polymorphic<E>::value> tesseract_common::my_rethrow_if_nested ( const E &  e)

Definition at line 68 of file utils.cpp.

◆ operator!=()

bool tesseract_common::operator!= ( const ProfileDictionary lhs,
const ProfileDictionary rhs 
)

Definition at line 68 of file tesseract_common_serialization_unit.cpp.

◆ operator<<()

std::ostream & tesseract_common::operator<< ( std::ostream &  os,
const AllowedCollisionMatrix acm 
)

Definition at line 131 of file allowed_collision_matrix.cpp.

◆ operator==() [1/2]

bool tesseract_common::operator== ( const AllowedCollisionEntries entries_1,
const AllowedCollisionEntries entries_2 
)

Definition at line 42 of file allowed_collision_matrix.cpp.

◆ operator==() [2/2]

bool tesseract_common::operator== ( const ProfileDictionary lhs,
const ProfileDictionary rhs 
)

Definition at line 50 of file tesseract_common_serialization_unit.cpp.

◆ pointersComparison()

template<typename T >
bool tesseract_common::pointersComparison ( const std::shared_ptr< T > &  p1,
const std::shared_ptr< T > &  p2 
)

Comparison operator for the objects 2 points point to.

Parameters
p1First pointer
p2Second pointer
Returns
True if *p1 < *p2 and neither is nullptr. Non-nullptr is considered > than nullptr

Definition at line 347 of file utils.h.

◆ pointersEqual()

template<typename T >
bool tesseract_common::pointersEqual ( const std::shared_ptr< T > &  p1,
const std::shared_ptr< T > &  p2 
)

Checks if 2 pointers point to objects that are ==.

Parameters
p1First pointer
p2Second pointer
Returns
True if the objects are == or both pointers are nullptr

Definition at line 336 of file utils.h.

◆ printNestedException()

void tesseract_common::printNestedException ( const std::exception &  e,
int  level = 0 
)

Print a nested exception.

Parameters
eThe exception to print
levelThe exception level which controls the indentation

Definition at line 246 of file utils.cpp.

◆ processYamlIncludeDirective()

YAML::Node tesseract_common::processYamlIncludeDirective ( const YAML::Node &  node,
const ResourceLocator locator 
)

Recursively processes a YAML node to resolve !include directives.

This function replaces any node tagged with !include with the content of the specified file. It also recursively processes maps and sequences to handle nested !include directives.

Parameters
nodeThe YAML node to process.
locatorThe locator used to resolve urls and relative file paths.
Returns
A YAML::Node with all !include directives resolved.
Exceptions
std::runtime_errorif an !include tag is used improperly (e.g., not scalar), or if a file specified in an !include directive cannot be loaded.

Definition at line 52 of file yaml_utils.cpp.

◆ QueryDoubleAttributeRequired()

int tesseract_common::QueryDoubleAttributeRequired ( const tinyxml2::XMLElement *  xml_element,
const char *  name,
double &  value 
)

Query a double attribute from an xml element and print error log.

This is the same QueryDoubleAttribute but it will print out error messages for the failure conditions so the user only needs to check for the tinyxml2::XML_SUCCESS since it is a required attribute.

Parameters
xml_elementThe xml attribute to query attribute
nameThe name of the attribute to query
valueThe value to update from the xml attribute
Returns
tinyxml2::XML_SUCCESS if successful, otherwise returns tinyxml2::XML_NO_ATTRIBUTE or tinyxml2::XML_WRONG_ATTRIBUTE_TYPE

Definition at line 405 of file utils.cpp.

◆ QueryIntAttributeRequired()

int tesseract_common::QueryIntAttributeRequired ( const tinyxml2::XMLElement *  xml_element,
const char *  name,
int &  value 
)

Query a int attribute from an xml element and print error log.

This is the same QueryIntAttribute but it will print out error messages for the failure conditions so the user only needs to check for the tinyxml2::XML_SUCCESS since it is a required attribute.

Parameters
xml_elementThe xml attribute to query attribute
nameThe name of the attribute to query
valueThe value to update from the xml attribute
Returns
tinyxml2::XML_SUCCESS if successful, otherwise returns tinyxml2::XML_NO_ATTRIBUTE or tinyxml2::XML_WRONG_ATTRIBUTE_TYPE

Definition at line 425 of file utils.cpp.

◆ QueryStringAttribute()

int tesseract_common::QueryStringAttribute ( const tinyxml2::XMLElement *  xml_element,
const char *  name,
std::string &  value 
)

Query a string attribute from an xml element.

Parameters
xml_elementThe xml attribute to query attribute
nameThe name of the attribute to query
valueThe value to update from the xml attribute
Returns
tinyxml2::XML_SUCCESS if successful, otherwise returns tinyxml2::XML_NO_ATTRIBUTE or tinyxml2::XML_WRONG_ATTRIBUTE_TYPE

Definition at line 369 of file utils.cpp.

◆ QueryStringAttributeRequired()

int tesseract_common::QueryStringAttributeRequired ( const tinyxml2::XMLElement *  xml_element,
const char *  name,
std::string &  value 
)

Query a string attribute from an xml element and print error log.

This is the same QueryStringAttribute but it will print out error messages for the failure conditions so the user only needs to check for the tinyxml2::XML_SUCCESS since it is a required attribute.

Parameters
xml_elementThe xml attribute to query attribute
nameThe name of the attribute to query
valueThe value to update from the xml attribute
Returns
tinyxml2::XML_SUCCESS if successful, otherwise returns tinyxml2::XML_NO_ATTRIBUTE or tinyxml2::XML_WRONG_ATTRIBUTE_TYPE

Definition at line 385 of file utils.cpp.

◆ QueryStringText()

int tesseract_common::QueryStringText ( const tinyxml2::XMLElement *  xml_element,
std::string &  text 
)

Query a string Text from xml element.

Parameters
xml_elementThe xml element to query string from
testThe value to update from the xml element
Returns
tinyxml2::XML_SUCCESS if successful, otherwise returns tinyxml2::XML_NO_ATTRIBUTE

Definition at line 349 of file utils.cpp.

◆ QueryStringValue() [1/2]

int tesseract_common::QueryStringValue ( const tinyxml2::XMLAttribute *  xml_attribute,
std::string &  value 
)

Query a string value from xml attribute.

Parameters
xml_attributeThe xml attribute to query string from
valueThe value to update from the xml attribute
Returns
tinyxml2::XML_SUCCESS if successful, otherwise returns tinyxml2::XML_WRONG_ATTRIBUTE_TYPE

Definition at line 359 of file utils.cpp.

◆ QueryStringValue() [2/2]

int tesseract_common::QueryStringValue ( const tinyxml2::XMLElement *  xml_element,
std::string &  value 
)

Query a string value from xml element.

Parameters
xml_elementThe xml element to query string from
valueThe value to update from the xml element
Returns
tinyxml2::XML_SUCCESS if successful, otherwise returns tinyxml2::XML_NO_ATTRIBUTE

Definition at line 339 of file utils.cpp.

◆ reorder()

void tesseract_common::reorder ( Eigen::Ref< Eigen::VectorXd >  v,
std::vector< Eigen::Index >  order 
)

Reorder Eigen::VectorXd implace given index list.

Parameters
vThe vector to reorder
orderA vector of index which define the new order

Definition at line 319 of file utils.cpp.

◆ rtrim()

void tesseract_common::rtrim ( std::string &  s)

Right trim string.

Parameters
sThe string to right trim

Definition at line 302 of file utils.cpp.

◆ satisfiesLimits() [1/2]

template<typename FloatType >
bool tesseract_common::satisfiesLimits ( const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &  limits,
const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &  max_diff,
const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &  max_rel_diff 
)

Check if values are within bounds or relatively equal to a limit.

Parameters
valuesThe values to check
limitsThe limits to perform check
max_diffThe max diff when comparing value to limit value max(abs(value - limit)) <= max_diff, if true they are considered equal
max_rel_diffThe max relative diff between value and limit abs(value - limit) <= largest * max_rel_diff, if true considered equal. The largest is the largest of the absolute values of value and limit.
Returns
True if the all values are within the limits or relatively equal to the limit, otherwise false.

Definition at line 98 of file kinematic_limits.h.

◆ satisfiesLimits() [2/2]

template<typename FloatType >
bool tesseract_common::satisfiesLimits ( const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &  limits,
FloatType  max_diff = static_cast<FloatType>(1e-6),
FloatType  max_rel_diff = std::numeric_limits<FloatType>::epsilon() 
)

Check if values is within bounds or relatively equal to a limit.

Parameters
valuesThe values to check
limitsThe limits to perform check
max_diffThe max diff when comparing value to limit value max(abs(value - limit)) <= max_diff, if true they are considered equal
max_rel_diffThe max relative diff between value and limit abs(value - limit) <= largest * max_rel_diff, if true considered equal. The largest is the largest of the absolute values of value and limit.
Returns
True if the all values are within the limits or relatively equal to the limit, otherwise false.

Definition at line 133 of file kinematic_limits.h.

◆ satisfiesLimits< double >() [1/2]

template bool tesseract_common::satisfiesLimits< double > ( const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &  limits,
const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &  max_diff,
const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &  max_rel_diff 
)

◆ satisfiesLimits< double >() [2/2]

template bool tesseract_common::satisfiesLimits< double > ( const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 2 >> &  limits,
double  max_diff,
double  max_rel_diff 
)

◆ satisfiesLimits< float >() [1/2]

template bool tesseract_common::satisfiesLimits< float > ( const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &  limits,
const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &  max_diff,
const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &  max_rel_diff 
)

◆ satisfiesLimits< float >() [2/2]

template bool tesseract_common::satisfiesLimits< float > ( const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 1 >> &  values,
const Eigen::Ref< const Eigen::Matrix< float, Eigen::Dynamic, 2 >> &  limits,
float  max_diff,
float  max_rel_diff 
)

◆ strFormat()

template<typename... Args>
std::string tesseract_common::strFormat ( const std::string &  format,
Args...  args 
)

Definition at line 63 of file utils.h.

◆ StringAttribute()

std::string tesseract_common::StringAttribute ( const tinyxml2::XMLElement *  xml_element,
const char *  name,
std::string  default_value 
)

Get string attribute if exist. If it does not exist it returns the default value.

Parameters
xml_elementThe xml element to attempt to parse attribute
nameThe name of the attribute
default_valueThe default value to return if attribute does not exist
Returns
Parsed string attribute or default value if attribute does not exist.

Definition at line 378 of file utils.cpp.

◆ testSerialization()

template<typename SerializableType >
void tesseract_common::testSerialization ( const SerializableType &  object,
const std::string &  typename_string 
)

Tests Boost serialization for a serializable type.

Serializes the type to XML file, binary file, and XML string. It then deserializes it and calls the equality operator on the results

Parameters
objectObject to be serialized
typename_stringPrefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension>

Definition at line 48 of file unit_test_utils.h.

◆ testSerializationAnyPolyStoredSharedPtr()

template<typename SerializableTypeStored >
void tesseract_common::testSerializationAnyPolyStoredSharedPtr ( const tesseract_common::AnyPoly object,
const std::string &  typename_string 
)

Tests Boost serialization for a serializable any poly type.

Serializes the type to XML file, binary file, and XML string using the base type. It then deserializes it, casts it to the derived type, and calls the equality operator on the results

Parameters
objectBase class pointer to the object to be serialized
typename_stringPrefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension>

Definition at line 244 of file unit_test_utils.h.

◆ testSerializationDerivedClass()

template<typename SerializableTypeBase , typename SerializableTypeDerived >
void tesseract_common::testSerializationDerivedClass ( const std::shared_ptr< SerializableTypeBase > &  object,
const std::string &  typename_string 
)

Tests Boost serialization for a serializable derived type.

Serializes the type to XML file, binary file, and XML string using the base type. It then deserializes it, casts it to the derived type, and calls the equality operator on the results

Parameters
objectBase class pointer to the object to be serialized
typename_stringPrefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension>

Definition at line 178 of file unit_test_utils.h.

◆ testSerializationPtr()

template<typename SerializableType >
void tesseract_common::testSerializationPtr ( const std::shared_ptr< SerializableType > &  object,
const std::string &  typename_string 
)

Tests Boost serialization of shared pointer for a serializable type.

Serializes the type to XML file, binary file, and XML string. It then deserializes it and calls the equality operator on the results

Parameters
objectObject to be serialized
typename_stringPrefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension>

Definition at line 128 of file unit_test_utils.h.

◆ toNumeric()

template<typename FloatType >
bool tesseract_common::toNumeric ( const std::string &  s,
FloatType &  value 
)

Convert a string to a numeric value type.

Parameters
sThe string to be converted
valueThe value to be loaded with converted string
Returns
True if successful, otherwise false

Definition at line 508 of file utils.h.

◆ toNumeric< double >()

template bool tesseract_common::toNumeric< double > ( const std::string &  ,
double &   
)

◆ toNumeric< float >()

template bool tesseract_common::toNumeric< float > ( const std::string &  ,
float &   
)

◆ toNumeric< int >()

template bool tesseract_common::toNumeric< int > ( const std::string &  ,
int &   
)

◆ toNumeric< long >()

template bool tesseract_common::toNumeric< long > ( const std::string &  ,
long &   
)

◆ toYAMLString()

std::string tesseract_common::toYAMLString ( const YAML::Node &  node)

Converts a YAML::Node to a yaml string.

Parameters
nodeInput node
Returns
String containing the yaml

Definition at line 135 of file yaml_utils.cpp.

◆ trim()

void tesseract_common::trim ( std::string &  s)

Trim left and right of string.

Parameters
sThe string to trim

Definition at line 304 of file utils.cpp.

◆ twistChangeBase()

void tesseract_common::twistChangeBase ( Eigen::Ref< Eigen::VectorXd >  twist,
const Eigen::Isometry3d &  change_base 
)

Change the base coordinate system of the Twist.

Parameters
twistThe current Twist which gets modified in place
change_baseThe transform from the desired frame to the current base frame of the Twist

Definition at line 98 of file utils.cpp.

◆ twistChangeRefPoint()

void tesseract_common::twistChangeRefPoint ( Eigen::Ref< Eigen::VectorXd >  twist,
const Eigen::Ref< const Eigen::Vector3d > &  ref_point 
)

Change the reference point of the provided Twist.

Parameters
twistThe current Twist which gets modified in place
ref_pointIs expressed in the same base frame of the Twist and is a vector from the old point to the new point.

Definition at line 91 of file utils.cpp.

◆ writeYamlToFile()

void tesseract_common::writeYamlToFile ( const YAML::Node &  node,
const std::string &  file_path 
)

Writes a YAML::Node to a file.

Parameters
nodeThe YAML::Node to write.
file_pathThe path to the output file.
Exceptions
std::runtime_errorif the file cannot be opened.

Definition at line 106 of file yaml_utils.cpp.

Variable Documentation

◆ mersenne

std::mt19937 tesseract_common::mersenne { static_cast<std::mt19937::result_type>(std::time(nullptr)) }
static

Random number generator.

Definition at line 55 of file utils.h.



tesseract_common
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:40