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... | |
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.
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.
using tesseract_common::AlignedVector = typedef std::vector<T, Eigen::aligned_allocator<T> > |
Definition at line 16 of file eigen_types.h.
using tesseract_common::AllowedCollisionEntries = typedef std::unordered_map<tesseract_common::LinkNamesPair, std::string, tesseract_common::PairHash> |
Definition at line 24 of file allowed_collision_matrix.h.
using tesseract_common::BoolAnyPoly = typedef AnyWrapper<bool> |
Definition at line 237 of file any_poly.h.
using tesseract_common::DoubleAnyPoly = typedef AnyWrapper<double> |
Definition at line 240 of file any_poly.h.
using tesseract_common::FloatAnyPoly = typedef AnyWrapper<float> |
Definition at line 241 of file any_poly.h.
using tesseract_common::IntAnyPoly = typedef AnyWrapper<int> |
Definition at line 238 of file any_poly.h.
using tesseract_common::JointStateAnyPoly = typedef AnyWrapper<JointState> |
Definition at line 245 of file joint_state.h.
using tesseract_common::JointStatePtrAnyPoly = typedef AnyWrapper<std::shared_ptr<JointState> > |
Definition at line 246 of file joint_state.h.
using tesseract_common::LinkNamesPair = typedef std::pair<std::string, std::string> |
using tesseract_common::ManipulatorInfoAnyPoly = typedef AnyWrapper<ManipulatorInfo> |
Definition at line 103 of file manipulator_info.h.
using tesseract_common::PairsCollisionMarginData = typedef std::unordered_map<tesseract_common::LinkNamesPair, double, tesseract_common::PairHash> |
Definition at line 66 of file collision_margin_data.h.
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.
using tesseract_common::ProfileDictionaryPtrAnyPoly = typedef tesseract_common::AnyWrapper<std::shared_ptr<ProfileDictionary> > |
Definition at line 162 of file profile_dictionary.h.
using tesseract_common::SimpleResourceLocatorFn = typedef std::function<std::string(const std::string&)> |
Definition at line 198 of file resource_locator.h.
using tesseract_common::SizeTAnyPoly = typedef AnyWrapper<std::size_t> |
Definition at line 243 of file any_poly.h.
using tesseract_common::StringAnyPoly = typedef AnyWrapper<std::string> |
Definition at line 242 of file any_poly.h.
using tesseract_common::Toolpath = typedef AlignedVector<VectorIsometry3d> |
Definition at line 33 of file eigen_types.h.
using tesseract_common::TrajArray = typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> |
Definition at line 34 of file eigen_types.h.
using tesseract_common::TransformMap = typedef AlignedMap<std::string, Eigen::Isometry3d> |
Definition at line 32 of file eigen_types.h.
using tesseract_common::UMapStringBoolAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, bool> > |
Definition at line 246 of file any_poly.h.
using tesseract_common::UMapStringDoubleAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, double> > |
Definition at line 249 of file any_poly.h.
using tesseract_common::UMapStringFloatAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, float> > |
Definition at line 250 of file any_poly.h.
using tesseract_common::UMapStringIntAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, int> > |
Definition at line 247 of file any_poly.h.
using tesseract_common::UMapStringSizeTAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, std::size_t> > |
Definition at line 251 of file any_poly.h.
using tesseract_common::UMapStringStringAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, std::string> > |
Definition at line 245 of file any_poly.h.
using tesseract_common::UMapStringUnsignedAnyPoly = typedef AnyWrapper<std::unordered_map<std::string, unsigned> > |
Definition at line 248 of file any_poly.h.
using tesseract_common::UnsignedAnyPoly = typedef AnyWrapper<unsigned> |
Definition at line 239 of file any_poly.h.
using tesseract_common::VectorIsometry3d = typedef AlignedVector<Eigen::Isometry3d> |
Definition at line 28 of file eigen_types.h.
using tesseract_common::VectorVector2d = typedef AlignedVector<Eigen::Vector2d> |
Definition at line 31 of file eigen_types.h.
using tesseract_common::VectorVector3d = typedef std::vector<Eigen::Vector3d> |
Definition at line 30 of file eigen_types.h.
using tesseract_common::VectorVector4d = typedef AlignedVector<Eigen::Vector4d> |
Definition at line 29 of file eigen_types.h.
|
strong |
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.
|
strong |
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.
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
a | A vector of double |
b | A vector of double |
max_diff | The max diff when comparing max(abs(a - b)) <= max_diff, if true they are considered equal |
max_rel_diff | The 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. |
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
a | A vector of double |
b | A vector of double |
max_diff | The max diff when comparing max(abs(a - b)) <= max_diff, if true they are considered equal |
max_rel_diff | The 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. |
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
a | Double |
b | Double |
max_diff | The max diff when comparing std::abs(a - b) <= max_diff, if true they are considered equal |
max_rel_diff | The 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. |
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
target | Target The desired transform to express the transform error difference in |
source | The current location of the source transform |
source_perturbed | The perturbed location of the source transform |
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
target | Target The desired transform to express the transform error difference in |
target_perturbed | The perturbed location of the target transform |
source | The current location of the source transform |
source_perturbed | The perturbed location of the source transform |
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
R | rotation error matrix |
std::pair<Eigen::Vector3d, double> tesseract_common::calcRotationalErrorDecomposed | ( | const Eigen::Ref< const Eigen::Matrix3d > & | R | ) |
Eigen::VectorXd tesseract_common::calcTransformError | ( | const Eigen::Isometry3d & | t1, |
const Eigen::Isometry3d & | t2 | ||
) |
Calculate error between two transforms expressed in t1 coordinate system.
t1 | Target Transform |
t2 | Current Transform |
void tesseract_common::checkForUnknownKeys | ( | const YAML::Node & | node, |
const std::set< std::string > & | expected_keys | ||
) |
Check node map for unknown keys.
node | The node to check |
expected_keys | The expected keys |
Definition at line 122 of file yaml_utils.cpp.
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
node1 | Input YAML::Node |
node2 | Input YAML::Node |
Definition at line 144 of file yaml_utils.cpp.
Eigen::Vector4d tesseract_common::computeRandomColor | ( | ) |
Eigen::VectorXd tesseract_common::concat | ( | const Eigen::VectorXd & | a, |
const Eigen::VectorXd & | b | ||
) |
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.
values | The values to enforce bounds on |
limits | The limits to perform check |
Definition at line 150 of file kinematic_limits.h.
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 | ||
) |
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 | ||
) |
std::string tesseract_common::fileToString | ( | const std::filesystem::path & | filepath | ) |
std::size_t tesseract_common::findSeparator | ( | const std::string & | str | ) |
Definition at line 152 of file resource_locator.cpp.
YAML::Node tesseract_common::fromYAMLString | ( | const std::string & | string | ) |
Converts yaml string to a YAML::Node.
string | Input string containing the yaml |
Definition at line 142 of file yaml_utils.cpp.
Eigen::VectorXd tesseract_common::generateRandomNumber | ( | const Eigen::Ref< const Eigen::MatrixX2d > & | limits | ) |
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.
link_names | Vector of link names for which we want the allowed collisions |
acm_entries | Entries in the ACM. Get this with AllowedCollisionMatrix::getAllAllowedCollisions() |
remove_duplicates | If true, duplicates will be removed. Default: true |
std::string tesseract_common::getTempPath | ( | ) |
std::string tesseract_common::getTimestampString | ( | ) |
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.
vec1 | Vector strings |
vec2 | Vector strings |
ordered | If true order is relavent, othwise if false order is not relavent |
equal_pred | Binary predicate passed into std::equals to determine if an element is equal. Useful for vectors of pointers |
comp | Binary function passed into std::sort. Only used it ordered == false. Useful for vectors of pointers |
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 &)> & | |||
) |
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 &)> & | |||
) |
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; } |
||
) |
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; } |
||
) |
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; } |
||
) |
bool tesseract_common::isNumeric | ( | const std::string & | s | ) |
bool tesseract_common::isNumeric | ( | const std::vector< std::string > & | sv | ) |
bool tesseract_common::isRelativePath | ( | const std::string & | url | ) |
Definition at line 46 of file resource_locator.cpp.
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.
joint_positions | The values to check |
position_limits | The limits to perform check |
Definition at line 78 of file kinematic_limits.h.
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 | ||
) |
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 | ||
) |
void tesseract_common::jacobianChangeBase | ( | Eigen::Ref< Eigen::MatrixXd > | jacobian, |
const Eigen::Isometry3d & | change_base | ||
) |
void tesseract_common::jacobianChangeRefPoint | ( | Eigen::Ref< Eigen::MatrixXd > | jacobian, |
const Eigen::Ref< const Eigen::Vector3d > & | ref_point | ||
) |
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.
file_path | The path to the YAML file/url to be loaded. |
locator | The locator used to resolve urls and relative file paths. |
std::runtime_error | if 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.
YAML::Node tesseract_common::loadYamlString | ( | const std::string & | yaml_string, |
const ResourceLocator & | locator | ||
) |
Definition at line 100 of file yaml_utils.cpp.
void tesseract_common::ltrim | ( | std::string & | s | ) |
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>
link_name1 | First link name |
link_name2 | Second link name |
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>
pair | The link name pair to load a lexicographically sorted pair of strings |
link_name1 | First link name |
link_name2 | Second link nam |
std::enable_if_t<!std::is_polymorphic<E>::value> tesseract_common::my_rethrow_if_nested | ( | const E & | ) |
std::enable_if_t<std::is_polymorphic<E>::value> tesseract_common::my_rethrow_if_nested | ( | const E & | e | ) |
bool tesseract_common::operator!= | ( | const ProfileDictionary & | lhs, |
const ProfileDictionary & | rhs | ||
) |
Definition at line 68 of file tesseract_common_serialization_unit.cpp.
std::ostream & tesseract_common::operator<< | ( | std::ostream & | os, |
const AllowedCollisionMatrix & | acm | ||
) |
Definition at line 131 of file allowed_collision_matrix.cpp.
bool tesseract_common::operator== | ( | const AllowedCollisionEntries & | entries_1, |
const AllowedCollisionEntries & | entries_2 | ||
) |
Definition at line 42 of file allowed_collision_matrix.cpp.
bool tesseract_common::operator== | ( | const ProfileDictionary & | lhs, |
const ProfileDictionary & | rhs | ||
) |
Definition at line 50 of file tesseract_common_serialization_unit.cpp.
bool tesseract_common::pointersComparison | ( | const std::shared_ptr< T > & | p1, |
const std::shared_ptr< T > & | p2 | ||
) |
bool tesseract_common::pointersEqual | ( | const std::shared_ptr< T > & | p1, |
const std::shared_ptr< T > & | p2 | ||
) |
void tesseract_common::printNestedException | ( | const std::exception & | e, |
int | level = 0 |
||
) |
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.
node | The YAML node to process. |
locator | The locator used to resolve urls and relative file paths. |
!include
directives resolved.std::runtime_error | if 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.
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.
xml_element | The xml attribute to query attribute |
name | The name of the attribute to query |
value | The value to update from the xml attribute |
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.
xml_element | The xml attribute to query attribute |
name | The name of the attribute to query |
value | The value to update from the xml attribute |
int tesseract_common::QueryStringAttribute | ( | const tinyxml2::XMLElement * | xml_element, |
const char * | name, | ||
std::string & | value | ||
) |
Query a string attribute from an xml element.
xml_element | The xml attribute to query attribute |
name | The name of the attribute to query |
value | The value to update from the xml attribute |
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.
xml_element | The xml attribute to query attribute |
name | The name of the attribute to query |
value | The value to update from the xml attribute |
int tesseract_common::QueryStringText | ( | const tinyxml2::XMLElement * | xml_element, |
std::string & | text | ||
) |
int tesseract_common::QueryStringValue | ( | const tinyxml2::XMLAttribute * | xml_attribute, |
std::string & | value | ||
) |
int tesseract_common::QueryStringValue | ( | const tinyxml2::XMLElement * | xml_element, |
std::string & | value | ||
) |
void tesseract_common::reorder | ( | Eigen::Ref< Eigen::VectorXd > | v, |
std::vector< Eigen::Index > | order | ||
) |
void tesseract_common::rtrim | ( | std::string & | s | ) |
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.
values | The values to check |
limits | The limits to perform check |
max_diff | The max diff when comparing value to limit value max(abs(value - limit)) <= max_diff, if true they are considered equal |
max_rel_diff | The 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. |
Definition at line 98 of file kinematic_limits.h.
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.
values | The values to check |
limits | The limits to perform check |
max_diff | The max diff when comparing value to limit value max(abs(value - limit)) <= max_diff, if true they are considered equal |
max_rel_diff | The 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. |
Definition at line 133 of file kinematic_limits.h.
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 | ||
) |
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 | ||
) |
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 | ||
) |
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 | ||
) |
std::string tesseract_common::strFormat | ( | const std::string & | format, |
Args... | args | ||
) |
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.
xml_element | The xml element to attempt to parse attribute |
name | The name of the attribute |
default_value | The default value to return if attribute does not exist |
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
object | Object to be serialized |
typename_string | Prefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension> |
Definition at line 48 of file unit_test_utils.h.
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
object | Base class pointer to the object to be serialized |
typename_string | Prefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension> |
Definition at line 244 of file unit_test_utils.h.
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
object | Base class pointer to the object to be serialized |
typename_string | Prefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension> |
Definition at line 178 of file unit_test_utils.h.
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
object | Object to be serialized |
typename_string | Prefix used for filepaths. Serialized files are put in /tmp/<typename_string>.<extension> |
Definition at line 128 of file unit_test_utils.h.
bool tesseract_common::toNumeric | ( | const std::string & | s, |
FloatType & | value | ||
) |
template bool tesseract_common::toNumeric< double > | ( | const std::string & | , |
double & | |||
) |
template bool tesseract_common::toNumeric< float > | ( | const std::string & | , |
float & | |||
) |
template bool tesseract_common::toNumeric< int > | ( | const std::string & | , |
int & | |||
) |
template bool tesseract_common::toNumeric< long > | ( | const std::string & | , |
long & | |||
) |
std::string tesseract_common::toYAMLString | ( | const YAML::Node & | node | ) |
Converts a YAML::Node to a yaml string.
node | Input node |
Definition at line 135 of file yaml_utils.cpp.
void tesseract_common::trim | ( | std::string & | s | ) |
void tesseract_common::twistChangeBase | ( | Eigen::Ref< Eigen::VectorXd > | twist, |
const Eigen::Isometry3d & | change_base | ||
) |
void tesseract_common::twistChangeRefPoint | ( | Eigen::Ref< Eigen::VectorXd > | twist, |
const Eigen::Ref< const Eigen::Vector3d > & | ref_point | ||
) |
void tesseract_common::writeYamlToFile | ( | const YAML::Node & | node, |
const std::string & | file_path | ||
) |
Writes a YAML::Node to a file.
node | The YAML::Node to write. |
file_path | The path to the output file. |
std::runtime_error | if the file cannot be opened. |
Definition at line 106 of file yaml_utils.cpp.