tools.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #ifndef EXOTICA_CORE_TOOLS_H_
31 #define EXOTICA_CORE_TOOLS_H_
32 
33 #include <Eigen/Dense>
34 #include <kdl/frames.hpp>
35 #include <string>
36 
42 #include <exotica_core/version.h>
43 
44 #include <std_msgs/ColorRGBA.h>
45 
46 // Forward declarations
47 namespace octomap
48 {
49 class OcTree;
50 }
51 namespace shapes
52 {
53 class Shape;
54 }
55 
59 #define EX_CONC(x, y) x##y
60 #define EX_UNIQ(x, y) EX_CONC(x, y)
61 
62 namespace exotica
63 {
68 std_msgs::ColorRGBA RandomColor();
69 inline std_msgs::ColorRGBA GetColor(double r, double g, double b, double a = 1.0)
70 {
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);
76  return ret;
77 }
78 
79 inline std_msgs::ColorRGBA GetColor(const Eigen::Vector4d& rgba)
80 {
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));
86  return ret;
87 }
88 
95 void LoadOBJ(const std::string& data, Eigen::VectorXi& tri,
96  Eigen::VectorXd& vert);
97 
98 std::shared_ptr<octomap::OcTree> LoadOctree(const std::string& file_path);
99 
100 std::shared_ptr<shapes::Shape> LoadOctreeAsShape(const std::string& file_path);
101 
102 void SaveMatrix(std::string file_name,
103  const Eigen::Ref<const Eigen::MatrixXd> mat);
104 
105 template <typename T>
106 std::vector<std::string> GetKeys(std::map<std::string, T> map)
107 {
108  std::vector<std::string> ret;
109  for (auto& it : map) ret.push_back(it.first);
110  return ret;
111 }
112 
113 std::string GetTypeName(const std::type_info& type);
114 
115 std::string ParsePath(const std::string& path);
116 
117 std::string LoadFile(const std::string& path);
118 
119 bool PathExists(const std::string& path);
120 
124 {
125  ARG0 = 0,
126  ARG1 = 1,
127  ARG2 = 2,
128  ARG3 = 3,
129  ARG4 = 4
130 };
131 } // namespace exotica
132 
133 namespace
134 {
135 template <class SharedPointer>
136 struct Holder
137 {
138  SharedPointer p;
139 
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(); }
144 };
145 } // namespace
146 
147 template <class T>
148 std::shared_ptr<T> ToStdPtr(const boost::shared_ptr<T>& p)
149 {
150  return std::shared_ptr<T>(p.get(), Holder<boost::shared_ptr<T>>(p));
151 }
152 
153 template <class T>
154 std::shared_ptr<T> ToStdPtr(const std::shared_ptr<T>& p)
155 {
156  return p;
157 }
158 
159 #endif // EXOTICA_CORE_TOOLS_H_
bool PathExists(const std::string &path)
Definition: tools.cpp:199
std::shared_ptr< octomap::OcTree > LoadOctree(const std::string &file_path)
Definition: tools.cpp:119
void LoadOBJ(const std::string &data, Eigen::VectorXi &tri, Eigen::VectorXd &vert)
LoadOBJ Loads mesh data from an OBJ file.
Definition: tools.cpp:75
std::vector< std::string > GetKeys(std::map< std::string, T > map)
Definition: tools.h:106
std_msgs::ColorRGBA RandomColor()
RandomColor Generates random opaque color.
Definition: tools.cpp:45
std::string LoadFile(const std::string &path)
Definition: tools.cpp:184
std::shared_ptr< T > ToStdPtr(const boost::shared_ptr< T > &p)
Definition: tools.h:148
std_msgs::ColorRGBA GetColor(const Eigen::Vector4d &rgba)
Definition: tools.h:79
void SaveMatrix(std::string file_name, const Eigen::Ref< const Eigen::MatrixXd > mat)
Definition: tools.cpp:58
ArgumentPosition
Argument position. Used as parameter to refer to an argument.
Definition: tools.h:123
std::string ParsePath(const std::string &path)
Definition: tools.cpp:145
std::shared_ptr< shapes::Shape > LoadOctreeAsShape(const std::string &file_path)
Definition: tools.cpp:126
std::string GetTypeName(const std::type_info &type)
Definition: tools.cpp:133


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:49