armarx::control::common Namespace Reference

This file is part of ArmarX. More...

Namespaces

 control_law
 This file is part of ArmarX.
 
 ft
 This file is part of ArmarX.
 
 mp
 This file is part of ArmarX.
 

Classes

class  MultivariateNormal
 
struct  SensorDevicesForNJointTorqueController
 

Enumerations

enum  ControllerType {
  TSAdm, TSImp, TSImpSafe, TSImpCol,
  TSAdmCol, TSMixImpVel, TSVel, TSMixImpVelCol,
  TSMPAdm, TSMPImp, TSMPImpCol, TSMPImpSafe,
  TSMPMixImpVel, TSMPVel, TSMPMixImpVelCol, QPWholeBodyImpedance,
  QPWholeBodyVelocity, WholeBodyTrajectoryController
}
 
enum  MPStatus {
  reset, trained, running, paused,
  finished
}
 
enum  MPType { taskspace, nullsapce, hand }
 

Functions

void addViaPoint (mp::arondto::MPConfig &cfg, const double &canValue, const Eigen::Matrix4f &viaPose)
 
void addViaPoint (mp::arondto::MPConfig &cfg, const double &canValue, const Eigen::VectorXf &viaPoint)
 
void addViaPoint (mp::arondto::MPConfig &cfg, const double &canValue, const std::vector< double > &viaPoint)
 
void addViaPoint (mp::arondto::MPConfig &cfg, const double &canValue, const std::vector< float > &viaPoint)
 
void appendToViapointList (std::vector< mp::arondto::ListViaPoint > &vpList, const double canonicalValue, const Eigen::Matrix4f &viaPose)
 
void appendToViapointList (std::vector< mp::arondto::ListViaPoint > &vpList, const double canonicalValue, const Eigen::VectorXf &viaPoint)
 
void appendToViapointList (std::vector< mp::arondto::ListViaPoint > &vpList, const double canonicalValue, const std::vector< double > &viaPoint)
 
void appendToViapointList (std::vector< mp::arondto::ListViaPoint > &vpList, const double canonicalValue, const std::vector< float > &viaPoint)
 
mp::arondto::MPTraj createDummyTraj (const int dimension, const int timesteps=100)
 create a dummy trajectory that only has zeros for every dimension. More...
 
