#include <Eigen/Dense>#include <kdl/frames.hpp>#include <string>#include <exotica_core/tools/conversions.h>#include <exotica_core/tools/exception.h>#include <exotica_core/tools/printable.h>#include <exotica_core/tools/timer.h>#include <exotica_core/tools/uncopyable.h>#include <exotica_core/version.h>#include <std_msgs/ColorRGBA.h>

Go to the source code of this file.
Namespaces | |
| exotica | |
| octomap | |
| shapes | |
Macros | |
| #define | EX_CONC(x, y) x##y |
| A double-wrapper MACRO functionality for generating unique object names: The actual functionality is provided by EX_UNIQ (for 'exotica unique') More... | |
| #define | EX_UNIQ(x, y) EX_CONC(x, y) |
Enumerations | |
| enum | exotica::ArgumentPosition { exotica::ARG0 = 0, exotica::ARG1 = 1, exotica::ARG2 = 2, exotica::ARG3 = 3, exotica::ARG4 = 4 } |
| Argument position. Used as parameter to refer to an argument. More... | |
Functions | |
| std_msgs::ColorRGBA | exotica::GetColor (const Eigen::Vector4d &rgba) |
| std_msgs::ColorRGBA | exotica::GetColor (double r, double g, double b, double a=1.0) |
| template<typename T > | |
| std::vector< std::string > | exotica::GetKeys (std::map< std::string, T > map) |
| std::string | exotica::GetTypeName (const std::type_info &type) |
| std::string | exotica::LoadFile (const std::string &path) |
| void | exotica::LoadOBJ (const std::string &data, Eigen::VectorXi &tri, Eigen::VectorXd &vert) |
| LoadOBJ Loads mesh data from an OBJ file. More... | |
| std::shared_ptr< octomap::OcTree > | exotica::LoadOctree (const std::string &file_path) |
| std::shared_ptr< shapes::Shape > | exotica::LoadOctreeAsShape (const std::string &file_path) |
| std::string | exotica::ParsePath (const std::string &path) |
| bool | exotica::PathExists (const std::string &path) |
| std_msgs::ColorRGBA | exotica::RandomColor () |
| RandomColor Generates random opaque color. More... | |
| void | exotica::SaveMatrix (std::string file_name, const Eigen::Ref< const Eigen::MatrixXd > mat) |
| template<class T > | |
| std::shared_ptr< T > | ToStdPtr (const boost::shared_ptr< T > &p) |
| template<class T > | |
| std::shared_ptr< T > | ToStdPtr (const std::shared_ptr< T > &p) |
| std::shared_ptr<T> ToStdPtr | ( | const boost::shared_ptr< T > & | p | ) |