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 {
  TSAdmittance, TSImpedance, TSMixedImpedanceVelocity, TSAdmittanceMP,
  TSImpedanceMP, TSMixedImpedanceVelocityMP, QPWholeBodyImpedance, QPWholeBodyVelocity,
  WholeBodyTrajectoryController
}
 

Functions

void debugEigenPose (StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
 
void debugEigenVec (StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
 
Eigen::Matrix4f dVecToMat4 (const mplib::core::DVec &dvec)
 
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)
 
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)
 
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 (Eigen::Matrix4f &mat)
 
std::vector< floatmat4ToFVec (Eigen::Matrix4f &mat)
 
Eigen::VectorXf pdf_gradient (const Eigen::VectorXf &mean, float std, const Eigen::VectorXf &x)
 
mplib::core::DVec poseToDVec (PosePtr &pose)
 
std::vector< floatposeToFVec (PosePtr &pose)
 
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
 

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
TSAdmittance 
TSImpedance 
TSMixedImpedanceVelocity 
TSAdmittanceMP 
TSImpedanceMP 
TSMixedImpedanceVelocityMP 
QPWholeBodyImpedance 
QPWholeBodyVelocity 
WholeBodyTrajectoryController 

Definition at line 29 of file type.h.

Function Documentation

◆ debugEigenPose()

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

Definition at line 103 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 115 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)

Definition at line 187 of file utils.cpp.

+ Here is the caller graph for this function:

◆ dVecToPose()

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

Definition at line 181 of file utils.cpp.

+ Here is the call graph for this function:

◆ dVecToString()

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

Definition at line 258 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 136 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 166 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 174 of file utils.cpp.

+ Here is the call graph for this function:

◆ getEigenMatrix()

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

Definition at line 39 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 13 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 44 of file utils.h.

◆ getEigenVecWithDefault()

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

Definition at line 66 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 84 of file utils.cpp.

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

◆ getValue()

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

Definition at line 68 of file utils.h.

◆ getValueWithDefault()

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

Definition at line 84 of file utils.h.

◆ mat4ToDVec()

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

Definition at line 209 of file utils.cpp.

+ Here is the caller graph for this function:

◆ mat4ToFVec()

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

Definition at line 237 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:

◆ poseToDVec()

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

Definition at line 202 of file utils.cpp.

+ Here is the call graph for this function:

◆ poseToFVec()

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

Definition at line 230 of file utils.cpp.

+ Here is the call graph for this function:

◆ sVecToString()

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

Definition at line 275 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 124 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 157 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 148 of file utils.cpp.

+ Here is the call graph for this function:

◆ vecToEigen()

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

Definition at line 269 of file utils.cpp.

Variable Documentation

◆ ControllerTypeNames

const simox::meta::EnumNames<ControllerType> ControllerTypeNames
inline
Initial value:
{
{ControllerType::TSAdmittance, "NJointTaskspaceAdmittanceController"},
{ControllerType::TSImpedance, "NJointTaskspaceImpedanceController"},
{ControllerType::TSMixedImpedanceVelocity,
"NJointTaskspaceMixedImpedanceVelocityController"},
{ControllerType::TSAdmittanceMP, "NJointTSAdmittanceMPController"},
{ControllerType::TSImpedanceMP, "NJointTSImpedanceMPController"},
{ControllerType::TSMixedImpedanceVelocityMP, "NJointTSMixedImpedanceVelocityMP"},
{ControllerType::WholeBodyTrajectoryController, "NJointWholeBodyTrajectoryController"}}

Definition at line 72 of file type.h.

◆ ControllerTypeShort

const simox::meta::EnumNames<ControllerType> ControllerTypeShort
inline
Initial value:
{
{ControllerType::TSAdmittance, "TSAdmittance"},
{ControllerType::TSImpedance, "TSImpedance"},
{ControllerType::TSMixedImpedanceVelocity, "TSMixedImpedanceVelocity"},
{ControllerType::TSAdmittanceMP, "TSAdmittanceMP"},
{ControllerType::TSImpedanceMP, "TSImpedanceMP"},
{ControllerType::TSMixedImpedanceVelocityMP, "TSMixedImpedanceVelocityMP"},
{ControllerType::QPWholeBodyImpedance, "QPWholeBodyImpedance"},
{ControllerType::QPWholeBodyVelocity, "QPWholeBodyVelocity"},
{ControllerType::WholeBodyTrajectoryController, "WholeBodyTrajectoryController"}}

Definition at line 52 of file type.h.