utils.h
Go to the documentation of this file.
1 /**
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @author Jianfeng Gao ( jianfeng dot gao at kit dot edu )
17  * @date 2022
18  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
19  * GNU General Public License
20  */
21 
22 #include <Eigen/Geometry>
23 
24 #include <SimoxUtility/json.h>
25 
28 
30 
31 #include <mplib/core/types.h>
32 
34 {
35 
36  Eigen::VectorXf getEigenVec(nlohmann::json& userConfig,
37  nlohmann::json& defaultConfig,
38  const std::string& entryName,
39  int size = 0,
40  int value = 0);
41 
42  template <typename T>
43  void
44  getEigenVec(nlohmann::json& userConfig,
45  nlohmann::json& defaultConfig,
46  const std::string& entryName,
47  T& vec)
48  {
49  if (userConfig.find(entryName) != userConfig.end())
50  {
51  vec = userConfig[entryName];
52  }
53  else
54  {
55  vec = defaultConfig[entryName];
56  }
57  }
58 
59  void
60  getEigenMatrix(nlohmann::json& userConfig, const std::string& entryName, Eigen::MatrixXf& mat);
61 
62  Eigen::VectorXf getEigenVecWithDefault(nlohmann::json& userConfig,
63  Eigen::VectorXf defaultValue,
64  const std::string& entryName);
65 
66  template <typename T>
67  T
68  getValue(nlohmann::json& userConfig,
69  nlohmann::json& defaultConfig,
70  const std::string& entryName)
71  {
72  if (userConfig.find(entryName) != userConfig.end())
73  {
74  return userConfig[entryName].get<T>();
75  }
76  else
77  {
78  return defaultConfig[entryName].get<T>();
79  }
80  }
81 
82  template <typename T>
83  T
84  getValueWithDefault(nlohmann::json& userConfig, T defaultValue, const std::string& entryName)
85  {
86  if (userConfig.find(entryName) != userConfig.end())
87  {
88  return userConfig[entryName].get<T>();
89  }
90  else
91  {
92  return defaultValue;
93  }
94  }
95 
96  void
97  debugEigenPose(StringVariantBaseMap& datafields, const std::string& name, Eigen::Matrix4f pose);
98  void
99  debugEigenVec(StringVariantBaseMap& datafields, const std::string& name, Eigen::VectorXf vec);
100 
101  void getError(Eigen::Matrix4f& currentPose,
102  Eigen::Vector3d& targetPosition,
103  Eigen::Quaterniond& targetQuaternion,
104  double& posiError,
105  double& oriError);
106 
107  void to_json(nlohmann::json& j, const Pose& fp);
108 
109  void from_json(const nlohmann::json& j, Pose& fp);
110 
111  void to_json(nlohmann::json& j, const PosePtr& fp);
112 
113  void from_json(const nlohmann::json& j, PosePtr& fp);
114 
115  void to_json(nlohmann::json& j, const PoseBasePtr& fp);
116 
117  void from_json(const nlohmann::json& j, PoseBasePtr& fp);
118 
119  PosePtr dVecToPose(const mplib::core::DVec& dvec);
120 
122 
124 
126 
127  std::vector<float> poseToFVec(PosePtr& pose);
128 
129  std::vector<float> mat4ToFVec(Eigen::Matrix4f& mat);
130 
131  std::string dVecToString(const mplib::core::DVec& dvec);
132 
133  Eigen::VectorXf vecToEigen(std::vector<float>& vec);
134 
135  std::string sVecToString(const std::vector<std::string>& vec,
136  const std::string& delimiter = ", ");
137 } // namespace armarx::control::common
armarx::control::common::debugEigenPose
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
Definition: utils.cpp:103
armarx::StringVariantBaseMap
std::map< std::string, VariantBasePtr > StringVariantBaseMap
Definition: ManagedIceObject.h:111
armarx::control::common::mat4ToFVec
std::vector< float > mat4ToFVec(Eigen::Matrix4f &mat)
Definition: utils.cpp:237
armarx::control::common::getValueWithDefault
T getValueWithDefault(nlohmann::json &userConfig, T defaultValue, const std::string &entryName)
Definition: utils.h:84
armarx::control::common::getEigenVecWithDefault
Eigen::VectorXf getEigenVecWithDefault(nlohmann::json &userConfig, Eigen::VectorXf defaultValue, const std::string &entryName)
Definition: utils.cpp:66
armarx::control::common::mat4ToDVec
mplib::core::DVec mat4ToDVec(Eigen::Matrix4f &mat)
Definition: utils.cpp:209
Pose.h
armarx::control::common::getError
void getError(Eigen::Matrix4f &currentPose, Eigen::Vector3d &targetPosition, Eigen::Quaterniond &targetQuaternion, double &posiError, double &oriError)
Definition: utils.cpp:84
armarx::control::common::from_json
void from_json(const nlohmann::json &j, Pose &fp)
Definition: utils.cpp:136
armarx::control::common
This file is part of ArmarX.
Definition: aron_conversions.cpp:29
IceInternal::Handle< Pose >
armarx::control::common::poseToFVec
std::vector< float > poseToFVec(PosePtr &pose)
Definition: utils.cpp:230
armarx::control::common::dVecToString
std::string dVecToString(const mplib::core::DVec &dvec)
Definition: utils.cpp:258
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
ManagedIceObject.h
armarx::control::common::mp::DVec
Ice::DoubleSeq DVec
Definition: MP.h:46
armarx::control::common::poseToDVec
mplib::core::DVec poseToDVec(PosePtr &pose)
Definition: utils.cpp:202
armarx::control::common::dVecToMat4
Eigen::Matrix4f dVecToMat4(const mplib::core::DVec &dvec)
Definition: utils.cpp:187
armarx::control::common::dVecToPose
PosePtr dVecToPose(const mplib::core::DVec &dvec)
Definition: utils.cpp:181
armarx::control::common::debugEigenVec
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Definition: utils.cpp:115
armarx::control::common::vecToEigen
Eigen::VectorXf vecToEigen(std::vector< float > &vec)
Definition: utils.cpp:269
armarx::control::common::getValue
T getValue(nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName)
Definition: utils.h:68
armarx::Pose
The Pose class.
Definition: Pose.h:242
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::control::common::to_json
void to_json(nlohmann::json &j, const Pose &fp)
Definition: utils.cpp:124
Eigen::Quaterniond
Quaternion< double, 0 > Quaterniond
Definition: EigenForwardDeclarations.h:62
armarx::control::common::getEigenVec
Eigen::VectorXf getEigenVec(nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName, int size, int value)
Definition: utils.cpp:13
Logging.h
T
float T
Definition: UnscentedKalmanFilterTest.cpp:35
armarx::control::common::sVecToString
std::string sVecToString(const std::vector< std::string > &vec, const std::string &delimiter)
Definition: utils.cpp:275
armarx::control::common::getEigenMatrix
void getEigenMatrix(nlohmann::json &userConfig, const std::string &entryName, Eigen::MatrixXf &mat)
Definition: utils.cpp:39