NJointTSDMPController.h
Go to the documentation of this file.
1 #pragma once
2 
3 
4 // armarx
5 #include <VirtualRobot/Robot.h>
6 #include <VirtualRobot/IK/DifferentialIK.h>
7 
8 // DMP
9 #include <dmp/representation/dmp/umitsmp.h>
10 
11 // armarx
18 
19 // control
20 #include <armarx/control/deprecated_njoint_mp_controller/task_space/ControllerInterface.h>
22 
23 
25 {
27 
28  TYPEDEF_PTRS_HANDLE(NJointTSDMPController);
29  TYPEDEF_PTRS_HANDLE(NJointTSDMPControllerControlData);
30 
31  using ViaPoint = std::pair<double, DMP::DVec >;
32  using ViaPointsSet = std::vector<ViaPoint >;
34  {
35  public:
38  // cartesian velocity control data
39  std::vector<float> nullspaceJointVelocities;
40  float avoidJointLimitsKp = 0;
41  std::vector<float> torqueKp;
42  std::vector<float> torqueKd;
43  VirtualRobot::IKSolver::CartesianSelection mode = VirtualRobot::IKSolver::All;
44  };
45 
46  /**
47  * @brief The NJointTSDMPController class
48  * @ingroup Library-RobotUnit-NJointControllers
49  */
51  public NJointControllerWithTripleBuffer<NJointTSDMPControllerControlData>,
53  {
54  class pidController
55  {
56  public:
57  float Kp = 0, Kd = 0;
58  float lastError = 0;
59  float update(float dt, float error)
60  {
61  float derivative = (error - lastError) / dt;
62  float retVal = Kp * error + Kd * derivative;
63  lastError = error;
64  return retVal;
65  }
66  };
67  public:
68  using ConfigPtrT = NJointTaskSpaceDMPControllerConfigPtr;
69  NJointTSDMPController(const RobotUnitPtr&, const NJointControllerConfigPtr& config, const VirtualRobot::RobotPtr&);
70 
71  // NJointControllerInterface interface
72  std::string getClassName(const Ice::Current&) const override;
73 
74  // NJointController interface
75 
76  void rtRun(const IceUtil::Time& sensorValuesTimestamp, const IceUtil::Time& timeSinceLastIteration) override;
77 
78  // NJointTSDMPControllerInterface interface
79  void learnDMPFromFiles(const Ice::StringSeq& fileNames, const Ice::Current&) override;
80  bool isFinished(const Ice::Current&) override
81  {
82  return finished;
83  }
84 
85  void runDMP(const Ice::DoubleSeq& goals, Ice::Double tau, const Ice::Current&) override;
86  void runDMPWithTime(const Ice::DoubleSeq& goals, Ice::Double timeDuration, const Ice::Current&) override;
87 
88  void setSpeed(Ice::Double times, const Ice::Current&) override;
89  void setViaPoints(Ice::Double u, const Ice::DoubleSeq& viapoint, const Ice::Current&) override;
90  void removeAllViaPoints(const Ice::Current&) override;
91 
92  void setGoals(const Ice::DoubleSeq& goals, const Ice::Current&) override;
93 
94  void setControllerTarget(Ice::Float avoidJointLimitsKp, NJointTaskSpaceDMPControllerMode::CartesianSelection mode, const Ice::Current&) override;
95  void setTorqueKp(const StringFloatDictionary& torqueKp, const Ice::Current&) override;
96  void setNullspaceJointVelocities(const StringFloatDictionary& nullspaceJointVelocities, const Ice::Current&) override;
97 
98 
99  void pauseDMP(const Ice::Current&) override;
100  void resumeDMP(const Ice::Current&) override;
101 
102  void resetDMP(const Ice::Current&) override;
103  void stopDMP(const Ice::Current&) override;
104 
105  double getCanVal(const Ice::Current&) override
106  {
107  return dmpCtrl->canVal;
108  }
109  std::string getDMPAsString(const Ice::Current&) override;
110  std::vector<double> createDMPFromString(const std::string& dmpString, const Ice::Current&) override;
111 
112  // VirtualRobot::IKSolver::CartesianSelection ModeFromIce(const NJointTaskSpaceDMPControllerMode::CartesianSelection mode);
113  Eigen::VectorXf calcIK(const Eigen::VectorXf& cartesianVel, const Eigen::VectorXf& nullspace, VirtualRobot::IKSolver::CartesianSelection mode);
114 
115 
116  void setMPWeights(const DoubleSeqSeq& weights, const Ice::Current&) override;
117  DoubleSeqSeq getMPWeights(const Ice::Current&) override;
118 
119  void setLinearVelocityKd(Ice::Float kd, const Ice::Current& = Ice::emptyCurrent) override;
120  void setLinearVelocityKp(Ice::Float kp, const Ice::Current& = Ice::emptyCurrent) override;
121  void setAngularVelocityKd(Ice::Float kd, const Ice::Current& = Ice::emptyCurrent) override;
122  void setAngularVelocityKp(Ice::Float kp, const Ice::Current& = Ice::emptyCurrent) override;
123 
124  protected:
125  void rtPreActivateController() override;
126  void rtPostDeactivateController() override;
128  virtual void onPublish(const SensorAndControl&, const DebugDrawerInterfacePrx&, const DebugObserverInterfacePrx&) override;
129 
130  void onInitNJointController() override;
131  void onDisconnectNJointController() override;
132  void controllerRun();
133 
134  private:
135  std::vector<std::string> jointNames;
136  struct DebugBufferData
137  {
138  StringFloatDictionary latestTargetVelocities;
139  StringFloatDictionary dmpTargets;
140  StringFloatDictionary currentPose;
141  double currentCanVal;
142  double mpcFactor;
143  double error;
144  double phaseStop;
145  double posError;
146  double oriError;
147  double deltaT;
148  };
149 
150  TripleBuffer<DebugBufferData> debugOutputData;
151 
152 
153  struct RTDebugData
154  {
155  Eigen::VectorXf targetJointVels;
156  };
157 
158  TripleBuffer<RTDebugData> rtDebugData;
159 
160 
161  struct RTToControllerData
162  {
163  double currentTime;
164  double deltaT;
165  Eigen::Matrix4f currentPose;
166  Eigen::VectorXf currentTwist;
167  };
169 
170  struct RTToUserData
171  {
172  Eigen::Matrix4f currentTcpPose;
173 
174  };
175  TripleBuffer<RTToUserData> rt2UserData;
176 
177 
179 
180  std::vector<const SensorValue1DoFActuatorTorque*> torqueSensors;
181  std::vector<const SensorValue1DoFGravityTorque*> gravityTorqueSensors;
182  std::vector<ControlTarget1DoFActuatorVelocity*> targets;
183  std::vector<const SensorValue1DoFActuatorVelocity*> velocitySensors;
184  std::vector<const SensorValue1DoFActuatorPosition*> positionSensors;
185 
186  // velocity ik controller parameters
187  std::vector<pidController> torquePIDs;
188  CartesianVelocityControllerPtr tcpController;
189  std::string nodeSetName;
190 
191  // dmp parameters
192  bool finished;
193  bool started;
194 
195  VirtualRobot::DifferentialIKPtr ik;
196  VirtualRobot::RobotNodePtr tcp;
197  VirtualRobot::RobotNodePtr refFrame;
198  Eigen::Vector6f targetVels;
199  Eigen::Matrix4f targetPose;
200 
201  NJointTaskSpaceDMPControllerConfigPtr cfg;
202  mutable MutexType controllerMutex;
204 
205 
206  std::string debugName;
207 
208  Eigen::VectorXf filtered_qvel;
209  Eigen::Vector3f filtered_position;
210  float vel_filter_factor;
211  float pos_filter_factor;
212  bool firstRun;
213 
214  float KpF;
215  float DpF;
216  float KoF;
217  float DoF;
218 
219  Eigen::VectorXf jointHighLimits;
220  Eigen::VectorXf jointLowLimits;
221 
222 
223  };
224 
225 } // namespace armarx
226 
armarx::control::deprecated_njoint_mp_controller::task_space::ViaPointsSet
std::vector< ViaPoint > ViaPointsSet
Definition: DeprecatedNJointTSDMPController.h:28
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:918
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:242
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::torqueKp
std::vector< float > torqueKp
Definition: NJointTSDMPController.h:41
armarx::NJointTaskSpaceDMPControllerInterface
Definition: ControllerInterface.ice:84
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:536
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:393
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:384
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::getClassName
std::string getClassName(const Ice::Current &) const override
Definition: NJointTSDMPController.cpp:141
armarx::control::deprecated_njoint_mp_controller::task_space
Definition: DeprecatedNJointPeriodicTSDMPCompliantController.cpp:6
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:212
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::getCanVal
double getCanVal(const Ice::Current &) override
Definition: NJointTSDMPController.h:105
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::targetTSVel
Eigen::Vector6f targetTSVel
Definition: NJointTSDMPController.h:36
armarx::NJointTaskSpaceDMPControllerInterface::getMPWeights
DoubleSeqSeq getMPWeights()
armarx::NJointControllerBase::ConfigPtrT
NJointControllerConfigPtr ConfigPtrT
Definition: NJointControllerBase.h:586
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:27
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::nullspaceJointVelocities
std::vector< float > nullspaceJointVelocities
Definition: NJointTSDMPController.h:39
armarx::PeriodicTask::pointer_type
IceUtil::Handle< PeriodicTask< T > > pointer_type
Shared pointer type for convenience.
Definition: PeriodicTask.h:67
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:147
armarx::detail::ControlThreadOutputBufferEntry
Definition: ControlThreadOutputBuffer.h:177
armarx::VariantType::Double
const VariantTypeId Double
Definition: Variant.h:919
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::learnDMPFromFiles
void learnDMPFromFiles(const Ice::StringSeq &fileNames, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:368
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:490
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:40
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:483
ControlTarget1DoFActuator.h
armarx::control::deprecated_njoint_mp_controller::tsvmp
Definition: NJointTaskSpaceImpedanceDMPController.h:20
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:67
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:13
NJointController.h
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setSpeed
void setSpeed(Ice::Double times, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:377
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::torqueKd
std::vector< float > torqueKd
Definition: NJointTSDMPController.h:42
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerPtr
std::shared_ptr< TaskSpaceDMPController > TaskSpaceDMPControllerPtr
Definition: NJointTaskSpaceImpedanceDMPController.h:24
armarx::NJointTaskSpaceDMPControllerInterface::getDMPAsString
string getDMPAsString()
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::isFinished
bool isFinished(const Ice::Current &) override
Definition: NJointTSDMPController.h:80
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData::targetPose
Eigen::Matrix4f targetPose
Definition: NJointTSDMPController.h:37
armarx::NJointControllerWithTripleBuffer< NJointTSDMPControllerControlData >::MutexType
std::recursive_mutex MutexType
Definition: NJointControllerWithTripleBuffer.h:13
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:43
Eigen::Matrix< float, 6, 1 >
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController
The NJointTSDMPController class.
Definition: NJointTSDMPController.h:50
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:419
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setNullspaceJointVelocities
void setNullspaceJointVelocities(const StringFloatDictionary &nullspaceJointVelocities, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:405
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPControllerControlData
Definition: NJointTSDMPController.h:33
dt
constexpr T dt
Definition: UnscentedKalmanFilterTest.cpp:42
armarx::control::deprecated_njoint_mp_controller::task_space::NJointTSDMPController::setGoals
void setGoals(const Ice::DoubleSeq &goals, const Ice::Current &) override
Definition: NJointTSDMPController.cpp:441
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:511
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::NJointTaskSpaceDMPControllerInterface::removeAllViaPoints
void removeAllViaPoints()
armarx::TripleBuffer< DebugBufferData >