TaskspaceVelocityController.cpp
Go to the documentation of this file.
2
3#include <SimoxUtility/math/convert/mat4f_to_quat.h>
4#include <VirtualRobot/IK/DifferentialIK.h>
5#include <VirtualRobot/IK/JacobiProvider.h>
6#include <VirtualRobot/MathTools.h>
7#include <VirtualRobot/Nodes/RobotNode.h>
8#include <VirtualRobot/Robot.h>
9#include <VirtualRobot/RobotNodeSet.h>
10
12
14
15#include "../utils.h"
16
18{
19
20 void
21 TaskspaceVelocityController::initialize(const VirtualRobot::RobotNodeSetPtr& rns,
22 const VirtualRobot::RobotNodeSetPtr& rtRns)
23 {
25 // auto numOfJoints = rns->getSize();
26
27 tcp = rns->getTCP();
28 rtTCP = rtRns->getTCP();
30 ik.reset(new VirtualRobot::DifferentialIK(
31 rtRns, rtRns->getRobot()->getRootNode(), VirtualRobot::JacobiProvider::eSVDDampedDynamic));
32
33 // I = Eigen::MatrixXf::Identity(numOfJoints, numOfJoints);
34 }
35
36 void
37 TaskspaceVelocityController::preactivateInit(const VirtualRobot::RobotNodeSetPtr& rns)
38 {
39 }
40
41 void
46
47 // bool
48 // TaskspaceVelocityController::isControlModeValid(
49 // const std::vector<std::string>& nameList,
50 // const std::map<std::string, std::string>& jointControlModeMap)
51 // {
52 // std::set<std::string> validModes = {"velocity", "torque"};
53 //
54 // for (const auto& pair : jointControlModeMap)
55 // {
56 // if (std::find(nameList.begin(), nameList.end(), pair.first) == nameList.end())
57 // {
58 // ARMARX_ERROR << "TaskspaceVelocityController: joint name '"
59 // << pair.first << "' not found in robot node set.";
60 // return false;
61 // }
62 //
63 // if (validModes.find(pair.second) == validModes.end())
64 // {
65 // ARMARX_ERROR
66 // << "TaskspaceVelocityController: Invalid control mode for joint '"
67 // << pair.first << "': " << pair.second << std::endl;
68 // return false;
69 // }
70 // }
71 //
72 // return true;
73 // }
74
75 // void
76 // TaskspaceVelocityController::updateFT(const FTConfig& c, RtStatus& rtStatus)
77 // {
78 // /// run in rt thread
79 // ftsensor.updateStatus();
80 // if (c.reCalibrate)
81 // {
82 // ftsensor.calibrated.store(false);
83 // /// TODO how to toggle recalibration?
84 // }
85 // ftsensor.compensateTCPGravity(c);
86 // if (!ftsensor.calibrated.load())
87 // {
88 // if (ftsensor.calibrate(c, rtStatus.deltaT))
89 // {
90 // ftsensor.calibrated.store(true);
91 // }
92 // }
93 // else
94 // {
95 // rtStatus.currentForceTorque = ftsensor.getFilteredForceTorque(c);
96 // }
97 // }
98
99 void
101 {
102 /// run in rt thread
103 rtStatus.currentPose = rtTCP->getPoseInRootFrame();
104
105 /// ---------------------------- safety guard by FT and target pose ------------------------
106 rtStatus.poseDiffMatImp =
107 c.desiredPose.block<3, 3>(0, 0) * rtStatus.currentPose.block<3, 3>(0, 0).transpose();
108 rtStatus.oriDiffAngleAxis.fromRotationMatrix(rtStatus.poseDiffMatImp);
109
110 /// this should not be moved to non rt, just in case non rt thread dies, rt still functions as safely
111 if (not ftsensor.isSafe(c.ftConfig))
112 {
113 ARMARX_INFO << "FTGuard indicates RT not safe";
114 c.desiredPose = rtStatus.desiredPose;
115 rtStatus.rtSafe = false;
116 rtStatus.rtTargetSafe = true;
117 }
118 else if ((c.desiredPose.block<3, 1>(0, 3) - rtStatus.currentPose.block<3, 1>(0, 3)).norm() >
119 c.safeDistanceMMToGoal or
120 std::fminf(rtStatus.oriDiffAngleAxis.angle(),
121 2 * M_PI - rtStatus.oriDiffAngleAxis.angle()) >
122 VirtualRobot::MathTools::deg2rad(c.safeRotAngleDegreeToGoal))
123 {
124 rtStatus.desiredPoseUnsafe = c.desiredPose;
125 c.desiredPose = rtStatus.desiredPose;
126 rtStatus.rtSafe = false;
127 rtStatus.rtTargetSafe = false;
128 }
129 else
130 {
131 rtStatus.desiredPose = c.desiredPose;
132 rtStatus.rtSafe = true;
133 rtStatus.rtTargetSafe = true;
134 }
135
136 auto nDoF = static_cast<Eigen::Index>(rtStatus.nDoF);
137 /// ------------------------------ compute jacobi ------------------------------------------
138 rtStatus.jacobi =
139 ik->getJacobianMatrix(rtTCP, VirtualRobot::IKSolver::CartesianSelection::All);
140 ARMARX_CHECK_EQUAL(nDoF, rtStatus.jacobi.cols());
141 ARMARX_CHECK_EQUAL(6, rtStatus.jacobi.rows());
142
143 // rtStatus.jpinv = ik->computePseudoInverseJacobianMatrix(rtStatus.jacobi, lambda);
144 rtStatus.jpinv = ik->computePseudoInverseJacobianMatrix(
145 rtStatus.jacobi,
146 ik->getJacobiRegularization(VirtualRobot::IKSolver::CartesianSelection::All));
147 ARMARX_CHECK_EQUAL(6, rtStatus.jpinv.cols());
148 ARMARX_CHECK_EQUAL(nDoF, rtStatus.jpinv.rows());
149
150 // rtStatus.jacobi.block(0, 0, 3, rtStatus.numJoints) =
151 // 0.001 * rtStatus.jacobi.block(0, 0, 3, rtStatus.numJoints);
152 // rtStatus.jpinv.block(0, 0, rtStatus.numJoints, 3) =
153 // 0.001 * rtStatus.jpinv.block(0, 0, rtStatus.numJoints, 3);
154
155 /// ------------------------------ update velocity/twist -----------------------------------
156 ARMARX_CHECK_EQUAL(nDoF, rtStatus.jointPosition.rows());
157 ARMARX_CHECK_EQUAL(nDoF, rtStatus.jointVelocity.rows());
158 ARMARX_CHECK_EQUAL(nDoF, rtStatus.qvelFiltered.rows());
159
160 rtStatus.qvelFiltered =
161 (1 - c.qvelFilter) * rtStatus.qvelFiltered + c.qvelFilter * rtStatus.jointVelocity;
162 rtStatus.currentTwist = rtStatus.jacobi * rtStatus.qvelFiltered; /// in mm/s
163
164 /// ------------------------------------- TS Error --------------------------------
165 /// calculate pose error between target pose and current pose
166 /// !!! This is very important: you have to keep position and orientation both
167 /// with UI unit (meter, radian) to calculate impedance force.
168
169 rtStatus.poseDiffMatImp = rtStatus.desiredPose.block<3, 3>(0, 0) *
170 rtStatus.currentPose.block<3, 3>(0, 0).transpose();
171 // rtStatus.poseErrorImp.head<3>() = 0.001 * (rtStatus.desiredPose.block<3, 1>(0, 3) -
172 // rtStatus.currentPose.block<3, 1>(0, 3));
173 rtStatus.poseErrorImp.head<3>() = (rtStatus.desiredPose.block<3, 1>(0, 3) -
174 rtStatus.currentPose.block<3, 1>(0, 3)); /// in mm
175 rtStatus.poseErrorImp.tail<3>() =
176 VirtualRobot::MathTools::eigen3f2rpy(rtStatus.poseDiffMatImp);
177
178 /// ------------------------------------- Velocity control ---------------------------------------------------
179 /// calculate pose error between target pose and current pose
180 /// !!! This is very important: you have to keep position and orientation both
181 /// with UI unit (meter, radian) to calculate desired Cartesian velocity.
182 rtStatus.cartesianVelTarget = c.kpCartesianVel.cwiseProduct(rtStatus.poseErrorImp) -
183 c.kdCartesianVel.cwiseProduct(rtStatus.currentTwist);
184
185 /// ----------------------------- Nullspace PD Control --------------------------------------------------
186 ARMARX_CHECK_EQUAL(nDoF, c.kpNullspaceVel.rows());
187 ARMARX_CHECK_EQUAL(nDoF, c.kdNullspaceVel.rows());
188 ARMARX_CHECK_EQUAL(nDoF, rtStatus.nullspaceVelocity.rows());
189 ARMARX_CHECK_EQUAL(nDoF, c.desiredNullspaceJointAngles.value().size());
190
191 rtStatus.nullspaceVelocity =
192 c.kpNullspaceVel.cwiseProduct(c.desiredNullspaceJointAngles.value() -
193 rtStatus.jointPosition) -
194 c.kdNullspaceVel.cwiseProduct(rtStatus.qvelFiltered);
195
196 /// ----------------------------- Map TS target velocity to JS --------------------------------------------------
197 ARMARX_CHECK_EQUAL(nDoF, rtStatus.desiredJointVelocity.rows());
198 rtStatus.desiredJointVelocity =
199 rtStatus.jpinv * rtStatus.cartesianVelTarget +
200 (rtStatus.I - rtStatus.jpinv * rtStatus.jacobi) * rtStatus.nullspaceVelocity;
201
202 /// ----------------------------- write torque target -------------------------------------
203 for (int i = 0; i < rtStatus.desiredJointVelocity.rows(); ++i)
204 {
205 rtStatus.desiredJointVelocity(i) =
206 std::clamp(rtStatus.desiredJointVelocity(i), -c.velocityLimit, c.velocityLimit);
207 }
208 }
209
210 // void
211 // TaskspaceVelocityController::RtStatus::reset(const unsigned int nDoF)
212 // {
213 // /// This function can be called before the RT thread.
214 // /// base
215 // // jointPosition.resize(nDoF, 0.);
216 // // jointVelocity.resize(nDoF, 0.);
217 // // jointTorque.resize(nDoF, 0.);
218 // jointPosition.setZero(nDoF);
219 // jointVelocity.setZero(nDoF);
220 // jointTorque.setZero(nDoF);
221 // deltaT = 0.0;
222 // accumulateTime = 0.0;
223 // numDoF = nDoF;
224 // // nDoFTorque = numDoFTorque;
225 // // nDoFVelocity = numDoFVelocity;
226 // // ARMARX_CHECK_EQUAL(numJoints, nDoFTorque + nDoFVelocity);
227 //
228 // /// targets
229 // desiredJointVelocity.setZero(nDoF);
230 // cartesianVelTarget.setZero();
231 // nullspaceVelocity.setZero(nDoF);
232 //
233 // /// force torque
234 // currentForceTorque.setZero();
235 //
236 // /// current status
237 // qvelFiltered.setZero(nDoF);
238 // currentPose.setZero();
239 // currentTwist.setZero();
240 // desiredPose.setZero();
241 // desiredPoseUnsafe.setZero();
242 //
243 // /// intermediate results
244 // poseDiffMatImp.setZero();
245 // poseErrorImp.setZero();
246 // oriDiffAngleAxis = Eigen::AngleAxisf::Identity();
247 //
248 // /// others
249 // jacobi.setZero(6, nDoF);
250 // jpinv.setZero(nDoF, 6);
251 // rtSafe = false;
252 // rtTargetSafe = true;
253 // }
254 //
255 // void
256 // TaskspaceVelocityController::RtStatus::rtPreActivate(const Eigen::Matrix4f& currentTCPPose)
257 // {
258 // /// !!!! TO BE UPDATED IN PREACTIVATE !!!!
259 // /// only then the up-to-date robot joint information is available
260 // currentPose = currentTCPPose;
261 // desiredPose = currentTCPPose;
262 // accumulateTime = 0.0;
263 // }
264
265} // namespace armarx::control::common::control_law
#define M_PI
Definition MathTools.h:17
constexpr T c
void initialize(const VirtualRobot::RobotNodeSetPtr &rns, const VirtualRobot::RobotNodeSetPtr &rtRns)
common::control_law::arondto::TaskspaceVelocityControllerConfig Config
#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...
#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...
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
Eigen::Vector6f cartesianVelTarget
for impedance control
Definition common.h:75
Eigen::MatrixXf I
for computing nullspace projection
Definition common.h:124
Eigen::MatrixXf jpinv
pseudo inverse of the jacobi [nDoF, 6], for vel control
Definition common.h:121
Eigen::MatrixXf jacobi
others jacobi matrix [6, nDoF]
Definition common.h:116
Eigen::Matrix3f poseDiffMatImp
intermediate results
Definition common.h:85
Eigen::VectorXf qvelFiltered
for velocity control
Definition common.h:78