24#include <Eigen/Geometry>
26#include <SimoxUtility/json.h>
33#include <armarx/control/common/mp/aron/MPConfig.aron.generated.h>
47 using DVec = std::vector<double>;
48 Eigen::VectorXf
getEigenVec(nlohmann::json& userConfig,
49 nlohmann::json& defaultConfig,
50 const std::string& entryName,
57 nlohmann::json& defaultConfig,
58 const std::string& entryName,
61 if (userConfig.find(entryName) != userConfig.end())
63 vec = userConfig[entryName];
67 vec = defaultConfig[entryName];
72 getEigenMatrix(nlohmann::json& userConfig,
const std::string& entryName, Eigen::MatrixXf& mat);
75 Eigen::VectorXf defaultValue,
76 const std::string& entryName);
81 nlohmann::json& defaultConfig,
82 const std::string& entryName)
84 if (userConfig.find(entryName) != userConfig.end())
86 return userConfig[entryName].get<
T>();
90 return defaultConfig[entryName].get<
T>();
98 if (userConfig.find(entryName) != userConfig.end())
100 return userConfig[entryName].get<
T>();
111 const std::string& name,
112 const Eigen::MatrixXd& mat);
114 const std::string& name,
115 const Eigen::MatrixXf& mat);
122 void getError(Eigen::Matrix4f& currentPose,
123 Eigen::Vector3d& targetPosition,
136 void to_json(nlohmann::json& j,
const PoseBasePtr& fp);
138 void from_json(
const nlohmann::json& j, PoseBasePtr& fp);
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);
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);
149 void skew(
const Eigen::Vector3f& vec, Eigen::Ref<Eigen::Matrix3f> result);
161 Eigen::Matrix4f
vec7fToMat4f(
const Eigen::VectorXf& vec);
176 std::vector<float>
mat4ToFVec(
const Eigen::Matrix4f& mat);
180 Eigen::VectorXf
vecToEigen(std::vector<float>& vec);
181 void dvecToEigenf(std::vector<double>& vec, Eigen::VectorXf& result);
183 std::string
sVecToString(
const std::vector<std::string>& vec,
184 const std::string& delimiter =
", ");
186 armarx::control::common::mp::arondto::MPTraj
187 mpTrajFromFile(std::string filename,
bool containsHeader =
true,
bool noTimeStamp =
false);
202 mp::arondto::MPTraj
createDummyTraj(
const int dimension,
const int timesteps = 100);
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>());
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>());
223 const double& canValue,
224 const std::vector<double>& viaPoint);
226 const double& canValue,
227 const std::vector<float>& viaPoint);
229 const double& canValue,
230 const Eigen::VectorXf& viaPoint);
232 void validateTSViaPoint(std::vector<double>& viaPoint, std::vector<double>& viaPointReference);
235 addViaPoint(mp::arondto::MPConfig& cfg,
const double& canValue,
const Eigen::Matrix4f& viaPose);
238 const double canonicalValue,
239 const std::vector<double>& viaPoint);
241 const double canonicalValue,
242 const std::vector<float>& viaPoint);
244 const double canonicalValue,
245 const Eigen::VectorXf& viaPoint);
247 const double canonicalValue,
248 const Eigen::Matrix4f& viaPose);
251 const Eigen::Matrix3f& rotMat2);
255 const Eigen::Matrix4f& desiredPose,
259 const Eigen::Matrix4f& pose1,
260 const Eigen::Matrix4f& pose2,
261 const std::string& namePose1,
262 const std::string& namePose2);
264 const Eigen::Matrix4f& pose2,
265 const std::string& namePose1,
266 const std::string& namePose2,
269 const std::string& who);
Quaternion< double, 0 > Quaterniond
Eigen::Vector4f calculateTransitionWeights(float z1, float z2)
helper functions
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)
void from_json(const nlohmann::json &j, Pose &fp)
Eigen::Matrix4f mirrorLeftRightOri(Eigen::Matrix4f &sourcePose)
Eigen::VectorXf getEigenVec(nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName, int size, int value)
void addViaPoint(mp::arondto::MPConfig &cfg, const double &canValue, const std::vector< double > &viaPoint)
DVec poseToDVec(PosePtr &pose)
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)
Eigen::Matrix3f getOriT(const Eigen::Matrix4f &matrix)
bool poseDeviationTooLarge(const Eigen::Matrix4f ¤tPose, const Eigen::Matrix4f &desiredPose, float positionThrMM, float angleThrDeg)
void getError(Eigen::Matrix4f ¤tPose, Eigen::Vector3d &targetPosition, Eigen::Quaterniond &targetQuaternion, double &posiError, double &oriError)
void setOri(Eigen::Matrix4f &matrix, const Eigen::Ref< const Eigen::Matrix3f > &ori)
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
mp::arondto::MPTraj mpTrajFromFile(std::string filepath, bool containsHeader, bool noTimeStamp)
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)
PosePtr dVecToPose(const DVec &dvec)
float getDeltaAngleBetweenPose(const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2)
Eigen::Block< Eigen::Matrix4f, 3, 3 > getOri(Eigen::Matrix4f &matrix)
Eigen::Matrix4f vec7fToMat4f(const Eigen::VectorXf &vec)
Eigen::Matrix4f dVecToMat4(const DVec &dvec)
create Eigen:Matrix4f from 7D double vector.
void getEigenMatrix(nlohmann::json &userConfig, const std::string &entryName, Eigen::MatrixXf &mat)
T getValueWithDefault(nlohmann::json &userConfig, T defaultValue, const std::string &entryName)
T getValue(nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName)
void validateTSViaPoint(std::vector< double > &viaPoint, std::vector< double > &viaPointReference)
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
std::vector< double > DVec
float getDeltaAngleBetweenRotMat(const Eigen::Matrix3f &rotMat1, const Eigen::Matrix3f &rotMat2)
void setPos(Eigen::Matrix4f &matrix, const Eigen::Ref< const Eigen::Vector3f > &pos)
Eigen::VectorXf vecToEigen(std::vector< float > &vec)
void to_json(nlohmann::json &j, const Pose &fp)
DVec mat4ToDVec(const Eigen::Matrix4f &mat)
convert Eigen:Matrix4f to 7D double vector.
void dvecToEigenf(std::vector< double > &vec, Eigen::VectorXf &result)
Eigen::VectorXf getEigenVecWithDefault(nlohmann::json &userConfig, Eigen::VectorXf defaultValue, const std::string &entryName)
void appendToViapointList(std::vector< mp::arondto::ListViaPoint > &vpList, const double canonicalValue, const std::vector< double > &viaPoint)
Eigen::Matrix4f mirrorLeftRightPose(Eigen::Matrix4f &sourcePose)
void skew(const Eigen::Vector3f &vec, Eigen::Ref< Eigen::Matrix3f > result)
std::vector< float > mat4ToFVec(const Eigen::Matrix4f &mat)
mp::arondto::MPTraj createDummyTraj(const int dimension, const int timesteps)
create a dummy trajectory that only has zeros for every dimension.
void debugEigenMat(StringVariantBaseMap &datafields, const std::string &name, const Eigen::MatrixXd &mat)
std::string sVecToString(const std::vector< std::string > &vec, const std::string &delimiter)
void debugStdVec(StringVariantBaseMap &datafields, const std::string &name, std::vector< float > vec)
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos(Eigen::Matrix4f &matrix)
std::string dVecToString(const DVec &dvec)
std::vector< float > poseToFVec(PosePtr &pose)
std::map< std::string, VariantBasePtr > StringVariantBaseMap
IceInternal::Handle< Pose > PosePtr