void debugEigenPose (StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
 
void debugEigenVec (StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
 
void debugStdVec (StringVariantBaseMap &datafields, const std::string &name, std::vector< float > vec)
 
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::Matrix4f dVecToMat4 (const mplib::core::DVec &dvec)
 create Eigen:Matrix4f from 7D double vector. More...
 
PosePtr dVecToPose (const mplib::core::DVec &dvec)
 
std::string dVecToString (const mplib::core::DVec &dvec)
 
void from_json (const nlohmann::json &j, Pose &fp)
 
void from_json (const nlohmann::json &j, PoseBasePtr &fp)
 
void from_json (const nlohmann::json &j, PosePtr &fp)
 
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)
 
mp::arondto::MPConfig getDefaultMPConfig (MPType mpType, const std::string &name, const std::string &nodeSetName, const double &durationSec, const std::vector< std::string > &mpTraj, const std::vector< mp::arondto::ListViaPoint > &viaPointList)
 
float getDeltaAngleBetweenPose (const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2)
 
float getDeltaAngleBetweenRotMat (const Eigen::Matrix3f &rotMat1, const Eigen::Matrix3f &rotMat2)
 
void getEigenMatrix (nlohmann::json &userConfig, const std::string &entryName, Eigen::MatrixXf &mat)
 
Eigen::VectorXf getEigenVec (nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName, int size, int value)
 
template<typename T >
void getEigenVec (nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName, T &vec)
 
Eigen::VectorXf getEigenVecWithDefault (nlohmann::json &userConfig, Eigen::VectorXf defaultValue, const std::string &entryName)
 
void getError (Eigen::Matrix4f &currentPose, Eigen::Vector3d &targetPosition, Eigen::Quaterniond &targetQuaternion, double &posiError, double &oriError)
 
Eigen::Block< Eigen::Matrix4f, 3, 3 > getOri (Eigen::Matrix4f &matrix)
 
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos (Eigen::Matrix4f &matrix)
 
template<typename T >
T getValue (nlohmann::json &userConfig, nlohmann::json &defaultConfig, const std::string &entryName)
 
template<typename T >
T getValueWithDefault (nlohmann::json &userConfig, T defaultValue, const std::string &entryName)
 
mplib::core::DVec mat4ToDVec (const Eigen::Matrix4f &mat)
 convert Eigen:Matrix4f to 7D double vector. More...
 
std::vector< floatmat4ToFVec (const Eigen::Matrix4f &mat)
 
Eigen::Matrix3f mirrorLeftRightOri (Eigen::Matrix3f &sourcePose)
 
Eigen::Matrix4f mirrorLeftRightOri (Eigen::Matrix4f &sourcePose)
 
Eigen::Matrix4f mirrorLeftRightPose (Eigen::Matrix4f &sourcePose)
 
mp::arondto::MPTraj mpTrajFromFile (std::string filepath, bool containsHeader, bool noTimeStamp)
 
Eigen::VectorXf pdf_gradient (const Eigen::VectorXf &mean, float std, const Eigen::VectorXf &x)
 
bool poseDeviationTooLarge (const Eigen::Matrix4f &currentPose, const Eigen::Matrix4f &desiredPose, float positionThrMM, float angleThrDeg)
 
mplib::core::DVec poseToDVec (PosePtr &pose)
 
std::vector< floatposeToFVec (PosePtr &pose)
 
void reportPoseDeviationWarning (const std::string &who, const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2, const std::string &namePose1, const std::string &namePose2)
 
std::string sVecToString (const std::vector< std::string > &vec, const std::string &delimiter)
 
void to_json (nlohmann::json &j, const Pose &fp)
 
void to_json (nlohmann::json &j, const PoseBasePtr &fp)
 
void to_json (nlohmann::json &j, const PosePtr &fp)
 
Eigen::VectorXf vecToEigen (std::vector< float > &vec)
 

Variables

const simox::meta::EnumNames< ControllerTypeControllerTypeNames
 
const simox::meta::EnumNames< ControllerTypeControllerTypeShort
 
const simox::meta::EnumNames< MPTypempTypeToString
 

Detailed Description

This file is part of ArmarX.

ArmarX is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License version 2 as published by the Free Software Foundation.

ArmarX is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Jianfeng Gao ( jianfeng dot gao at kit dot edu )
Date
2022

Enumeration Type Documentation

◆ ControllerType

enum ControllerType
strong
Enumerator
TSAdm 
TSImp 
TSImpSafe 
TSImpCol 
TSAdmCol 
TSMixImpVel 
TSVel 
TSMixImpVelCol 
TSMPAdm 
TSMPImp 
TSMPImpCol 
TSMPImpSafe 
TSMPMixImpVel 
TSMPVel 
TSMPMixImpVelCol 
QPWholeBodyImpedance 
QPWholeBodyVelocity 
WholeBodyTrajectoryController 

Definition at line 29 of file type.h.

◆ MPStatus

enum MPStatus
strong
Enumerator
reset 
trained 
running 
paused 
finished 

Definition at line 71 of file type.h.

◆ MPType

enum MPType
strong
Enumerator
taskspace 
nullsapce 
hand 

Definition at line 59 of file type.h.

Function Documentation

◆ addViaPoint() [1/4]

void addViaPoint ( mp::arondto::MPConfig &  cfg,
const double &  canValue,
const Eigen::Matrix4f &  viaPose 
)

Definition at line 498 of file utils.cpp.

+ Here is the call graph for this function:

◆ addViaPoint() [2/4]

void addViaPoint ( mp::arondto::MPConfig &  cfg,
const double &  canValue,
const Eigen::VectorXf &  viaPoint 
)

Definition at line 487 of file utils.cpp.

+ Here is the call graph for this function:

◆ addViaPoint() [3/4]

void addViaPoint ( mp::arondto::MPConfig &  cfg,
const double &  canValue,
const std::vector< double > &  viaPoint 
)

Definition at line 463 of file utils.cpp.

+ Here is the caller graph for this function:

◆ addViaPoint() [4/4]

void addViaPoint ( mp::arondto::MPConfig &  cfg,
const double &  canValue,
const std::vector< float > &  viaPoint 
)

Definition at line 474 of file utils.cpp.

+ Here is the call graph for this function:

◆ appendToViapointList() [1/4]

void appendToViapointList ( std::vector< mp::arondto::ListViaPoint > &  vpList,
const double  canonicalValue,
const Eigen::Matrix4f &  viaPose 
)

Definition at line 542 of file utils.cpp.

+ Here is the call graph for this function:

◆ appendToViapointList() [2/4]

void appendToViapointList ( std::vector< mp::arondto::ListViaPoint > &  vpList,
const double  canonicalValue,
const Eigen::VectorXf &  viaPoint 
)

Definition at line 529 of file utils.cpp.

+ Here is the call graph for this function:

◆ appendToViapointList() [3/4]

void appendToViapointList ( std::vector< mp::arondto::ListViaPoint > &  vpList,
const double  canonicalValue,
const std::vector< double > &  viaPoint 
)

Definition at line 505 of file utils.cpp.

+ Here is the caller graph for this function:

◆ appendToViapointList() [4/4]

void appendToViapointList ( std::vector< mp::arondto::ListViaPoint > &  vpList,
const double  canonicalValue,
const std::vector< float > &  viaPoint 
)

Definition at line 516 of file utils.cpp.

+ Here is the call graph for this function:

◆ createDummyTraj()

mp::arondto::MPTraj createDummyTraj ( const int  dimension,
const int  timesteps = 100 
)

create a dummy trajectory that only has zeros for every dimension.

Parameters
dimensionthe dimension of the trajectory, e.g. 7d for taskspace and Nd for N-joint kinematic chain.
timestepsthe total number of timesteps in the trajectory
Returns
the MPTraj instance

Note that, we you use this to configure MPs and execute it after, you'll have to set a proper start and goal for it, either set them in the MPListConfig for the corresponding MP and call startAll(), or use start("MPName", start, goal, duration_second). Otherwise, the MP will assume the first and last timestep being the start and goal, which are all zeros and therefore wrong for your task.

Definition at line 414 of file utils.cpp.

◆ debugEigenPose()

void debugEigenPose ( StringVariantBaseMap datafields,
const std::string &  name,
Eigen::Matrix4f  pose 
)

Definition at line 113 of file utils.cpp.

+ Here is the caller graph for this function:

◆ debugEigenVec()

void debugEigenVec ( StringVariantBaseMap datafields,
const std::string &  name,
Eigen::VectorXf  vec 
)

Definition at line 125 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ debugStdVec()

void debugStdVec ( StringVariantBaseMap datafields,
const std::string &  name,
std::vector< float vec 
)

Definition at line 134 of file utils.cpp.

+ Here is the call graph for this function:

◆ detectAndReportPoseDeviationWarning()

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 at line 600 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ dVecToMat4()

Eigen::Matrix4f dVecToMat4 ( const mplib::core::DVec &  dvec)

create Eigen:Matrix4f from 7D double vector.

Parameters
dvec[x, y, z, qw, qx, qy, qz] format
Returns
Eigen::Matrix4f \in SE(3)

Note that, the order of the quaternion elements follows w, x, y, z format

Definition at line 218 of file utils.cpp.

+ Here is the caller graph for this function:

◆ dVecToPose()

PosePtr dVecToPose ( const mplib::core::DVec &  dvec)

Definition at line 212 of file utils.cpp.

+ Here is the call graph for this function:

◆ dVecToString()

std::string dVecToString ( const mplib::core::DVec &  dvec)

Definition at line 289 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ from_json() [1/3]

void from_json ( const nlohmann::json &  j,
Pose fp 
)

Definition at line 155 of file utils.cpp.

+ Here is the caller graph for this function:

◆ from_json() [2/3]

void from_json ( const nlohmann::json &  j,
PoseBasePtr &  fp 
)

Definition at line 185 of file utils.cpp.

+ Here is the call graph for this function:

◆ from_json() [3/3]

void from_json ( const nlohmann::json &  j,
PosePtr fp 
)

Definition at line 193 of file utils.cpp.

+ Here is the call graph for this function:

◆ getDefaultMPConfig() [1/2]

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 at line 423 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getDefaultMPConfig() [2/2]

mp::arondto::MPConfig getDefaultMPConfig ( MPType  mpType,
const std::string &  name,
const std::string &  nodeSetName,
const double &  durationSec,
const std::vector< std::string > &  mpTraj,
const std::vector< mp::arondto::ListViaPoint > &  viaPointList 
)

Definition at line 447 of file utils.cpp.

+ Here is the call graph for this function:

◆ getDeltaAngleBetweenPose()

float getDeltaAngleBetweenPose ( const Eigen::Matrix4f &  pose1,
const Eigen::Matrix4f &  pose2 
)

Definition at line 563 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getDeltaAngleBetweenRotMat()

float getDeltaAngleBetweenRotMat ( const Eigen::Matrix3f &  rotMat1,
const Eigen::Matrix3f &  rotMat2 
)

Definition at line 551 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getEigenMatrix()

void getEigenMatrix ( nlohmann::json &  userConfig,
const std::string &  entryName,
Eigen::MatrixXf &  mat 
)

Definition at line 49 of file utils.cpp.

◆ getEigenVec() [1/2]

Eigen::VectorXf getEigenVec ( nlohmann::json &  userConfig,
nlohmann::json &  defaultConfig,
const std::string &  entryName,
int  size,
int  value 
)

Definition at line 23 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getEigenVec() [2/2]

void armarx::control::common::getEigenVec ( nlohmann::json &  userConfig,
nlohmann::json &  defaultConfig,
const std::string &  entryName,
T vec 
)

Definition at line 47 of file utils.h.

◆ getEigenVecWithDefault()

Eigen::VectorXf getEigenVecWithDefault ( nlohmann::json &  userConfig,
Eigen::VectorXf  defaultValue,
const std::string &  entryName 
)

Definition at line 76 of file utils.cpp.

+ Here is the caller graph for this function:

◆ getError()

void getError ( Eigen::Matrix4f &  currentPose,
Eigen::Vector3d &  targetPosition,
Eigen::Quaterniond targetQuaternion,
double &  posiError,
double &  oriError 
)

Definition at line 94 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getOri()

Eigen::Block< Eigen::Matrix4f, 3, 3 > getOri ( Eigen::Matrix4f &  matrix)

Definition at line 200 of file utils.cpp.

◆ getPos()

Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos ( Eigen::Matrix4f &  matrix)

Definition at line 206 of file utils.cpp.

◆ getValue()

T armarx::control::common::getValue ( nlohmann::json &  userConfig,
nlohmann::json &  defaultConfig,
const std::string &  entryName 
)

Definition at line 71 of file utils.h.

◆ getValueWithDefault()

T armarx::control::common::getValueWithDefault ( nlohmann::json &  userConfig,
T  defaultValue,
const std::string &  entryName 
)

Definition at line 87 of file utils.h.

◆ mat4ToDVec()

mplib::core::DVec mat4ToDVec ( const Eigen::Matrix4f &  mat)

convert Eigen:Matrix4f to 7D double vector.

Parameters
matEigen::Matrix4f \in SE(3)
Returns
vector of format [x, y, z, qw, qx, qy, qz]

Note that, the order of the quaternion elements follows w, x, y, z format

Definition at line 240 of file utils.cpp.

+ Here is the caller graph for this function:

◆ mat4ToFVec()

std::vector< float > mat4ToFVec ( const Eigen::Matrix4f &  mat)

Definition at line 268 of file utils.cpp.

+ Here is the caller graph for this function:

◆ mirrorLeftRightOri() [1/2]

Eigen::Matrix3f mirrorLeftRightOri ( Eigen::Matrix3f &  sourcePose)

Definition at line 635 of file utils.cpp.

+ Here is the call graph for this function:

◆ mirrorLeftRightOri() [2/2]

Eigen::Matrix4f mirrorLeftRightOri ( Eigen::Matrix4f &  sourcePose)

Definition at line 628 of file utils.cpp.

+ Here is the call graph for this function:

◆ mirrorLeftRightPose()

Eigen::Matrix4f mirrorLeftRightPose ( Eigen::Matrix4f &  sourcePose)

Definition at line 621 of file utils.cpp.

+ Here is the call graph for this function:

◆ mpTrajFromFile()

armarx::control::common::mp::arondto::MPTraj mpTrajFromFile ( std::string  filepath,
bool  containsHeader,
bool  noTimeStamp 
)

Definition at line 321 of file utils.cpp.

+ Here is the caller graph for this function:

◆ pdf_gradient()

Eigen::VectorXf pdf_gradient ( const Eigen::VectorXf &  mean,
float  std,
const Eigen::VectorXf &  x 
)

Definition at line 64 of file math.cpp.

+ Here is the call graph for this function:

◆ poseDeviationTooLarge()

bool poseDeviationTooLarge ( const Eigen::Matrix4f &  currentPose,
const Eigen::Matrix4f &  desiredPose,
float  positionThrMM,
float  angleThrDeg 
)

Definition at line 570 of file utils.cpp.

+ Here is the call graph for this function:

◆ poseToDVec()

mplib::core::DVec poseToDVec ( PosePtr pose)

Definition at line 233 of file utils.cpp.

+ Here is the call graph for this function:

◆ poseToFVec()

std::vector< float > poseToFVec ( PosePtr pose)

Definition at line 261 of file utils.cpp.

+ Here is the call graph for this function:

◆ reportPoseDeviationWarning()

void reportPoseDeviationWarning ( const std::string &  who,
const Eigen::Matrix4f &  pose1,
const Eigen::Matrix4f &  pose2,
const std::string &  namePose1,
const std::string &  namePose2 
)

Definition at line 581 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ sVecToString()

std::string sVecToString ( const std::vector< std::string > &  vec,
const std::string &  delimiter 
)

Definition at line 306 of file utils.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ to_json() [1/3]

void to_json ( nlohmann::json &  j,
const Pose fp 
)

Definition at line 143 of file utils.cpp.

+ Here is the caller graph for this function:

◆ to_json() [2/3]

void to_json ( nlohmann::json &  j,
const PoseBasePtr &  fp 
)

Definition at line 176 of file utils.cpp.

+ Here is the call graph for this function:

◆ to_json() [3/3]

void to_json ( nlohmann::json &  j,
const PosePtr fp 
)

Definition at line 167 of file utils.cpp.

+ Here is the call graph for this function:

◆ vecToEigen()

Eigen::VectorXf vecToEigen ( std::vector< float > &  vec)

Definition at line 300 of file utils.cpp.

Variable Documentation

◆ ControllerTypeNames

const simox::meta::EnumNames<ControllerType> ControllerTypeNames
inline
Initial value:
{
{ControllerType::TSAdm, "NJointTaskspaceAdmittanceController"},
{ControllerType::TSImp, "NJointTaskspaceImpedanceController"},
{ControllerType::TSImpSafe, "NJointTaskspaceSafetyImpedanceController"},
{ControllerType::TSImpCol, "NJointTaskspaceCollisionAvoidanceImpedanceController"},
{ControllerType::TSMixImpVel, "NJointTaskspaceMixedImpedanceVelocityController"},
{ControllerType::TSVel, "NJointTaskspaceVelocityController"},
{ControllerType::TSMixImpVelCol,
"NJointTaskspaceCollisionAvoidanceMixedImpedanceVelocityController"},
{ControllerType::TSMPAdm, "NJointTSAdmittanceMPController"},
{ControllerType::TSMPImp, "NJointTSImpedanceMPController"},
{ControllerType::TSMPImpCol, "NJointTSCollisionAvoidanceImpedanceMPController"},
{ControllerType::TSMPImpSafe, "NJointTSSafetyImpedanceMPController"},
{ControllerType::TSMPMixImpVel, "NJointTSMixedImpedanceVelocityMPController"},
{ControllerType::TSMPVel, "NJointTSVelocityMPController"},
{ControllerType::TSMPMixImpVelCol, "NJointTSCollisionAvoidanceMixedImpedanceVelocityMP"},
{ControllerType::WholeBodyTrajectoryController, "NJointWholeBodyTrajectoryController"}}

Definition at line 110 of file type.h.

◆ ControllerTypeShort

const simox::meta::EnumNames<ControllerType> ControllerTypeShort
inline
Initial value:
{
{ControllerType::TSAdm, "TSAdm"},
{ControllerType::TSImp, "TSImp"},
{ControllerType::TSImpSafe, "TSImpSafe"},
{ControllerType::TSImpCol, "TSImpCol"},
{ControllerType::TSMixImpVel, "TSMixImpVel"},
{ControllerType::TSVel, "TSVel"},
{ControllerType::TSMixImpVelCol, "TSMixImpVelCol"},
{ControllerType::TSMPAdm, "TSMPAdm"},
{ControllerType::TSMPImp, "TSMPImp"},
{ControllerType::TSMPImpCol, "TSMPImpCol"},
{ControllerType::TSMPImpSafe, "TSMPImpSafe"},
{ControllerType::TSMPMixImpVel, "TSMPMixImpVel"},
{ControllerType::TSMPVel, "TSMPVel"},
{ControllerType::TSMPMixImpVelCol, "TSMPMixImpVelCol"},
{ControllerType::QPWholeBodyImpedance, "QPWholeBodyImpedance"},
{ControllerType::QPWholeBodyVelocity, "QPWholeBodyVelocity"},
{ControllerType::WholeBodyTrajectoryController, "WholeBodyTrajectoryController"}}

Definition at line 84 of file type.h.

◆ mpTypeToString

const simox::meta::EnumNames<MPType> mpTypeToString
inline
Initial value:
= {{MPType::taskspace, "taskspace"},
{MPType::nullsapce, "nullspace"},
{MPType::hand, "hand"}}

Definition at line 80 of file type.h.