armarx::control::common Namespace Reference

This file is part of ArmarX. More...

Namespaces

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

Classes

class  MultivariateNormal
 
struct  SensorDevicesForNJointTorqueController
 

Typedefs

using DVec = std::vector<double>
 

Enumerations

enum class  ControllerType {
  TSAdm , TSImp , TSVel , TSMixImpVel ,
  TSImpCol , TSAdmCol , TSVelCol , TSVeloCol ,
  TSMixImpVelCol , TSMPAdm , TSMPImp , TSMPVel ,
  TSMPMixImpVel , TSMPImpCol , TSMPVelCol , TSMPVeloCol ,
  TSMPMixImpVelCol , TSMPVelWiping , TSMPImpWiping , TSMPMixImpVelColWiping ,
  QPWholeBodyImpedance , QPWholeBodyVelocity , WholeBodyTrajectoryController , ZMQTSVel ,
  ZMQTSImp , ZMQTSImpCol , ZMQTSMixImpVel , ZMQTSMixImpVelCol ,
  ZenohTSVel , ZenohTSImp , ZenohTSImpCol , ZenohTSMixImpVel ,
  ZenohTSMixImpVelCol , SharedMemoryTSVel , SharedMemoryTSVelCol , SharedMemoryTSVeloCol ,
  SharedMemoryTSImp , SharedMemoryTSImpCol , SharedMemoryTSMixImpVel , SharedMemoryTSMixImpVelCol
}
 
enum class  MPStatus {
  reset , trained , running , paused ,
  finished
}
 
enum class  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.
 
void debugEigenMat (StringVariantBaseMap &datafields, const std::string &name, const Eigen::MatrixXd &mat)
 
void debugEigenMat (StringVariantBaseMap &datafields, const std::string &name, const Eigen::MatrixXf &mat)
 
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)
 
void dvecToEigenf (std::vector< double > &vec, Eigen::VectorXf &result)
 
Eigen::Matrix4f dVecToMat4 (const DVec &dvec)
 create Eigen:Matrix4f from 7D double vector.
 
PosePtr dVecToPose (const DVec &dvec)
 
std::string dVecToString (const 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::Matrix3f getOri (const Eigen::Matrix4f &matrix)
 
Eigen::Block< Eigen::Matrix4f, 3, 3 > getOri (Eigen::Matrix4f &matrix)
 
Eigen::Matrix3f getOriT (const Eigen::Matrix4f &matrix)
 
Eigen::Vector3f getPos (const 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)
 
DVec mat4ToDVec (const Eigen::Matrix4f &mat)
 convert Eigen:Matrix4f to 7D double vector.
 
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)
 
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)
 
void setOri (Eigen::Matrix4f &matrix, const Eigen::Ref< const Eigen::Matrix3f > &ori)
 
void setPos (Eigen::Matrix4f &matrix, const Eigen::Ref< const Eigen::Vector3f > &pos)
 
void skew (const Eigen::Vector3f &vec, Eigen::Ref< Eigen::Matrix3f > result)
 
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)
 
void validateTSViaPoint (std::vector< double > &viaPoint, std::vector< double > &viaPointReference)
 
Eigen::Matrix4f vec7fToMat4f (const Eigen::VectorXf &vec)
 
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

Typedef Documentation

◆ DVec

using DVec = std::vector<double>

Definition at line 47 of file utils.h.

Enumeration Type Documentation

◆ ControllerType

enum class ControllerType
strong
Enumerator
TSAdm 
TSImp 
TSVel 
TSMixImpVel 
TSImpCol 
TSAdmCol 
TSVelCol 
TSVeloCol 
TSMixImpVelCol 
TSMPAdm 
TSMPImp 
TSMPVel 
TSMPMixImpVel 
TSMPImpCol 
TSMPVelCol 
TSMPVeloCol 
TSMPMixImpVelCol 
TSMPVelWiping 
TSMPImpWiping 
TSMPMixImpVelColWiping 
QPWholeBodyImpedance 
QPWholeBodyVelocity 
WholeBodyTrajectoryController 
ZMQTSVel 
ZMQTSImp 
ZMQTSImpCol 
ZMQTSMixImpVel 
ZMQTSMixImpVelCol 
ZenohTSVel 
ZenohTSImp 
ZenohTSImpCol 
ZenohTSMixImpVel 
ZenohTSMixImpVelCol 
SharedMemoryTSVel 
SharedMemoryTSVelCol 
SharedMemoryTSVeloCol 
SharedMemoryTSImp 
SharedMemoryTSImpCol 
SharedMemoryTSMixImpVel 
SharedMemoryTSMixImpVelCol 

Definition at line 29 of file type.h.

◆ MPStatus

enum class MPStatus
strong
Enumerator
reset 
trained 
running 
paused 
finished 

Definition at line 103 of file type.h.

◆ MPType

enum class MPType
strong
Enumerator
taskspace 
nullsapce 
hand 

Definition at line 91 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 641 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 630 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 606 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 617 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 716 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 703 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 679 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 690 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 547 of file utils.cpp.

◆ debugEigenMat() [1/2]

void debugEigenMat ( StringVariantBaseMap & datafields,
const std::string & name,
const Eigen::MatrixXd & mat )

Definition at line 152 of file utils.cpp.

+ Here is the caller graph for this function:

◆ debugEigenMat() [2/2]

void debugEigenMat ( StringVariantBaseMap & datafields,
const std::string & name,
const Eigen::MatrixXf & mat )

Definition at line 171 of file utils.cpp.

◆ debugEigenPose()

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

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

+ Here is the caller graph for this function:

◆ debugStdVec()

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

Definition at line 199 of file utils.cpp.

◆ 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 773 of file utils.cpp.

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

◆ dvecToEigenf()

void dvecToEigenf ( std::vector< double > & vec,
Eigen::VectorXf & result )

Definition at line 425 of file utils.cpp.

◆ dVecToMat4()

Eigen::Matrix4f dVecToMat4 ( const 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 325 of file utils.cpp.

+ Here is the caller graph for this function:

◆ dVecToPose()

PosePtr dVecToPose ( const DVec & dvec)

Definition at line 319 of file utils.cpp.

+ Here is the call graph for this function:

◆ dVecToString()

std::string dVecToString ( const DVec & dvec)

Definition at line 408 of file utils.cpp.

+ Here is the caller graph for this function:

◆ from_json() [1/3]

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

Definition at line 220 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 250 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 258 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 556 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 590 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 736 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 725 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 76 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 50 of file utils.cpp.

+ Here is the caller graph for this function:

◆ getEigenVec() [2/2]

template<typename T>
void getEigenVec ( nlohmann::json & userConfig,
nlohmann::json & defaultConfig,
const std::string & entryName,
T & vec )

Definition at line 56 of file utils.h.

◆ getEigenVecWithDefault()

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

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

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

◆ getOri() [1/2]

Eigen::Matrix3f getOri ( const Eigen::Matrix4f & matrix)

Definition at line 271 of file utils.cpp.

◆ getOri() [2/2]

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

Definition at line 265 of file utils.cpp.

+ Here is the caller graph for this function:

◆ getOriT()

Eigen::Matrix3f getOriT ( const Eigen::Matrix4f & matrix)

Definition at line 289 of file utils.cpp.

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

◆ getPos() [1/2]

Eigen::Vector3f getPos ( const Eigen::Matrix4f & matrix)

Definition at line 313 of file utils.cpp.

◆ getPos() [2/2]

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

Definition at line 301 of file utils.cpp.

+ Here is the caller graph for this function:

◆ getValue()

template<typename T>
T getValue ( nlohmann::json & userConfig,
nlohmann::json & defaultConfig,
const std::string & entryName )

Definition at line 80 of file utils.h.

+ Here is the caller graph for this function:

◆ getValueWithDefault()

template<typename T>
T getValueWithDefault ( nlohmann::json & userConfig,
T defaultValue,
const std::string & entryName )

Definition at line 96 of file utils.h.

+ Here is the caller graph for this function:

◆ mat4ToDVec()

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 359 of file utils.cpp.

+ Here is the caller graph for this function:

◆ mat4ToFVec()

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

Definition at line 387 of file utils.cpp.

+ Here is the caller graph for this function:

◆ mirrorLeftRightOri() [1/2]

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

Definition at line 813 of file utils.cpp.

+ Here is the call graph for this function:

◆ mirrorLeftRightOri() [2/2]

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

Definition at line 805 of file utils.cpp.

+ Here is the call graph for this function:

◆ mirrorLeftRightPose()

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

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

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

◆ poseToDVec()

DVec poseToDVec ( PosePtr & pose)

Definition at line 352 of file utils.cpp.

+ Here is the call graph for this function:

◆ poseToFVec()

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

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

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

◆ setOri()

void setOri ( Eigen::Matrix4f & matrix,
const Eigen::Ref< const Eigen::Matrix3f > & ori )

Definition at line 295 of file utils.cpp.

+ Here is the caller graph for this function:

◆ setPos()

void setPos ( Eigen::Matrix4f & matrix,
const Eigen::Ref< const Eigen::Vector3f > & pos )

Definition at line 307 of file utils.cpp.

+ Here is the caller graph for this function:

◆ skew()

void skew ( const Eigen::Vector3f & vec,
Eigen::Ref< Eigen::Matrix3f > result )

Definition at line 277 of file utils.cpp.

+ 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 439 of file utils.cpp.

+ Here is the caller graph for this function:

◆ to_json() [1/3]

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

Definition at line 208 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 241 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 232 of file utils.cpp.

+ Here is the call graph for this function:

◆ validateTSViaPoint()

void validateTSViaPoint ( std::vector< double > & viaPoint,
std::vector< double > & viaPointReference )

Definition at line 648 of file utils.cpp.

+ Here is the caller graph for this function:

◆ vec7fToMat4f()

Eigen::Matrix4f vec7fToMat4f ( const Eigen::VectorXf & vec)

Definition at line 340 of file utils.cpp.

+ Here is the caller graph for this function:

◆ vecToEigen()

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

Definition at line 419 of file utils.cpp.

Variable Documentation

◆ ControllerTypeNames

const simox::meta::EnumNames<ControllerType> ControllerTypeNames
inline

Definition at line 170 of file type.h.

◆ ControllerTypeShort

const simox::meta::EnumNames<ControllerType> ControllerTypeShort
inline

Definition at line 116 of file type.h.

◆ mpTypeToString

const simox::meta::EnumNames<MPType> mpTypeToString
inline
Initial value:

Definition at line 112 of file type.h.