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 <SimoxUtility/json.h>
26 
27 #include <Eigen/Geometry>
28 #include <mplib/core/types.h>
29 
30 
31 
33 {
34 
35 Eigen::VectorXf getEigenVec(nlohmann::json& userConfig, nlohmann::json& defaultConfig, const std::string& entryName, int size = 0, int value = 0);
36 
37 template <typename T>
38 void getEigenVec(nlohmann::json& userConfig, nlohmann::json& defaultConfig, const std::string& entryName, T& vec)
39 {
40  if (userConfig.find(entryName) != userConfig.end())
41  {
42  vec = userConfig[entryName];
43  }
44  else
45  {
46  vec = defaultConfig[entryName];
47  }
48 }
49 
50 void getEigenMatrix(nlohmann::json& userConfig, const std::string& entryName, Eigen::MatrixXf& mat);
51 
52 Eigen::VectorXf getEigenVecWithDefault(nlohmann::json& userConfig, Eigen::VectorXf defaultValue, const std::string& entryName);
53 
54 template <typename T>
55 T getValue(nlohmann::json& userConfig, nlohmann::json& defaultConfig, const std::string& entryName)
56 {
57  if (userConfig.find(entryName) != userConfig.end())
58  {
59  return userConfig[entryName].get<T>();
60  }
61  else
62  {
63  return defaultConfig[entryName].get<T>();
64  }
65 }
66 
67 template <typename T>
68 T getValueWithDefault(nlohmann::json& userConfig, T defaultValue, const std::string& entryName)
69 {
70  if (userConfig.find(entryName) != userConfig.end())
71  {
72  return userConfig[entryName].get<T>();
73  }
74  else
75  {
76  return defaultValue;
77  }
78 }
79 
80 void debugEigenPose(StringVariantBaseMap& datafields, const std::string& name, Eigen::Matrix4f pose);
81 void debugEigenVec(StringVariantBaseMap& datafields, const std::string& name, Eigen::VectorXf vec);
82 
83 void getError(Eigen::Matrix4f& currentPose, Eigen::Vector3d& targetPosition, Eigen::Quaterniond& targetQuaternion, double& posiError, double& oriError);
84 
85 void to_json(nlohmann::json& j, const Pose& fp);
86 
87 void from_json(const nlohmann::json& j, Pose& fp);
88 
89 void to_json(nlohmann::json& j, const PosePtr& fp);
90 
91 void from_json(const nlohmann::json& j, PosePtr& fp);
92 
93 void to_json(nlohmann::json& j, const PoseBasePtr& fp);
94 
95 void from_json(const nlohmann::json& j, PoseBasePtr& fp);
96 
97 PosePtr dVecToPose(const mplib::core::DVec& dvec);
98 
99 Eigen::Matrix4f dVecToMat4(const mplib::core::DVec& dvec);
100 
101 mplib::core::DVec poseToDVec(PosePtr& pose);
102 
103 mplib::core::DVec mat4ToDVec(Eigen::Matrix4f& mat);
104 
105 std::vector<float> poseToFVec(PosePtr& pose);
106 
107 std::vector<float> mat4ToFVec(Eigen::Matrix4f& mat);
108 
109 std::string dVecToString(const mplib::core::DVec& dvec);
110 
111 Eigen::VectorXf vecToEigen(std::vector<float> &vec);
112 }
armarx::control::common::debugEigenPose
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
Definition: utils.cpp:84
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:208
armarx::control::common::getValueWithDefault
T getValueWithDefault(nlohmann::json &userConfig, T defaultValue, const std::string &entryName)
Definition: utils.h:68
armarx::control::common::getEigenVecWithDefault
Eigen::VectorXf getEigenVecWithDefault(nlohmann::json &userConfig, Eigen::VectorXf defaultValue, const std::string &entryName)
Definition: utils.cpp:56
armarx::control::common::mat4ToDVec
mplib::core::DVec mat4ToDVec(Eigen::Matrix4f &mat)
Definition: utils.cpp:182
Pose.h
armarx::control::common::getError
void getError(Eigen::Matrix4f &currentPose, Eigen::Vector3d &targetPosition, Eigen::Quaterniond &targetQuaternion, double &posiError, double &oriError)
Definition: utils.cpp:70
armarx::control::common::from_json
void from_json(const nlohmann::json &j, Pose &fp)
Definition: utils.cpp:117
armarx::control::common
This file is part of ArmarX.
Definition: aron_conversions.cpp:25
IceInternal::Handle< Pose >
armarx::control::common::poseToFVec
std::vector< float > poseToFVec(PosePtr &pose)
Definition: utils.cpp:202
armarx::control::common::dVecToString
std::string dVecToString(const mplib::core::DVec &dvec)
Definition: utils.cpp:228
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
ManagedIceObject.h
armarx::control::common::poseToDVec
mplib::core::DVec poseToDVec(PosePtr &pose)
Definition: utils.cpp:176
armarx::control::common::dVecToMat4
Eigen::Matrix4f dVecToMat4(const mplib::core::DVec &dvec)
Definition: utils.cpp:162
armarx::control::common::dVecToPose
PosePtr dVecToPose(const mplib::core::DVec &dvec)
Definition: utils.cpp:157
armarx::control::common::debugEigenVec
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Definition: utils.cpp:95
armarx::control::common::vecToEigen
Eigen::VectorXf vecToEigen(std::vector< float > &vec)
Definition: utils.cpp:238
armarx::control::common::getValue
T getValue(nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName)
Definition: utils.h:55
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:103
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:10
Logging.h
T
float T
Definition: UnscentedKalmanFilterTest.cpp:35
armarx::control::common::getEigenMatrix
void getEigenMatrix(nlohmann::json &userConfig, const std::string &entryName, Eigen::MatrixXf &mat)
Definition: utils.cpp:30