DeprecatedNJointTaskSpaceAdmittanceDMPController.h
Go to the documentation of this file.
1
2#pragma once
3
4#include <VirtualRobot/VirtualRobot.h>
5
9
11
13#include <armarx/control/deprecated_njoint_mp_controller/task_space/ControllerInterface.h>
14
15#include <dmp/representation/dmp/umidmp.h>
16
17namespace armarx
18{
19 class SensorValue1DoFActuatorTorque;
20 class SensorValue1DoFActuatorVelocity;
21 class SensorValue1DoFActuatorPosition;
22 class ControlTarget1DoFActuatorTorque;
24} // namespace armarx
25
27{
28 namespace tsvmp = armarx::control::deprecated_njoint_mp_controller::tsvmp;
29
32
42
43 /**
44 * @brief The DeprecatedNJointTaskSpaceAdmittanceDMPController class
45 * @ingroup Library-RobotUnit-NJointControllers
46 */
49 DeprecatedNJointTaskSpaceAdmittanceDMPControllerControlData>,
51 {
52 public:
53 using ConfigPtrT = DeprecatedNJointTaskSpaceAdmittanceDMPControllerConfigPtr;
55 const NJointControllerConfigPtr& config,
57
58 // NJointControllerInterface interface
59 std::string getClassName(const Ice::Current&) const override;
60
61 // NJointController interface
62 void rtRun(const IceUtil::Time& sensorValuesTimestamp,
63 const IceUtil::Time& timeSinceLastIteration) override;
64
65 // DeprecatedNJointTaskSpaceAdmittanceDMPControllerInterface interface
66 void learnDMPFromFiles(const Ice::StringSeq& fileNames, const Ice::Current&) override;
67 bool isFinished(const Ice::Current&) override;
68
69 void
70 setViaPoints(Ice::Double u, const Ice::DoubleSeq& viapoint, const Ice::Current&) override;
71 void setGoals(const Ice::DoubleSeq& goals, const Ice::Current&) override;
72
73 void learnJointDMPFromFiles(const std::string& fileName,
74 const Ice::FloatSeq& currentJVS,
75 const Ice::Current&) override;
76 void runDMP(const Ice::DoubleSeq& goals,
77 const Ice::Current& iceCurrent = Ice::emptyCurrent) override;
78 void runDMPWithTime(const Ice::DoubleSeq& goals,
79 Ice::Double timeDuration,
80 const Ice::Current&) override;
81
82 Ice::Double getVirtualTime(const Ice::Current&) override;
83
84 void stopDMP(const Ice::Current&) override;
85 void resumeDMP(const Ice::Current&) override;
86 void pauseDMP(const Ice::Current&) override;
87 void resetDMP(const Ice::Current&) override;
88
89 void setMPWeights(const DoubleSeqSeq& weights, const Ice::Current&) override;
90 DoubleSeqSeq getMPWeights(const Ice::Current&) override;
91
92 void removeAllViaPoints(const Ice::Current&) override;
93
94 void setKpImpedance(const Eigen::Vector6f& kpImpedance, const Ice::Current&) override;
95 void setKdImpedance(const Eigen::Vector6f& kdImpedance, const Ice::Current&) override;
96
97 void setKpAdmittance(const Eigen::Vector6f& kpAdmittance, const Ice::Current&) override;
98 void setKdAdmittance(const Eigen::Vector6f& kdAdmittance, const Ice::Current&) override;
99 void setKmAdmittance(const Eigen::Vector6f& kmAdmittance, const Ice::Current&) override;
100
101 void setTCPMass(Ice::Float mass, const Ice::Current&) override;
102 void setTCPCoMInFTFrame(const Eigen::Vector3f& com, const Ice::Current&) override;
103
104 void setNullspaceVelocityKd(const Eigen::VectorXf& kd, const Ice::Current&) override;
105 void setNullspaceVelocityKp(const Eigen::VectorXf& kp, const Ice::Current&) override;
106 void setUseNullSpaceJointDMP(bool enable, const Ice::Current&) override;
107 void setTargetNullSpaceJointValues(const Eigen::VectorXf& jointValues,
108 const Ice::Current&) override;
109 void setPotentialForceBaseline(const Eigen::Vector3f&,
110 const Eigen::Vector3f&,
111 const Ice::Current&) override;
112
113 std::string getDMPAsString(const Ice::Current&) override;
114 Ice::DoubleSeq createDMPFromString(const std::string&, const Ice::Current&) override;
115 Ice::Double getCanVal(const Ice::Current&) override;
116 void setStartAndGoals(const Ice::DoubleSeq& starts,
117 const Ice::DoubleSeq& goals,
118 const Ice::Current& ice) override;
119
120 Eigen::Vector6f getFilteredForceTorque(Eigen::Vector3f& forceBaseline,
121 Eigen::Vector3f& torqueBaseline,
122 Eigen::Vector6f& handCompensatedFT);
123 Eigen::Vector6f getTCPGravityCompensation(Eigen::Matrix4f& currentPose, float tcpMass);
124 // RTController::ControllerInfo getControllerInfo(const Ice::Current& ice) override;
125 std::string getKinematicChainName(const Ice::Current&) override;
126
127 protected:
128 virtual void onPublish(const SensorAndControl&,
130 const DebugObserverInterfacePrx&) override;
131
132 void onInitNJointController() override;
133 void onDisconnectNJointController() override;
134 void controllerRun();
135
136 private:
137 // RTController::ControllerInfo info;
138 std::string kinematic_chain;
139
140 // ---------------------- Buffer: rt 2 debug data ----------------------
141 struct DebugRTData
142 {
143 double currentCanVal;
144 double mpcfactor;
145 float targetPose_x;
146 float targetPose_y;
147 float targetPose_z;
148 float targetPose_qw;
149 float targetPose_qx;
150 float targetPose_qy;
151 float targetPose_qz;
152
153 float virtualPose_x;
154 float virtualPose_y;
155 float virtualPose_z;
156 float virtualPose_qw;
157 float virtualPose_qx;
158 float virtualPose_qy;
159 float virtualPose_qz;
160
161 float currentPose_x;
162 float currentPose_y;
163 float currentPose_z;
164 float currentPose_qw;
165 float currentPose_qx;
166 float currentPose_qy;
167 float currentPose_qz;
168
169 float currentKpos_x;
170 float currentKpos_y;
171 float currentKpos_z;
172 float currentKori_x;
173 float currentKori_y;
174 float currentKori_z;
175 float currentKnull_x;
176 float currentKnull_y;
177 float currentKnull_z;
178
179 float currentDpos_x;
180 float currentDpos_y;
181 float currentDpos_z;
182 float currentDori_x;
183 float currentDori_y;
184 float currentDori_z;
185 float currentDnull_x;
186 float currentDnull_y;
187 float currentDnull_z;
188
189 StringFloatDictionary desired_torques;
190 StringFloatDictionary desired_nullspaceJoint;
191 float forceDesired_x;
192 float forceDesired_y;
193 float forceDesired_z;
194 float forceDesired_rx;
195 float forceDesired_ry;
196 float forceDesired_rz;
197
198 float ft_InRoot_x;
199 float ft_InRoot_y;
200 float ft_InRoot_z;
201 float ft_InRoot_rx;
202 float ft_InRoot_ry;
203 float ft_InRoot_rz;
204
205 float ft_FilteredInRoot_x;
206 float ft_FilteredInRoot_y;
207 float ft_FilteredInRoot_z;
208 float ft_FilteredInRoot_rx;
209 float ft_FilteredInRoot_ry;
210 float ft_FilteredInRoot_rz;
211
212 float deltaT;
213
214 Eigen::Vector6f kmAdmittance;
215 Eigen::Vector6f gravityCompensation;
216 Eigen::Vector3f forceBaseline;
217 Eigen::Vector3f torqueBaseline;
218 Eigen::Vector3f forceOffset;
219 Eigen::Vector3f torqueOffset;
220 };
221
223
224 // ---------------------- Buffer: rt 2 MP thread data ----------------------
225 struct RT2MPData
226 {
227 double currentTime;
228 double deltaT;
229 Eigen::Matrix4f currentPose;
230 Eigen::VectorXf currentTwist;
231 };
232
234
235 // ---------------------- Buffer: rt 2 interface data ----------------------
236 struct RT2InterfaceData
237 {
238 Eigen::Matrix4f currentTcpPose;
239 };
240
242
243 // ---------------------- Buffer: control parameter ----------------------
244 struct CtrlParams
245 {
246 Eigen::Vector6f kpImpedance;
247 Eigen::Vector6f kdImpedance;
248
249 Eigen::Vector6f kpAdmittance;
250 Eigen::Vector6f kdAdmittance;
251 Eigen::Vector6f kmAdmittance;
252
253 Eigen::VectorXf knull;
254 Eigen::VectorXf dnull;
255
256 Eigen::Vector3f forceBaseline;
257 Eigen::Vector3f torqueBaseline;
258
259 float tcpMass;
260 Eigen::Vector3f tcpCoMInForceSensorFrame;
261 };
262
264
265
266 // ---------------------- Admittance Control Variables ----------------------
267
268 Eigen::Vector6f virtualAcc;
269 Eigen::Vector6f virtualVel;
270 Eigen::Matrix4f virtualPose;
271
272 // ---------------------- low-level control variables ----------------------
273 // device
274 std::vector<const SensorValue1DoFActuatorTorque*> torqueSensors;
275 std::vector<const SensorValue1DoFActuatorVelocity*> velocitySensors;
276 std::vector<const SensorValue1DoFActuatorPosition*> positionSensors;
277 std::vector<ControlTarget1DoFActuatorTorque*> targets;
278
279 VirtualRobot::DifferentialIKPtr ik;
280 VirtualRobot::RobotNodePtr tcp;
281
282 // ---------------------- MP variables ----------------------
283 DMP::Vec<DMP::DMPState> currentJointState;
284 DMP::UMIDMPPtr nullSpaceJointDMPPtr;
285
286 mutable MutexType mpMutex;
288 DeprecatedNJointTaskSpaceAdmittanceDMPControllerConfigPtr cfg;
290
291 // phaseStop parameters
292 double phaseL;
293 double phaseK;
294 double phaseDist0;
295 double phaseDist1;
296 double posToOriRatio;
297
298 float torqueLimit;
299 int numOfJoints;
300 std::vector<std::string> jointNames;
301
302 std::atomic_bool useNullSpaceJointDMP;
303 bool isNullSpaceJointDMPLearned;
304
305 std::atomic_bool rtFirstRun = true;
306 std::atomic_bool rtReady = false;
307 std::atomic_bool mpRunning = false;
308 std::atomic_bool mpFinished = false;
309
310 Eigen::Matrix4f previousTargetPose;
311 Eigen::VectorXf qvel_filtered;
312
313 /// force torque sensor
314 const SensorValueForceTorque* forceSensor;
315 Eigen::Vector3f forceOffset;
316 Eigen::Vector3f torqueOffset;
317 Eigen::Vector3f filteredForce;
318 Eigen::Vector3f filteredTorque;
319 Eigen::Vector3f filteredForceInRoot;
320 Eigen::Vector3f filteredTorqueInRoot;
321 std::atomic<float> timeForCalibration;
322
323 std::atomic_bool enableTCPGravityCompensation;
324 Eigen::Matrix4f forceFrameInTCP = Eigen::Matrix4f::Identity();
325 Eigen::Vector3f tcpCoMInTCPFrame;
326
327 protected:
328 void rtPreActivateController() override;
329 };
330
331} // namespace armarx::control::deprecated_njoint_mp_controller::task_space
#define TYPEDEF_PTRS_HANDLE(T)
NJointControllerWithTripleBuffer(const DeprecatedNJointTaskSpaceAdmittanceDMPControllerControlData &initialCommands=DeprecatedNJointTaskSpaceAdmittanceDMPControllerControlData())
IceUtil::Handle< PeriodicTask< T > > pointer_type
Shared pointer type for convenience.
Same as the TripleBuffer, but partial writes of the data structure are ok. The write operation may be...
virtual void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
void learnJointDMPFromFiles(const std::string &fileName, const Ice::FloatSeq &currentJVS, const Ice::Current &) override
DeprecatedNJointTaskSpaceAdmittanceDMPController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Eigen::Vector6f getFilteredForceTorque(Eigen::Vector3f &forceBaseline, Eigen::Vector3f &torqueBaseline, Eigen::Vector6f &handCompensatedFT)
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
void setStartAndGoals(const Ice::DoubleSeq &starts, const Ice::DoubleSeq &goals, const Ice::Current &ice) override
Brief description of class targets.
Definition targets.h:39
boost::shared_ptr< class UMIDMP > UMIDMPPtr
Matrix< float, 6, 1 > Vector6f
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
This file offers overloads of toIce() and fromIce() functions for STL container types.
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
IceUtil::Handle< class RobotUnit > RobotUnitPtr
Definition FTSensor.h:34
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl