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#pragma once
23
24#include <Eigen/Geometry>
25
26#include <SimoxUtility/json.h>
27
30
32
33#include <armarx/control/common/mp/aron/MPConfig.aron.generated.h>
35
36//#include <mplib/core/types.h>
37
39{
40
42 {
43 /// helper functions
44 Eigen::Vector4f calculateTransitionWeights(float z1, float z2);
45 } // namespace control_law::helper
46
47 using DVec = std::vector<double>;
48 Eigen::VectorXf getEigenVec(nlohmann::json& userConfig,
49 nlohmann::json& defaultConfig,
50 const std::string& entryName,
51 int size = 0,
52 int value = 0);
53
54 template <typename T>
55 void
56 getEigenVec(nlohmann::json& userConfig,
57 nlohmann::json& defaultConfig,
58 const std::string& entryName,
59 T& vec)
60 {
61 if (userConfig.find(entryName) != userConfig.end())
62 {
63 vec = userConfig[entryName];
64 }
65 else
66 {
67 vec = defaultConfig[entryName];
68 }
69 }
70
71 void
72 getEigenMatrix(nlohmann::json& userConfig, const std::string& entryName, Eigen::MatrixXf& mat);
73
74 Eigen::VectorXf getEigenVecWithDefault(nlohmann::json& userConfig,
75 Eigen::VectorXf defaultValue,
76 const std::string& entryName);
77
78 template <typename T>
79 T
80 getValue(nlohmann::json& userConfig,
81 nlohmann::json& defaultConfig,
82 const std::string& entryName)
83 {
84 if (userConfig.find(entryName) != userConfig.end())
85 {
86 return userConfig[entryName].get<T>();
87 }
88 else
89 {
90 return defaultConfig[entryName].get<T>();
91 }
92 }
93
94 template <typename T>
95 T
96 getValueWithDefault(nlohmann::json& userConfig, T defaultValue, const std::string& entryName)
97 {
98 if (userConfig.find(entryName) != userConfig.end())
99 {
100 return userConfig[entryName].get<T>();
101 }
102 else
103 {
104 return defaultValue;
105 }
106 }
107
108 void
109 debugEigenPose(StringVariantBaseMap& datafields, const std::string& name, Eigen::Matrix4f pose);
110 void debugEigenMat(StringVariantBaseMap& datafields,
111 const std::string& name,
112 const Eigen::MatrixXd& mat);
113 void debugEigenMat(StringVariantBaseMap& datafields,
114 const std::string& name,
115 const Eigen::MatrixXf& mat);
116 void
117 debugEigenVec(StringVariantBaseMap& datafields, const std::string& name, Eigen::VectorXf vec);
118
119 void
120 debugStdVec(StringVariantBaseMap& datafields, const std::string& name, std::vector<float> vec);
121
122 void getError(Eigen::Matrix4f& currentPose,
123 Eigen::Vector3d& targetPosition,
124 Eigen::Quaterniond& targetQuaternion,
125 double& posiError,
126 double& oriError);
127
128 void to_json(nlohmann::json& j, const Pose& fp);
129
130 void from_json(const nlohmann::json& j, Pose& fp);
131
132 void to_json(nlohmann::json& j, const PosePtr& fp);
133
134 void from_json(const nlohmann::json& j, PosePtr& fp);
135
136 void to_json(nlohmann::json& j, const PoseBasePtr& fp);
137
138 void from_json(const nlohmann::json& j, PoseBasePtr& fp);
139
140 Eigen::Block<Eigen::Matrix4f, 3, 3> getOri(Eigen::Matrix4f& matrix);
141 Eigen::Matrix3f getOri(const Eigen::Matrix4f& matrix);
142 Eigen::Matrix3f getOriT(const Eigen::Matrix4f& matrix);
143 void setOri(Eigen::Matrix4f& matrix, const Eigen::Ref<const Eigen::Matrix3f>& ori);
144
145 Eigen::Block<Eigen::Matrix4f, 3, 1> getPos(Eigen::Matrix4f& matrix);
146 Eigen::Vector3f getPos(const Eigen::Matrix4f& matrix);
147 void setPos(Eigen::Matrix4f& matrix, const Eigen::Ref<const Eigen::Vector3f>& pos);
148
149 void skew(const Eigen::Vector3f& vec, Eigen::Ref<Eigen::Matrix3f> result);
150
151 PosePtr dVecToPose(const DVec& dvec);
152
153 /**
154 * @brief create Eigen:Matrix4f from 7D double vector.
155 * @param dvec [x, y, z, qw, qx, qy, qz] format
156 * @return Eigen::Matrix4f \in SE(3)
157 *
158 * Note that, the order of the quaternion elements follows w, x, y, z format
159 */
160 Eigen::Matrix4f dVecToMat4(const DVec& dvec);
161 Eigen::Matrix4f vec7fToMat4f(const Eigen::VectorXf& vec);
162
163 DVec poseToDVec(PosePtr& pose);
164
165 /**
166 * @brief convert Eigen:Matrix4f to 7D double vector.
167 * @param mat Eigen::Matrix4f \in SE(3)
168 * @return vector of format [x, y, z, qw, qx, qy, qz]
169 *
170 * Note that, the order of the quaternion elements follows w, x, y, z format
171 */
172 DVec mat4ToDVec(const Eigen::Matrix4f& mat);
173
174 std::vector<float> poseToFVec(PosePtr& pose);
175
176 std::vector<float> mat4ToFVec(const Eigen::Matrix4f& mat);
177
178 std::string dVecToString(const DVec& dvec);
179
180 Eigen::VectorXf vecToEigen(std::vector<float>& vec);
181 void dvecToEigenf(std::vector<double>& vec, Eigen::VectorXf& result);
182
183 std::string sVecToString(const std::vector<std::string>& vec,
184 const std::string& delimiter = ", ");
185
186 armarx::control::common::mp::arondto::MPTraj
187 mpTrajFromFile(std::string filename, bool containsHeader = true, bool noTimeStamp = false);
188
189 /**
190 * @brief create a dummy trajectory that only has zeros for every dimension.
191 * @param dimension the dimension of the trajectory, e.g. 7d for taskspace and
192 * Nd for N-joint kinematic chain.
193 * @param timesteps the total number of timesteps in the trajectory
194 * @return the MPTraj instance
195 *
196 * Note that, we you use this to configure MPs and execute it after, you'll have to set
197 * a proper start and goal for it, either set them in the MPListConfig for the corresponding
198 * MP and call startAll(), or use start("MPName", start, goal, duration_second).
199 * Otherwise, the MP will assume the first and last timestep being the start and goal, which
200 * are all zeros and therefore wrong for your task.
201 */
202 mp::arondto::MPTraj createDummyTraj(const int dimension, const int timesteps = 100);
203
204 mp::arondto::MPConfig getDefaultMPConfig(
205 MPType mpType,
206 const std::string& name,
207 const std::string& nodeSetName,
208 const double& durationSec = -1.0,
209 const std::vector<mp::arondto::MPTraj>& mpTraj = std::vector<mp::arondto::MPTraj>(),
210 const std::vector<mp::arondto::ListViaPoint>& viaPointList =
211 std::vector<mp::arondto::ListViaPoint>());
212
213 mp::arondto::MPConfig
215 const std::string& name,
216 const std::string& nodeSetName,
217 const double& durationSec,
218 const std::vector<std::string>& mpTraj = std::vector<std::string>(),
219 const std::vector<mp::arondto::ListViaPoint>& viaPointList =
220 std::vector<mp::arondto::ListViaPoint>());
221
222 void addViaPoint(mp::arondto::MPConfig& cfg,
223 const double& canValue,
224 const std::vector<double>& viaPoint);
225 void addViaPoint(mp::arondto::MPConfig& cfg,
226 const double& canValue,
227 const std::vector<float>& viaPoint);
228 void addViaPoint(mp::arondto::MPConfig& cfg,
229 const double& canValue,
230 const Eigen::VectorXf& viaPoint);
231
232 void validateTSViaPoint(std::vector<double>& viaPoint, std::vector<double>& viaPointReference);
233
234 void
235 addViaPoint(mp::arondto::MPConfig& cfg, const double& canValue, const Eigen::Matrix4f& viaPose);
236
237 void appendToViapointList(std::vector<mp::arondto::ListViaPoint>& vpList,
238 const double canonicalValue,
239 const std::vector<double>& viaPoint);
240 void appendToViapointList(std::vector<mp::arondto::ListViaPoint>& vpList,
241 const double canonicalValue,
242 const std::vector<float>& viaPoint);
243 void appendToViapointList(std::vector<mp::arondto::ListViaPoint>& vpList,
244 const double canonicalValue,
245 const Eigen::VectorXf& viaPoint);
246 void appendToViapointList(std::vector<mp::arondto::ListViaPoint>& vpList,
247 const double canonicalValue,
248 const Eigen::Matrix4f& viaPose);
249
250 float getDeltaAngleBetweenRotMat(const Eigen::Matrix3f& rotMat1,
251 const Eigen::Matrix3f& rotMat2);
252 float getDeltaAngleBetweenPose(const Eigen::Matrix4f& pose1, const Eigen::Matrix4f& pose2);
253
254 bool poseDeviationTooLarge(const Eigen::Matrix4f& currentPose,
255 const Eigen::Matrix4f& desiredPose,
256 float positionThrMM,
257 float angleThrDeg);
258 void reportPoseDeviationWarning(const std::string& who,
259 const Eigen::Matrix4f& pose1,
260 const Eigen::Matrix4f& pose2,
261 const std::string& namePose1,
262 const std::string& namePose2);
263 bool detectAndReportPoseDeviationWarning(const Eigen::Matrix4f& pose1,
264 const Eigen::Matrix4f& pose2,
265 const std::string& namePose1,
266 const std::string& namePose2,
267 float positionThrMM,
268 float angleThrDeg,
269 const std::string& who);
270
271 Eigen::Matrix4f mirrorLeftRightPose(Eigen::Matrix4f& sourcePose);
272 Eigen::Matrix4f mirrorLeftRightOri(Eigen::Matrix4f& sourcePose);
273 Eigen::Matrix3f mirrorLeftRightOri(Eigen::Matrix3f& sourcePose);
274} // namespace armarx::control::common
The Pose class.
Definition Pose.h:243
Quaternion< double, 0 > Quaterniond
Eigen::Vector4f calculateTransitionWeights(float z1, float z2)
helper functions
Definition utils.cpp:25
This file is part of ArmarX.
void reportPoseDeviationWarning(const std::string &who, const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2, const std::string &namePose1, const std::string &namePose2)
Definition utils.cpp:754
void from_json(const nlohmann::json &j, Pose &fp)
Definition utils.cpp:220
Eigen::Matrix4f mirrorLeftRightOri(Eigen::Matrix4f &sourcePose)
Definition utils.cpp:805
Eigen::VectorXf getEigenVec(nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName, int size, int value)
Definition utils.cpp:50
void addViaPoint(mp::arondto::MPConfig &cfg, const double &canValue, const std::vector< double > &viaPoint)
Definition utils.cpp:606
DVec poseToDVec(PosePtr &pose)
Definition utils.cpp:352
bool detectAndReportPoseDeviationWarning(const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2, const std::string &namePose1, const std::string &namePose2, float positionThrMM, float angleThrDeg, const std::string &who)
Definition utils.cpp:773
Eigen::Matrix3f getOriT(const Eigen::Matrix4f &matrix)
Definition utils.cpp:289
bool poseDeviationTooLarge(const Eigen::Matrix4f &currentPose, const Eigen::Matrix4f &desiredPose, float positionThrMM, float angleThrDeg)
Definition utils.cpp:742
void getError(Eigen::Matrix4f &currentPose, Eigen::Vector3d &targetPosition, Eigen::Quaterniond &targetQuaternion, double &posiError, double &oriError)
Definition utils.cpp:121
void setOri(Eigen::Matrix4f &matrix, const Eigen::Ref< const Eigen::Matrix3f > &ori)
Definition utils.cpp:295
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Definition utils.cpp:190
mp::arondto::MPTraj mpTrajFromFile(std::string filepath, bool containsHeader, bool noTimeStamp)
Definition utils.cpp:454
mp::arondto::MPConfig getDefaultMPConfig(MPType mpType, const std::string &name, const std::string &nodeSetName, const double &durationSec, const std::vector< mp::arondto::MPTraj > &mpTraj, const std::vector< mp::arondto::ListViaPoint > &viaPointList)
Definition utils.cpp:556
PosePtr dVecToPose(const DVec &dvec)
Definition utils.cpp:319
float getDeltaAngleBetweenPose(const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2)
Definition utils.cpp:736
Eigen::Block< Eigen::Matrix4f, 3, 3 > getOri(Eigen::Matrix4f &matrix)
Definition utils.cpp:265
Eigen::Matrix4f vec7fToMat4f(const Eigen::VectorXf &vec)
Definition utils.cpp:340
Eigen::Matrix4f dVecToMat4(const DVec &dvec)
create Eigen:Matrix4f from 7D double vector.
Definition utils.cpp:325
void getEigenMatrix(nlohmann::json &userConfig, const std::string &entryName, Eigen::MatrixXf &mat)
Definition utils.cpp:76
T getValueWithDefault(nlohmann::json &userConfig, T defaultValue, const std::string &entryName)
Definition utils.h:96
T getValue(nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName)
Definition utils.h:80
void validateTSViaPoint(std::vector< double > &viaPoint, std::vector< double > &viaPointReference)
Definition utils.cpp:648
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
Definition utils.cpp:140
std::vector< double > DVec
Definition utils.h:47
float getDeltaAngleBetweenRotMat(const Eigen::Matrix3f &rotMat1, const Eigen::Matrix3f &rotMat2)
Definition utils.cpp:725
void setPos(Eigen::Matrix4f &matrix, const Eigen::Ref< const Eigen::Vector3f > &pos)
Definition utils.cpp:307
Eigen::VectorXf vecToEigen(std::vector< float > &vec)
Definition utils.cpp:419
void to_json(nlohmann::json &j, const Pose &fp)
Definition utils.cpp:208
DVec mat4ToDVec(const Eigen::Matrix4f &mat)
convert Eigen:Matrix4f to 7D double vector.
Definition utils.cpp:359
void dvecToEigenf(std::vector< double > &vec, Eigen::VectorXf &result)
Definition utils.cpp:425
Eigen::VectorXf getEigenVecWithDefault(nlohmann::json &userConfig, Eigen::VectorXf defaultValue, const std::string &entryName)
Definition utils.cpp:103
void appendToViapointList(std::vector< mp::arondto::ListViaPoint > &vpList, const double canonicalValue, const std::vector< double > &viaPoint)
Definition utils.cpp:679
Eigen::Matrix4f mirrorLeftRightPose(Eigen::Matrix4f &sourcePose)
Definition utils.cpp:797
void skew(const Eigen::Vector3f &vec, Eigen::Ref< Eigen::Matrix3f > result)
Definition utils.cpp:277
std::vector< float > mat4ToFVec(const Eigen::Matrix4f &mat)
Definition utils.cpp:387
mp::arondto::MPTraj createDummyTraj(const int dimension, const int timesteps)
create a dummy trajectory that only has zeros for every dimension.
Definition utils.cpp:547
void debugEigenMat(StringVariantBaseMap &datafields, const std::string &name, const Eigen::MatrixXd &mat)
Definition utils.cpp:152
std::string sVecToString(const std::vector< std::string > &vec, const std::string &delimiter)
Definition utils.cpp:439
void debugStdVec(StringVariantBaseMap &datafields, const std::string &name, std::vector< float > vec)
Definition utils.cpp:199
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos(Eigen::Matrix4f &matrix)
Definition utils.cpp:301
std::string dVecToString(const DVec &dvec)
Definition utils.cpp:408
std::vector< float > poseToFVec(PosePtr &pose)
Definition utils.cpp:380
std::map< std::string, VariantBasePtr > StringVariantBaseMap
IceInternal::Handle< Pose > PosePtr
Definition Pose.h:306