Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TOOLS_H_
31 #define EXOTICA_CORE_TOOLS_H_
33 #include <Eigen/Dense>
34 #include <kdl/frames.hpp>
44 #include <std_msgs/ColorRGBA.h>
59 #define EX_CONC(x, y) x##y
60 #define EX_UNIQ(x, y) EX_CONC(x, y)
69 inline std_msgs::ColorRGBA
GetColor(
double r,
double g,
double b,
double a = 1.0)
71 std_msgs::ColorRGBA ret;
72 ret.r =
static_cast<float>(
r);
73 ret.g =
static_cast<float>(g);
74 ret.b =
static_cast<float>(b);
75 ret.a =
static_cast<float>(a);
79 inline std_msgs::ColorRGBA
GetColor(
const Eigen::Vector4d& rgba)
81 std_msgs::ColorRGBA ret;
82 ret.r =
static_cast<float>(rgba(0));
83 ret.g =
static_cast<float>(rgba(1));
84 ret.b =
static_cast<float>(rgba(2));
85 ret.a =
static_cast<float>(rgba(3));
95 void LoadOBJ(
const std::string& data, Eigen::VectorXi& tri,
96 Eigen::VectorXd& vert);
98 std::shared_ptr<octomap::OcTree>
LoadOctree(
const std::string& file_path);
103 const Eigen::Ref<const Eigen::MatrixXd> mat);
105 template <
typename T>
106 std::vector<std::string>
GetKeys(std::map<std::string, T> map)
108 std::vector<std::string> ret;
109 for (
auto& it : map) ret.push_back(it.first);
113 std::string
GetTypeName(
const std::type_info& type);
115 std::string
ParsePath(
const std::string& path);
117 std::string
LoadFile(
const std::string& path);
135 template <
class SharedPo
inter>
140 Holder(
const SharedPointer& p) : p(p) {}
141 Holder(
const Holder& other) : p(other.p) {}
142 Holder(Holder&& other) : p(
std::move(other.p)) {}
143 void operator()(...) { p.reset(); }
154 std::shared_ptr<T>
ToStdPtr(
const std::shared_ptr<T>& p)
159 #endif // EXOTICA_CORE_TOOLS_H_
void LoadOBJ(const std::string &data, Eigen::VectorXi &tri, Eigen::VectorXd &vert)
LoadOBJ Loads mesh data from an OBJ file.
std_msgs::ColorRGBA GetColor(double r, double g, double b, double a=1.0)
std::vector< std::string > GetKeys(std::map< std::string, T > map)
std_msgs::ColorRGBA RandomColor()
RandomColor Generates random opaque color.
std::string LoadFile(const std::string &path)
void SaveMatrix(std::string file_name, const Eigen::Ref< const Eigen::MatrixXd > mat)
ArgumentPosition
Argument position. Used as parameter to refer to an argument.
std::string ParsePath(const std::string &path)
std::shared_ptr< shapes::Shape > LoadOctreeAsShape(const std::string &file_path)
std::shared_ptr< octomap::OcTree > LoadOctree(const std::string &file_path)
bool PathExists(const std::string &path)
std::string GetTypeName(const std::type_info &type)
exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02