Namespaces | Functions | Variables
utils.h File Reference

Common Tesseract Utility Functions. More...

#include <tesseract_common/macros.h>
#include <array>
#include <vector>
#include <set>
#include <string>
#include <sstream>
#include <stdexcept>
#include <random>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <tesseract_common/allowed_collision_matrix.h>
#include <filesystem>
Include dependency graph for utils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 tesseract_common
 
 tinyxml2
 

Functions

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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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]. More...
 
Eigen::VectorXd tesseract_common::calcTransformError (const Eigen::Isometry3d &t1, const Eigen::Isometry3d &t2)
 Calculate error between two transforms expressed in t1 coordinate system. More...
 
Eigen::Vector4d tesseract_common::computeRandomColor ()
 This computes a random color RGBA [0, 1] with alpha set to 1. More...
 
Eigen::VectorXd tesseract_common::concat (const Eigen::VectorXd &a, const Eigen::VectorXd &b)
 Concatenate two vector. More...
 
std::string tesseract_common::fileToString (const std::filesystem::path &filepath)
 Read in the contents of the file into a string. More...
 
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. More...
 
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. More...
 
std::string tesseract_common::getTempPath ()
 Get the host temp directory path. More...
 
std::string tesseract_common::getTimestampString ()
 Get Timestamp string. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
bool tesseract_common::isNumeric (const std::string &s)
 Determine if a string is a number. More...
 
bool tesseract_common::isNumeric (const std::vector< std::string > &sv)
 Determine if each string in vector is a number. More...
 
void tesseract_common::jacobianChangeBase (Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Isometry3d &change_base)
 Change the base coordinate system of the jacobian. More...
 
void tesseract_common::jacobianChangeRefPoint (Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Ref< const Eigen::Vector3d > &ref_point)
 Change the reference point of the jacobian. More...
 
void tesseract_common::ltrim (std::string &s)
 Left trim string. More...
 
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. More...
 
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 ==. More...
 
void tesseract_common::printNestedException (const std::exception &e, int level=0)
 Print a nested exception. More...
 
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. More...
 
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. More...
 
int tesseract_common::QueryStringAttribute (const tinyxml2::XMLElement *xml_element, const char *name, std::string &value)
 Query a string attribute from an xml element. More...
 
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. More...
 
int tesseract_common::QueryStringText (const tinyxml2::XMLElement *xml_element, std::string &text)
 Query a string Text from xml element. More...
 
int tesseract_common::QueryStringValue (const tinyxml2::XMLAttribute *xml_attribute, std::string &value)
 Query a string value from xml attribute. More...
 
int tesseract_common::QueryStringValue (const tinyxml2::XMLElement *xml_element, std::string &value)
 Query a string value from xml element. More...
 
void tesseract_common::reorder (Eigen::Ref< Eigen::VectorXd > v, std::vector< Eigen::Index > order)
 Reorder Eigen::VectorXd implace given index list. More...
 
void tesseract_common::rtrim (std::string &s)
 Right trim string. More...
 
template<typename... Args>
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. More...
 
template<typename FloatType >
bool tesseract_common::toNumeric (const std::string &s, FloatType &value)
 Convert a string to a numeric value type. More...
 
void tesseract_common::trim (std::string &s)
 Trim left and right of string. More...
 
void tesseract_common::twistChangeBase (Eigen::Ref< Eigen::VectorXd > twist, const Eigen::Isometry3d &change_base)
 Change the base coordinate system of the Twist. More...
 
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. More...
 

Variables

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

Detailed Description

Common Tesseract Utility Functions.

Author
Levi Armstrong
Date
January 18, 2018
Version
TODO
Bug:
No known bugs
License
Software License Agreement (Apache License)
Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Definition in file utils.h.



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