NJointTSDMPController.h
Go to the documentation of this file.
1 #pragma once
2 
3 
4 // armarx
5 #include <VirtualRobot/VirtualRobot.h>
6 
7 // DMP
8 #include <dmp/representation/dmp/umitsmp.h>
9 
10 // armarx
12 
18 
19 // control
21 #include <armarx/control/deprecated_njoint_mp_controller/task_space/ControllerInterface.h>
22 
23 namespace armarx
24 {
25  class SensorValue1DoFActuatorTorque;
26  class SensorValue1DoFActuatorVelocity;
27  class SensorValue1DoFActuatorPosition;
28  class ControlTarget1DoFActuatorTorque;
29  class SensorValueForceTorque;
30 } // namespace armarx
31 
33 {
35 
36  TYPEDEF_PTRS_HANDLE(NJointTSDMPController);
37  TYPEDEF_PTRS_HANDLE(NJointTSDMPControllerControlData);
38 
39  using ViaPoint = std::pair<double, DMP::DVec>;
40  using ViaPointsSet = std::vector<ViaPoint>;
41 
43  {
44  public:
47  // cartesian velocity control data
48  std::vector<float> nullspaceJointVelocities;
49  float avoidJointLimitsKp = 0;
50  std::vector<float> torqueKp;
51  std::vector<float> torqueKd;
52  VirtualRobot::IKSolver::CartesianSelection mode = VirtualRobot::IKSolver::All;
53  };
54 
55  /**
56  * @brief The NJointTSDMPController class
57  * @ingroup Library-RobotUnit-NJointControllers
58  */
60  public NJointControllerWithTripleBuffer<NJointTSDMPControllerControlData>,
62  {
63  class pidController
64  {
65  public:
66  float Kp = 0, Kd = 0;
67  float lastError = 0;
68 
69  float
70  update(float dt, float error)
71  {
72  float derivative = (error - lastError) / dt;
73  float retVal = Kp * error + Kd * derivative;
74  lastError = error;
75  return retVal;
76  }
77  };
78 
79  public:
80  using ConfigPtrT = NJointTaskSpaceDMPControllerConfigPtr;
82  const NJointControllerConfigPtr& config,
83  const VirtualRobot::RobotPtr&);
84 
85  // NJointControllerInterface interface
86  std::string getClassName(const Ice::Current&) const override;
87 
88  // NJointController interface
89 
90  void rtRun(const IceUtil::Time& sensorValuesTimestamp,
91  const IceUtil::Time& timeSinceLastIteration) override;
92 
93  // NJointTSDMPControllerInterface interface
94  void learnDMPFromFiles(const Ice::StringSeq& fileNames, const Ice::Current&) override;
95 
96  bool
97  isFinished(const Ice::Current&) override
98  {
99  return finished;
100  }
101 
102  void runDMP(const Ice::DoubleSeq& goals, Ice::Double tau, const Ice::Current&) override;
103  void runDMPWithTime(const Ice::DoubleSeq& goals,
104  Ice::Double timeDuration,
105  const Ice::Current&) override;
106 
107  void setSpeed(Ice::Double times, const Ice::Current&) override;
108  void
109  setViaPoints(Ice::Double u, const Ice::DoubleSeq& viapoint, const Ice::Current&) override;
110  void removeAllViaPoints(const Ice::Current&) override;
111 
112  void setGoals(const Ice::DoubleSeq& goals, const Ice::Current&) override;
113 
114  void setControllerTarget(Ice::Float avoidJointLimitsKp,
116  const Ice::Current&) override;
117  void setTorqueKp(const StringFloatDictionary& torqueKp, const Ice::Current&) override;
118  void setNullspaceJointVelocities(const StringFloatDictionary& nullspaceJointVelocities,
119  const Ice::Current&) override;
120 
121 
122  void pauseDMP(const Ice::Current&) override;
123  void resumeDMP(const Ice::Current&) override;
124 
125  void resetDMP(const Ice::Current&) override;
126  void stopDMP(const Ice::Current&) override;
127 
128  double
129  getCanVal(const Ice::Current&) override
130  {
131  return dmpCtrl->canVal;
132  }
133 
134  std::string getDMPAsString(const Ice::Current&) override;
135  std::vector<double> createDMPFromString(const std::string& dmpString,
136  const Ice::Current&) override;
137 
138  // VirtualRobot::IKSolver::CartesianSelection ModeFromIce(const NJointTaskSpaceDMPControllerMode::CartesianSelection mode);
139  Eigen::VectorXf calcIK(const Eigen::VectorXf& cartesianVel,
140  const Eigen::VectorXf& nullspace,
142 
143 
144  void setMPWeights(const DoubleSeqSeq& weights, const Ice::Current&) override;
145  DoubleSeqSeq getMPWeights(const Ice::Current&) override;
146 
147  void setLinearVelocityKd(Ice::Float kd, const Ice::Current& = Ice::emptyCurrent) override;
148  void setLinearVelocityKp(Ice::Float kp, const Ice::Current& = Ice::emptyCurrent) override;
149  void setAngularVelocityKd(Ice::Float kd, const Ice::Current& = Ice::emptyCurrent) override;
150  void setAngularVelocityKp(Ice::Float kp, const Ice::Current& = Ice::emptyCurrent) override;
151 
152  protected:
153  void rtPreActivateController() override;
154  void rtPostDeactivateController() override;
157  virtual void onPublish(const SensorAndControl&,
159  const DebugObserverInterfacePrx&) override;
160 
161  void onInitNJointController() override;
162  void onDisconnectNJointController() override;
163  void controllerRun();
164 
165  private:
166  std::vector<std::string> jointNames;
167 
168  struct DebugBufferData
169  {
170  StringFloatDictionary latestTargetVelocities;
171  StringFloatDictionary dmpTargets;
172  StringFloatDictionary currentPose;
173  double currentCanVal;
174  double mpcFactor;
175  double error;
176  double phaseStop;
177  double posError;
178  double oriError;
179  double deltaT;
180  };
181 
182  TripleBuffer<DebugBufferData> debugOutputData;
183 
184  struct RTDebugData
185  {
186  Eigen::VectorXf targetJointVels;
187  };
188 
189  TripleBuffer<RTDebugData> rtDebugData;
190 
191  struct RTToControllerData
192  {
193  double currentTime;
194  double deltaT;
195  Eigen::Matrix4f currentPose;
196  Eigen::VectorXf currentTwist;
197  };
198 
200 
201  struct RTToUserData
202  {
203  Eigen::Matrix4f currentTcpPose;
204  };
205 
206  TripleBuffer<RTToUserData> rt2UserData;
207 
208 
210 
211  std::vector<const SensorValue1DoFActuatorTorque*> torqueSensors;
212  std::vector<const SensorValue1DoFGravityTorque*> gravityTorqueSensors;
213  std::vector<ControlTarget1DoFActuatorVelocity*> targets;
214  std::vector<const SensorValue1DoFActuatorVelocity*> velocitySensors;
215  std::vector<const SensorValue1DoFActuatorPosition*> positionSensors;
216 
217  // velocity ik controller parameters
218  std::vector<pidController> torquePIDs;
219  CartesianVelocityControllerPtr tcpController;
220  std::string nodeSetName;
221 
222  // dmp parameters
223  bool finished;
224  bool started;
225 
226  VirtualRobot::DifferentialIKPtr ik;
227  VirtualRobot::RobotNodePtr tcp;
228  VirtualRobot::RobotNodePtr refFrame;
229  Eigen::Vector6f targetVels;
230  Eigen::Matrix4f targetPose;
231 
232  NJointTaskSpaceDMPControllerConfigPtr cfg;
233  mutable MutexType controllerMutex;
235 
236 
237  std::string debugName;
238 
239  Eigen::VectorXf filtered_qvel;
240  Eigen::Vector3f filtered_position;
241  float vel_filter_factor;
242  float pos_filter_factor;
243  bool firstRun;
244 
245  float KpF;
246  float DpF;
247  float KoF;
248  float DoF;
249 
250  Eigen::VectorXf jointHighLimits;
251  Eigen::VectorXf jointLowLimits;
252  };
253 
254 } // namespace armarx::control::deprecated_njoint_mp_controller::task_space
armarx::control::deprecated_njoint_mp_controller::task_space::ViaPointsSet
std::vector< ViaPoint > ViaPointsSet
Definition: DeprecatedNJointTSDMPController.h:37
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::onPublish
virtual void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
Definition: NJointTSDMPController.cpp:572
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::onInitNJointController
void onInitNJointController() override
Definition: NJointTSDMPController.cpp:626
armarx::VariantType::Float
const VariantTypeId Float
Definition: Variant.h:919
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::rtRun
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
Definition: NJointTSDMPController.cpp:247
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::torqueKp
std::vector< float > torqueKp
Definition: NJointTSDMPController.h:50
armarx::NJointTaskSpaceDMPControllerInterface
Definition: ControllerInterface.ice:83
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::runDMPWithTime
void runDMPWithTime(const Ice::DoubleSeq &goals, Ice::Double timeDuration, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:537
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setLinearVelocityKd
void setLinearVelocityKd(Ice::Float kd, const Ice::Current &=Ice::emptyCurrent) override
Definition: NJointTSDMPController.cpp:677
armarx::NJointControllerWithTripleBuffer
Definition: NJointControllerWithTripleBuffer.h:10
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setAngularVelocityKp
void setAngularVelocityKp(Ice::Float kp, const Ice::Current &=Ice::emptyCurrent) override
Definition: NJointTSDMPController.cpp:695
RobotUnit.h
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setTorqueKp
void setTorqueKp(const StringFloatDictionary &torqueKp, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:397
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:650
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setViaPoints
void setViaPoints(Ice::Double u, const Ice::DoubleSeq &viapoint, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:388
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::getClassName
std::string getClassName(const Ice::Current &) const override
Definition: NJointTSDMPController.cpp:146
armarx::control::deprecated_njoint_mp_controller::task_space
Definition: DeprecatedNJointPeriodicTSDMPCompliantController.cpp:20
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::onDisconnectNJointController
void onDisconnectNJointController() override
Definition: NJointTSDMPController.cpp:647
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::calcIK
Eigen::VectorXf calcIK(const Eigen::VectorXf &cartesianVel, const Eigen::VectorXf &nullspace, VirtualRobot::IKSolver::CartesianSelection mode)
Definition: NJointTSDMPController.cpp:217
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::getCanVal
double getCanVal(const Ice::Current &) override
Definition: NJointTSDMPController.h:129
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::targetTSVel
Eigen::Vector6f targetTSVel
Definition: NJointTSDMPController.h:45
armarx::NJointTaskSpaceDMPControllerInterface::getMPWeights
DoubleSeqSeq getMPWeights()
armarx::NJointControllerBase::ConfigPtrT
NJointControllerConfigPtr ConfigPtrT
Definition: NJointControllerBase.h:587
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::rtPostDeactivateController
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
Definition: NJointTSDMPController.cpp:567
armarx::control::deprecated_njoint_mp_controller::task_space::ViaPoint
std::pair< double, DMP::DVec > ViaPoint
Definition: DeprecatedNJointTSDMPController.h:36
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::nullspaceJointVelocities
std::vector< float > nullspaceJointVelocities
Definition: NJointTSDMPController.h:48
armarx::PeriodicTask::pointer_type
IceUtil::Handle< PeriodicTask< T > > pointer_type
Shared pointer type for convenience.
Definition: PeriodicTask.h:68
armarx::CartesianVelocityControllerPtr
std::shared_ptr< CartesianVelocityController > CartesianVelocityControllerPtr
Definition: CartesianVelocityController.h:34
armarx::NJointTaskSpaceDMPControllerInterface::resumeDMP
void resumeDMP()
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::controllerRun
void controllerRun()
Definition: NJointTSDMPController.cpp:152
armarx::detail::ControlThreadOutputBufferEntry
Definition: ControlThreadOutputBuffer.h:182
armarx::VariantType::Double
const VariantTypeId Double
Definition: Variant.h:920
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::learnDMPFromFiles
void learnDMPFromFiles(const Ice::StringSeq &fileNames, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:372
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::rtPreActivateController
void rtPreActivateController() override
This function is called before the controller is activated.
Definition: NJointTSDMPController.cpp:562
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setLinearVelocityKp
void setLinearVelocityKp(Ice::Float kp, const Ice::Current &=Ice::emptyCurrent) override
Definition: NJointTSDMPController.cpp:683
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::ModeFromIce
VirtualRobot::IKSolver::CartesianSelection ModeFromIce(const NJointTaskSpaceDMPControllerMode::CartesianSelection mode)
Definition: NJointTSDMPController.cpp:492
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setMPWeights
void setMPWeights(const DoubleSeqSeq &weights, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:653
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::avoidJointLimitsKp
float avoidJointLimitsKp
Definition: NJointTSDMPController.h:49
armarx::NJointTaskSpaceDMPControllerMode::CartesianSelection
CartesianSelection
Definition: ControllerInterface.ice:34
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::createDMPFromString
std::vector< double > createDMPFromString(const std::string &dmpString, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:485
ControlTarget1DoFActuator.h
armarx::control::deprecated_njoint_mp_controller::tsvmp
Definition: NJointTaskSpaceImpedanceDMPController.h:27
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::armem::server::ltm::util::mongodb::detail::update
bool update(mongocxx::collection &coll, const nlohmann::json &query, const nlohmann::json &update)
Definition: mongodb.cpp:68
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setAngularVelocityKd
void setAngularVelocityKd(Ice::Float kd, const Ice::Current &=Ice::emptyCurrent) override
Definition: NJointTSDMPController.cpp:689
TaskSpaceVMP.h
CartesianVelocityController.h
CycleUtil.h
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::NJointTSDMPController
NJointTSDMPController(const RobotUnitPtr &, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Definition: NJointTSDMPController.cpp:18
NJointController.h
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setSpeed
void setSpeed(Ice::Double times, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:381
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::torqueKd
std::vector< float > torqueKd
Definition: NJointTSDMPController.h:51
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerPtr
std::shared_ptr< TaskSpaceDMPController > TaskSpaceDMPControllerPtr
Definition: NJointTaskSpaceImpedanceDMPController.h:31
armarx::NJointTaskSpaceDMPControllerInterface::getDMPAsString
string getDMPAsString()
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::isFinished
bool isFinished(const Ice::Current &) override
Definition: NJointTSDMPController.h:97
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::targetPose
Eigen::Matrix4f targetPose
Definition: NJointTSDMPController.h:46
armarx::NJointControllerWithTripleBuffer< NJointTSDMPControllerControlData >::MutexType
std::recursive_mutex MutexType
Definition: NJointControllerWithTripleBuffer.h:13
IceUtil::Handle< class RobotUnit >
armarx::NJointTaskSpaceDMPControllerInterface::pauseDMP
void pauseDMP()
IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface >
armarx::control::deprecated_njoint_mp_controller::task_space::TYPEDEF_PTRS_HANDLE
TYPEDEF_PTRS_HANDLE(DeprecatedNJointPeriodicTSDMPCompliantController)
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::mode
VirtualRobot::IKSolver::CartesianSelection mode
Definition: NJointTSDMPController.h:52
Eigen::Matrix< float, 6, 1 >
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController
The NJointTSDMPController class.
Definition: NJointTSDMPController.h:59
armarx::NJointTaskSpaceDMPControllerInterface::resetDMP
void resetDMP()
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setControllerTarget
void setControllerTarget(Ice::Float avoidJointLimitsKp, NJointTaskSpaceDMPControllerMode::CartesianSelection mode, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:423
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setNullspaceJointVelocities
void setNullspaceJointVelocities(const StringFloatDictionary &nullspaceJointVelocities, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:409
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData
Definition: NJointTSDMPController.h:42
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
dt
constexpr T dt
Definition: UnscentedKalmanFilterTest.cpp:45
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setGoals
void setGoals(const Ice::DoubleSeq &goals, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:443
armarx::NJointTaskSpaceDMPControllerInterface::stopDMP
void stopDMP()
SensorValue1DoFActuator.h
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::runDMP
void runDMP(const Ice::DoubleSeq &goals, Ice::Double tau, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:512
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:19
armarx::NJointTaskSpaceDMPControllerInterface::removeAllViaPoints
void removeAllViaPoints()
armarx::TripleBuffer< DebugBufferData >