TaskspaceImpedanceController.cpp
Go to the documentation of this file.
2 
3 #include <SimoxUtility/math/convert/mat4f_to_quat.h>
4 #include <VirtualRobot/MathTools.h>
5 
7 
9 
10 #include "../utils.h"
11 
13 {
14 
15  void
16  TaskspaceImpedanceController::initialize(const VirtualRobot::RobotNodeSetPtr& rns,
17  const VirtualRobot::RobotNodeSetPtr& rtRns)
18  {
20  tcp = rns->getTCP();
21  rtTCP = rtRns->getTCP();
23  ik.reset(new VirtualRobot::DifferentialIK(
24  rtRns, rtRns->getRobot()->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
25 
26  numOfJoints = rns->getSize();
28  }
29 
30  void
31  TaskspaceImpedanceController::preactivateInit(const VirtualRobot::RobotNodeSetPtr& rns)
32  {
33  }
34 
35  void
37  {
38  ftsensor.reset();
39  }
40 
41  // void
42  // TaskspaceImpedanceController::updateFT(const FTConfig& c, RtStatus& rtStatus)
43  // {
44  // /// run in rt thread
45  // ftsensor.updateStatus();
46  // if (c.reCalibrate)
47  // {
48  // ftsensor.calibrated.store(false);
49  // /// TODO how to toggle recalibration?
50  // }
51  // ftsensor.compensateTCPGravity(c);
52  // if (!ftsensor.calibrated.load())
53  // {
54  // if (ftsensor.calibrate(c, rtStatus.deltaT))
55  // {
56  // ftsensor.calibrated.store(true);
57  // }
58  // }
59  // else
60  // {
61  // rtStatus.currentForceTorque = ftsensor.getFilteredForceTorque(c);
62  // }
63  // }
64 
65  void
67  {
68  /// run in rt thread
69  rtStatus.currentPose = rtTCP->getPoseInRootFrame();
70 
71  /// ---------------------------- safety guard by FT and target pose ------------------------
72  rtStatus.poseDiffMatImp =
73  c.desiredPose.block<3, 3>(0, 0) * rtStatus.currentPose.block<3, 3>(0, 0).transpose();
74  rtStatus.oriDiffAngleAxis.fromRotationMatrix(rtStatus.poseDiffMatImp);
75 
76  /// this should not be moved to non rt, just in case non rt thread dies, rt still functions as safely
77  if (not ftsensor.isSafe(c.ftConfig))
78  {
79  ARMARX_INFO << "FTGuard indicates RT not safe";
80  c.desiredPose = rtStatus.desiredPose;
81  rtStatus.rtSafe = false;
82  rtStatus.rtTargetSafe = true;
83  }
84  else if ((c.desiredPose.block<3, 1>(0, 3) - rtStatus.currentPose.block<3, 1>(0, 3)).norm() >
85  c.safeDistanceMMToGoal or
86  std::fminf(rtStatus.oriDiffAngleAxis.angle(),
87  2 * M_PI - rtStatus.oriDiffAngleAxis.angle()) >
88  VirtualRobot::MathTools::deg2rad(c.safeRotAngleDegreeToGoal))
89  {
90  c.desiredPose = rtStatus.desiredPose;
91  rtStatus.rtSafe = false;
92  rtStatus.rtTargetSafe = false;
93  }
94  else
95  {
96  rtStatus.desiredPose = c.desiredPose;
97  rtStatus.rtSafe = true;
98  rtStatus.rtTargetSafe = true;
99  }
100 
101  /// ------------------------------ compute jacobi ------------------------------------------
102  rtStatus.jacobi =
103  ik->getJacobianMatrix(rtTCP, VirtualRobot::IKSolver::CartesianSelection::All);
104  rtStatus.jacobi.block(0, 0, 3, rtStatus.numJoints) =
105  0.001 * rtStatus.jacobi.block(0, 0, 3, rtStatus.numJoints);
106  ARMARX_CHECK_EQUAL(rtStatus.numJoints, rtStatus.jacobi.cols());
107  ARMARX_CHECK_EQUAL(6, rtStatus.jacobi.rows());
108 
109  rtStatus.jtpinv =
110  ik->computePseudoInverseJacobianMatrix(rtStatus.jacobi.transpose(), lambda);
111  ARMARX_CHECK_EQUAL(rtStatus.numJoints, rtStatus.jtpinv.cols());
112  ARMARX_CHECK_EQUAL(6, rtStatus.jtpinv.rows());
113 
114  /// ------------------------------ update velocity/twist -----------------------------------
115  ARMARX_CHECK_EQUAL(rtStatus.numJoints, rtStatus.jointPos.rows());
116  ARMARX_CHECK_EQUAL(rtStatus.numJoints, rtStatus.jointVel.rows());
117  ARMARX_CHECK_EQUAL(rtStatus.numJoints, rtStatus.qvelFiltered.rows());
118 
119  rtStatus.qvelFiltered =
120  (1 - c.qvelFilter) * rtStatus.qvelFiltered + c.qvelFilter * rtStatus.jointVel;
121  rtStatus.currentTwist = rtStatus.jacobi * rtStatus.qvelFiltered;
122 
123  /// ------------------------------------- Impedance control --------------------------------
124  /// calculate pose error between target pose and current pose
125  /// !!! This is very important: you have to keep postion and orientation both
126  /// with UI unit (meter, radian) to calculate impedance force.
127 
128  rtStatus.poseDiffMatImp = rtStatus.desiredPose.block<3, 3>(0, 0) *
129  rtStatus.currentPose.block<3, 3>(0, 0).transpose();
130  rtStatus.poseErrorImp.head(3) = 0.001 * (rtStatus.desiredPose.block<3, 1>(0, 3) -
131  rtStatus.currentPose.block<3, 1>(0, 3));
132  rtStatus.poseErrorImp.tail(3) =
133  VirtualRobot::MathTools::eigen3f2rpy(rtStatus.poseDiffMatImp);
134 
135  rtStatus.forceImpedance = c.kpImpedance.cwiseProduct(rtStatus.poseErrorImp) -
136  c.kdImpedance.cwiseProduct(rtStatus.currentTwist);
137 
138  /// ----------------------------- Nullspace PD Control -------------------------------------
139  ARMARX_CHECK_EQUAL(rtStatus.numJoints, c.kpNullspace.rows());
140  ARMARX_CHECK_EQUAL(rtStatus.numJoints, rtStatus.nullspaceTorque.rows());
141  ARMARX_CHECK_EQUAL(rtStatus.numJoints, c.desiredNullspaceJointAngles.value().size());
142  rtStatus.nullspaceTorque =
143  c.kpNullspace.cwiseProduct(c.desiredNullspaceJointAngles.value() - rtStatus.jointPos) -
144  c.kdNullspace.cwiseProduct(rtStatus.qvelFiltered);
145 
146  /// ----------------------------- Map TS target force to JS --------------------------------
147  ARMARX_CHECK_EQUAL(rtStatus.numJoints, rtStatus.desiredJointTorques.rows());
148  rtStatus.desiredJointTorques =
149  rtStatus.jacobi.transpose() * rtStatus.forceImpedance +
150  (I - rtStatus.jacobi.transpose() * rtStatus.jtpinv) * rtStatus.nullspaceTorque;
151 
152  /// ----------------------------- write torque target -------------------------------------
153  for (int i = 0; i < rtStatus.desiredJointTorques.rows(); ++i)
154  {
155  rtStatus.desiredJointTorques(i) =
156  std::clamp(rtStatus.desiredJointTorques(i), -c.torqueLimit, c.torqueLimit);
157  }
158  }
159 
160  void
162  {
163  /// This function can be called before the RT thread.
164  /// base
165  jointPosition.resize(nDoF, 0.);
166  jointVelocity.resize(nDoF, 0.);
167  jointTorque.resize(nDoF, 0.);
168  jointPos.setZero(nDoF);
169  jointVel.setZero(nDoF);
170  jointTor.setZero(nDoF);
171  deltaT = 0.0;
172  numJoints = nDoF;
173 
174  /// targets
175  desiredJointTorques.setZero(nDoF);
176  nullspaceTorque.setZero(nDoF);
177 
178  /// force torque
179  currentForceTorque.setZero();
180 
181  /// task space variables
182  forceImpedance.setZero();
183 
184  /// current status
185  qvelFiltered.setZero(nDoF);
186  currentPose.setZero();
187  currentTwist.setZero();
188  desiredPose.setZero();
189 
190  /// intermediate results
191  poseDiffMatImp.setZero();
192  poseErrorImp.setZero();
194 
195  /// others
196  jacobi.setZero(6, nDoF);
197  jtpinv.setZero(6, nDoF);
198  rtSafe = false;
199  rtTargetSafe = true;
200  }
201 
202  void
204  {
205  /// !!!! TO BE UPDATED IN PREACTIVATE !!!!
206  /// only then the up-to-date robot joint information is available
207  currentPose = currentTCPPose;
208  desiredPose = currentTCPPose;
209  }
210 
211 } // namespace armarx::control::common::control_law
armarx::control::common::control_law::RobotStatus::jointTor
Eigen::VectorXf jointTor
Definition: common.h:37
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::jacobi
Eigen::MatrixXf jacobi
others
Definition: TaskspaceImpedanceController.h:72
armarx::control::common::ft::FTSensor::isSafe
bool isSafe(const FTConfig &c)
Definition: FTSensor.cpp:192
armarx::control::common::control_law::TaskspaceImpedanceController::ftsensor
common::ft::FTSensor ftsensor
Definition: TaskspaceImpedanceController.h:94
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::forceImpedance
Eigen::Vector6f forceImpedance
task space variables
Definition: TaskspaceImpedanceController.h:58
TaskspaceImpedanceController.h
armarx::control::common::control_law::RobotStatus::jointTorque
std::vector< float > jointTorque
Definition: common.h:34
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::desiredPose
Eigen::Matrix4f desiredPose
Definition: TaskspaceImpedanceController.h:64
ARMARX_CHECK_NOT_NULL
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
Definition: ExpressionException.h:206
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::oriDiffAngleAxis
Eigen::AngleAxisf oriDiffAngleAxis
Definition: TaskspaceImpedanceController.h:69
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::desiredJointTorques
Eigen::VectorXf desiredJointTorques
targets
Definition: TaskspaceImpedanceController.h:51
armarx::control::common::control_law::RobotStatus::jointPos
Eigen::VectorXf jointPos
Definition: common.h:35
armarx::control::common::control_law::TaskspaceImpedanceController::numOfJoints
unsigned int numOfJoints
Definition: TaskspaceImpedanceController.h:81
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::control::common::control_law::RobotStatus::jointVelocity
std::vector< float > jointVelocity
Definition: common.h:33
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::reset
void reset(const unsigned int nDoF)
Definition: TaskspaceImpedanceController.cpp:161
armarx::control::common::control_law::TaskspaceImpedanceController::preactivateInit
void preactivateInit(const VirtualRobot::RobotNodeSetPtr &rns)
Definition: TaskspaceImpedanceController.cpp:31
device.h
clamp
double clamp(double x, double a, double b)
Definition: point.hpp:125
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::jtpinv
Eigen::MatrixXf jtpinv
Definition: TaskspaceImpedanceController.h:73
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::currentForceTorque
Eigen::Vector6f currentForceTorque
force torque
Definition: TaskspaceImpedanceController.h:55
armarx::control::common::control_law::TaskspaceImpedanceController::initialize
void initialize(const VirtualRobot::RobotNodeSetPtr &rns, const VirtualRobot::RobotNodeSetPtr &rtRns)
Definition: TaskspaceImpedanceController.cpp:16
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
M_PI
#define M_PI
Definition: MathTools.h:17
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::qvelFiltered
Eigen::VectorXf qvelFiltered
current status
Definition: TaskspaceImpedanceController.h:61
armarx::control::common::control_law::TaskspaceImpedanceController::run
void run(Config &c, RtStatus &robotStatus)
Definition: TaskspaceImpedanceController.cpp:66
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::currentTwist
Eigen::Vector6f currentTwist
Definition: TaskspaceImpedanceController.h:63
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::rtPreActivate
void rtPreActivate(const Eigen::Matrix4f &currentPose)
Definition: TaskspaceImpedanceController.cpp:203
armarx::control::common::control_law::RobotStatus::jointVel
Eigen::VectorXf jointVel
Definition: common.h:36
armarx::control::common::control_law
This file is part of ArmarX.
Definition: aron_conversions.cpp:68
armarx::control::common::ft::FTSensor::reset
void reset()
Definition: FTSensor.cpp:87
armarx::control::common::control_law::TaskspaceImpedanceController::rtTCP
VirtualRobot::RobotNodePtr rtTCP
Definition: TaskspaceImpedanceController.h:93
armarx::control::common::control_law::RobotStatus::jointPosition
std::vector< float > jointPosition
Definition: common.h:32
for
for(;yybottom<=yytop;yybottom++)
Definition: Grammar.cpp:790
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::rtSafe
bool rtSafe
Definition: TaskspaceImpedanceController.h:74
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::poseDiffMatImp
Eigen::Matrix3f poseDiffMatImp
intermediate results
Definition: TaskspaceImpedanceController.h:67
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::currentPose
Eigen::Matrix4f currentPose
Definition: TaskspaceImpedanceController.h:62
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::rtTargetSafe
bool rtTargetSafe
Definition: TaskspaceImpedanceController.h:75
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::nullspaceTorque
Eigen::VectorXf nullspaceTorque
Definition: TaskspaceImpedanceController.h:52
armarx::control::common::control_law::TaskspaceImpedanceController::Config
common::control_law::arondto::TaskspaceImpedanceControllerConfig Config
Definition: TaskspaceImpedanceController.h:44
armarx::control::common::control_law::TaskspaceImpedanceController::tcp
VirtualRobot::RobotNodePtr tcp
Definition: TaskspaceImpedanceController.h:92
ControlThreadOutputBuffer.h
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus::poseErrorImp
Eigen::Vector6f poseErrorImp
Definition: TaskspaceImpedanceController.h:68
armarx::control::common::control_law::TaskspaceImpedanceController::firstRun
void firstRun()
Definition: TaskspaceImpedanceController.cpp:36
ARMARX_CHECK_EQUAL
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
Definition: ExpressionException.h:130
armarx::control::common::control_law::TaskspaceImpedanceController::RtStatus
internal status of the controller, containing intermediate variables, mutable targets
Definition: TaskspaceImpedanceController.h:48
armarx::transpose
std::vector< std::vector< T > > transpose(const std::vector< std::vector< T >> &src, Thrower thrower)
Definition: SimoxCSpace.cpp:706
armarx::control::common::control_law::RobotStatus::numJoints
unsigned int numJoints
Definition: common.h:39
armarx::control::common::control_law::RobotStatus::deltaT
double deltaT
Definition: common.h:38