DSJointCarryController.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package DSController::ArmarXObjects::DSJointCarryController
17  * @author Mahdi Khoramshahi ( m80 dot khoramshahi at gmail dot com )
18  * @date 2018
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #ifndef _ARMARX_LIB_DSController_DSJointCarryController_H
24 #define _ARMARX_LIB_DSController_DSJointCarryController_H
25 
26 #include <VirtualRobot/Robot.h>
27 #include <VirtualRobot/Tools/Gravity.h>
28 #include <VirtualRobot/IK/DifferentialIK.h>
30 
36 
37 #include <armarx/control/ds_controller/DSControllerInterface.h>
38 
39 #include "GMRDynamics.h"
40 #include "MathLib.h"
41 
42 
44 {
45 
47 
49  {
50  int K_gmm_;
51  int dim_;
52  std::vector<double> Priors_;
53  std::vector<double> Mu_;
54  std::vector<double> Sigma_;
55  std::vector<double> attractor_;
56  double dt_;
57  };
58 
59 
61  {
62  public:
64 
65  JointCarryGMMMotionGen(const std::string& fileName)
66  {
67  getGMMParamsFromJsonFile(fileName);
68  }
69 
72  Eigen::Vector3f guard_target;
73  Eigen::Vector3f guard_desiredVelocity;
74 
75  float scaling;
76  float v_max;
77 
78  void getGMMParamsFromJsonFile(const std::string& fileName)
79  {
80  std::ifstream infile { fileName };
81  std::string objDefs = { std::istreambuf_iterator<char>(infile), std::istreambuf_iterator<char>() };
82  JSONObjectPtr json = new JSONObject();
83  json->fromString(objDefs);
84  guard_gmmParas.K_gmm_ = json->getInt("K");
85  guard_gmmParas.dim_ = json->getInt("Dim");
86  json->getArray<double>("Priors", guard_gmmParas.Priors_);
87  json->getArray<double>("Mu", guard_gmmParas.Mu_);
88  json->getArray<double>("Attractor", guard_gmmParas.attractor_);
89  json->getArray<double>("Sigma", guard_gmmParas.Sigma_);
90  scaling = json->getDouble("Scaling");
91  v_max = json->getDouble("MaxVelocity");
92 
94  guard_gmm->initGMR(0, 2, 3, 5);
95  std::cout << "line 162." << std::endl;
96 
97 
98  for (int i = 0; i < 3; ++i)
99  {
101  }
102 
103  std::cout << "Finished GMM." << std::endl;
104 
105  }
106 
107 
109  const Eigen::Vector3f& positionInMeter,
110  float positionErrorToleranceInMeter)
111  {
112  MathLib::Vector position_error;
113  position_error.Resize(3);
114 
115  MathLib::Vector desired_vel;
116  desired_vel.Resize(3);
117 
118  Eigen::Vector3f positionError = positionInMeter - guard_target;
119  if (positionError.norm() < positionErrorToleranceInMeter)
120  {
121  positionError.setZero();
122  }
123 
124  for (int i = 0; i < 3; ++i)
125  {
126  position_error(i) = positionError(i);
127  }
128 
129  desired_vel = guard_gmm->getVelocity(position_error);
130 
131  guard_desiredVelocity << desired_vel(0), desired_vel(1), desired_vel(2);
132 
134 
135  float lenVec = guard_desiredVelocity.norm();
136 
137  if (std::isnan(lenVec))
138  {
139  guard_desiredVelocity.setZero();
140  }
141 
142  if (lenVec > v_max)
143  {
145  }
146  }
147 
148 
149 
150  };
151 
153 
155  {
156  public:
157  Eigen::Vector3f leftDesiredLinearVelocity;
158  Eigen::Vector3f leftDesiredAngularError;
159  Eigen::Vector3f rightDesiredLinearVelocity;
160  Eigen::Vector3f rightDesiredAngularError;
161  };
162 
163 
164  /**
165  * @defgroup Library-DSJointCarryController DSJointCarryController
166  * @ingroup armarx_control
167  * A description of the library DSJointCarryController.
168  *
169  * @class DSJointCarryController
170  * @ingroup Library-DSJointCarryController
171  * @brief Brief description of class DSJointCarryController.
172  *
173  * Detailed description of class DSJointCarryController.
174  */
175  class DSJointCarryController : public NJointControllerWithTripleBuffer<DSJointCarryControllerControlData>, public DSJointCarryControllerInterface
176  {
177 
178  // ManagedIceObject interface
179  protected:
180  void onInitNJointController();
182 
183 
184  void controllerRun();
185 
186 
187 
188  // NJointControllerInterface interface
189  public:
190  using ConfigPtrT = DSJointCarryControllerConfigPtr;
191 
192  DSJointCarryController(const RobotUnitPtr& robotUnit, const NJointControllerConfigPtr& config, const VirtualRobot::RobotPtr&);
193 
194 
195  std::string getClassName(const Ice::Current&) const
196  {
197  return "DSJointCarryController";
198  }
199 
200  // NJointController interface
201  void rtRun(const IceUtil::Time& sensorValuesTimestamp, const IceUtil::Time& timeSinceLastIteration);
202 
203  // DSJointCarryControllerInterface interface
204  public:
205  void setGuardInHandPosition(const Ice::FloatSeq& guardPositionToHandInMeter, const Ice::Current&);
206  void setGuardOrientation(const Ice::FloatSeq& guardOrientationInRobotBase, const Ice::Current&);
207  void setDesiredGuardOri(const Ice::FloatSeq& desiredOrientationInRobotBase, const Ice::Current&);
208  void setRotationStiffness(const Ice::FloatSeq& rotationStiffness, const Ice::Current&);
209  void setGuardObsAvoidVel(const Ice::FloatSeq& guardVel, const Ice::Current&);
210  float getGMMVel(const Ice::Current&);
211  private:
212  mutable MutexType interface2CtrlDataMutex;
213 
214  float deadzone(float currentValue, float targetValue, float threshold);
215  Eigen::Quaternionf quatSlerp(double t, const Eigen::Quaternionf& q0, const Eigen::Quaternionf& q1);
216  JointCarryGMMMotionGenPtr gmmMotionGenerator;
217  struct DSJointCarryControllerSensorData
218  {
219  Eigen::Matrix4f left_tcpPose;
220  Eigen::Matrix4f right_tcpPose;
221  Eigen::Vector3f left_force;
222  Eigen::Vector3f right_force;
223  double currentTime;
224 
225  };
227 
228  struct DSCtrlDebugInfo
229  {
230  Eigen::Vector3f leftDesiredLinearVelocity;
231  Eigen::Vector3f rightDesiredLinearVelocity;
232  };
233  TripleBuffer<DSCtrlDebugInfo> debugCtrlDataInfo;
234 
235  struct Interface2CtrlData
236  {
237  Eigen::Vector3f guardToHandInMeter;
238  Eigen::Quaternionf guardOriInRobotBase;
239  Eigen::Quaternionf desiredGuardOriInRobotBase;
240  Eigen::Vector3f guardRotationStiffness;
241  Eigen::Vector3f guardObsAvoidVel;
242  };
243  TripleBuffer<Interface2CtrlData> interface2CtrlData;
244 
245  struct DSRTDebugInfo
246  {
247  StringFloatDictionary desired_torques;
248  };
249  TripleBuffer<DSRTDebugInfo> debugDataInfo;
250 
251  struct Ctrl2InterfaceData
252  {
253  float guardZVel;
254  };
255  TripleBuffer<Ctrl2InterfaceData> ctrl2InterfaceData;
256 
257  std::vector<const SensorValue1DoFActuatorTorque*> left_torqueSensors;
258  std::vector<const SensorValue1DoFGravityTorque*> left_gravityTorqueSensors;
259  std::vector<const SensorValue1DoFActuatorVelocity*> left_velocitySensors;
260  std::vector<const SensorValue1DoFActuatorPosition*> left_positionSensors;
261 
262  std::vector<const SensorValue1DoFActuatorTorque*> right_torqueSensors;
263  std::vector<const SensorValue1DoFGravityTorque*> right_gravityTorqueSensors;
264  std::vector<const SensorValue1DoFActuatorVelocity*> right_velocitySensors;
265  std::vector<const SensorValue1DoFActuatorPosition*> right_positionSensors;
266 
267  const SensorValueForceTorque* leftForceTorque;
268  const SensorValueForceTorque* rightForceTorque;
269 
270  std::vector<ControlTarget1DoFActuatorTorque*> left_torque_targets;
271  std::vector<ControlTarget1DoFActuatorTorque*> right_torque_targets;
272 
273  VirtualRobot::RobotNodePtr left_arm_tcp;
274  VirtualRobot::RobotNodePtr right_arm_tcp;
275 
276  VirtualRobot::RobotNodePtr left_sensor_frame;
277  VirtualRobot::RobotNodePtr right_sensor_frame;
278 
279  VirtualRobot::DifferentialIKPtr left_ik;
280  VirtualRobot::DifferentialIKPtr right_ik;
281 
282  Eigen::Quaternionf left_desiredQuaternion;
283  Eigen::Quaternionf right_desiredQuaternion;
284 
285  Eigen::Vector3f left_currentTCPLinearVelocity_filtered;
286  Eigen::Vector3f left_currentTCPAngularVelocity_filtered;
287  Eigen::Vector3f right_currentTCPLinearVelocity_filtered;
288  Eigen::Vector3f right_currentTCPAngularVelocity_filtered;
289 
290  Eigen::VectorXf left_jointVelocity_filtered;
291  Eigen::VectorXf right_jointVelocity_filtered;
292 
293  Eigen::VectorXf left_desiredTorques_filtered;
294  Eigen::VectorXf right_desiredTorques_filtered;
295  Eigen::Vector3f left_tcpDesiredTorque_filtered;
296  Eigen::Vector3f right_tcpDesiredTorque_filtered;
297 
298  float smooth_startup;
299 
300  DSJointCarryControllerConfigPtr cfg;
301  float filterTimeConstant;
302 
303  std::vector<std::string> left_jointNames;
304  std::vector<std::string> right_jointNames;
305 
306  float posiKp;
307  float v_max;
308  std::vector<float> Damping;
309  float oriKp;
310  float oriDamping;
311  float torqueLimit;
312  float null_torqueLimit;
313  float nullspaceKp;
314  float nullspaceDamping;
315  Eigen::VectorXf left_qnullspace;
316  Eigen::VectorXf right_qnullspace;
317 
318 
319  Eigen::Quaternionf desired_guardOri;
320 
321  float positionErrorTolerance;
322  bool controllerStopRequested = false;
323  bool controllerRunFinished = false;
324 
325  // NJointController interface
326  protected:
328 
329  // NJointController interface
330  protected:
333 
334  };
335 
336 }
337 
338 #endif
armarx::control::ds_controller::JointCarryGMMMotionGen::JointCarryGMMMotionGen
JointCarryGMMMotionGen(const std::string &fileName)
Definition: DSJointCarryController.h:65
armarx::control::ds_controller::DSJointCarryControllerControlData::rightDesiredLinearVelocity
Eigen::Vector3f rightDesiredLinearVelocity
Definition: DSJointCarryController.h:159
armarx::control::ds_controller::JointCarryGMRParameters::dim_
int dim_
Definition: DSJointCarryController.h:51
boost::shared_ptr< GMRDynamics >
Vector
Eigen::Matrix< T, 3, 1 > Vector
Definition: UnscentedKalmanFilterTest.cpp:36
JSONObject.h
armarx::NJointControllerWithTripleBuffer
Definition: NJointControllerWithTripleBuffer.h:10
RobotUnit.h
armarx::JSONObject
The JSONObject class is used to represent and (de)serialize JSON objects.
Definition: JSONObject.h:43
armarx::DebugObserverInterfacePrx
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
Definition: JointController.h:44
armarx::control::ds_controller::JointCarryGMRParameters::dt_
double dt_
Definition: DSJointCarryController.h:56
SensorValueForceTorque.h
armarx::control::ds_controller
Definition: DSJointCarryController.cpp:28
armarx::NJointControllerBase::ConfigPtrT
NJointControllerConfigPtr ConfigPtrT
Definition: NJointControllerBase.h:586
armarx::control::ds_controller::JointCarryGMRParameters
Definition: DSJointCarryController.h:48
armarx::control::ds_controller::DSJointCarryController::setDesiredGuardOri
void setDesiredGuardOri(const Ice::FloatSeq &desiredOrientationInRobotBase, const Ice::Current &)
Definition: DSJointCarryController.cpp:585
armarx::control::ds_controller::JointCarryGMMMotionGen::guard_gmm
JointCarryGMMPtr guard_gmm
Definition: DSJointCarryController.h:70
armarx::control::ds_controller::DSJointCarryController::setGuardOrientation
void setGuardOrientation(const Ice::FloatSeq &guardOrientationInRobotBase, const Ice::Current &)
Definition: DSJointCarryController.cpp:562
armarx::control::ds_controller::DSJointCarryController::onPublish
void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &)
Definition: DSJointCarryController.cpp:690
armarx::SensorAndControl
detail::ControlThreadOutputBufferEntry SensorAndControl
Definition: NJointControllerBase.h:72
armarx::control::ds_controller::DSJointCarryController::rtPreActivateController
void rtPreActivateController()
This function is called before the controller is activated.
Definition: DSJointCarryController.cpp:711
armarx::control::ds_controller::DSJointCarryController::onInitNJointController
void onInitNJointController()
Definition: DSJointCarryController.cpp:33
armarx::control::ds_controller::DSJointCarryController::DSJointCarryController
DSJointCarryController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Definition: DSJointCarryController.cpp:70
armarx::control::ds_controller::JointCarryGMMMotionGen::v_max
float v_max
Definition: DSJointCarryController.h:76
armarx::DSJointCarryControllerInterface::getGMMVel
float getGMMVel()
armarx::DSJointCarryControllerInterface
Definition: DSControllerInterface.ice:171
IceInternal::Handle< JSONObject >
armarx::control::ds_controller::DSJointCarryController::controllerRun
void controllerRun()
Definition: DSJointCarryController.cpp:276
GMRDynamics
Definition: GMRDynamics.h:20
armarx::control::ds_controller::JointCarryGMRParameters::attractor_
std::vector< double > attractor_
Definition: DSJointCarryController.h:55
armarx::control::ds_controller::JointCarryGMMMotionGenPtr
boost::shared_ptr< JointCarryGMMMotionGen > JointCarryGMMMotionGenPtr
Definition: DSJointCarryController.h:152
armarx::control::ds_controller::JointCarryGMMMotionGen
Definition: DSJointCarryController.h:60
armarx::control::ds_controller::JointCarryGMRParameters::K_gmm_
int K_gmm_
Definition: DSJointCarryController.h:50
armarx::control::ds_controller::DSJointCarryControllerControlData::leftDesiredLinearVelocity
Eigen::Vector3f leftDesiredLinearVelocity
Definition: DSJointCarryController.h:157
armarx::control::ds_controller::JointCarryGMMMotionGen::getGMMParamsFromJsonFile
void getGMMParamsFromJsonFile(const std::string &fileName)
Definition: DSJointCarryController.h:78
armarx::control::ds_controller::DSJointCarryControllerControlData::rightDesiredAngularError
Eigen::Vector3f rightDesiredAngularError
Definition: DSJointCarryController.h:160
armarx::control::ds_controller::DSJointCarryController::rtPostDeactivateController
void rtPostDeactivateController()
This function is called after the controller is deactivated.
Definition: DSJointCarryController.cpp:716
ControlTarget1DoFActuator.h
Eigen::Quaternionf
Quaternion< float, 0 > Quaternionf
Definition: EigenForwardDeclarations.h:61
armarx::control::ds_controller::JointCarryGMRParameters::Mu_
std::vector< double > Mu_
Definition: DSJointCarryController.h:53
armarx::control::ds_controller::JointCarryGMMMotionGen::scaling
float scaling
Definition: DSJointCarryController.h:75
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::control::ds_controller::JointCarryGMMMotionGen::updateDesiredVelocity
void updateDesiredVelocity(const Eigen::Vector3f &positionInMeter, float positionErrorToleranceInMeter)
Definition: DSJointCarryController.h:108
armarx::control::ds_controller::JointCarryGMMMotionGen::guard_desiredVelocity
Eigen::Vector3f guard_desiredVelocity
Definition: DSJointCarryController.h:73
NJointController.h
armarx::control::ds_controller::DSJointCarryController::getClassName
std::string getClassName(const Ice::Current &) const
Definition: DSJointCarryController.h:195
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::control::ds_controller::DSJointCarryController::setGuardObsAvoidVel
void setGuardObsAvoidVel(const Ice::FloatSeq &guardVel, const Ice::Current &)
Definition: DSJointCarryController.cpp:608
armarx::NJointControllerWithTripleBuffer< DSJointCarryControllerControlData >::MutexType
std::recursive_mutex MutexType
Definition: NJointControllerWithTripleBuffer.h:13
armarx::control::ds_controller::JointCarryGMRParameters::Sigma_
std::vector< double > Sigma_
Definition: DSJointCarryController.h:54
armarx::Quaternion< float, 0 >
armarx::control::ds_controller::DSJointCarryController::rtRun
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
TODO make protected and use attorneys.
Definition: DSJointCarryController.cpp:374
armarx::control::ds_controller::JointCarryGMMMotionGen::JointCarryGMMMotionGen
JointCarryGMMMotionGen()
Definition: DSJointCarryController.h:63
armarx::control::ds_controller::DSJointCarryController
Brief description of class DSJointCarryController.
Definition: DSJointCarryController.h:175
armarx::control::ds_controller::JointCarryGMMMotionGen::guard_gmmParas
JointCarryGMRParameters guard_gmmParas
Definition: DSJointCarryController.h:71
armarx::control::ds_controller::JointCarryGMRParameters::Priors_
std::vector< double > Priors_
Definition: DSJointCarryController.h:52
armarx::control::ds_controller::DSJointCarryControllerControlData::leftDesiredAngularError
Eigen::Vector3f leftDesiredAngularError
Definition: DSJointCarryController.h:158
armarx::control::ds_controller::DSJointCarryController::setRotationStiffness
void setRotationStiffness(const Ice::FloatSeq &rotationStiffness, const Ice::Current &)
Definition: DSJointCarryController.cpp:598
armarx::control::ds_controller::JointCarryGMMMotionGen::guard_target
Eigen::Vector3f guard_target
Definition: DSJointCarryController.h:72
armarx::control::ds_controller::DSJointCarryController::setGuardInHandPosition
void setGuardInHandPosition(const Ice::FloatSeq &guardPositionToHandInMeter, const Ice::Current &)
Definition: DSJointCarryController.cpp:575
armarx::control::ds_controller::DSJointCarryController::onDisconnectNJointController
void onDisconnectNJointController()
Definition: DSJointCarryController.cpp:58
GMRDynamics.h
armarx::DebugDrawerInterfacePrx
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
Definition: JointController.h:40
armarx::control::ds_controller::JointCarryGMMPtr
boost::shared_ptr< GMRDynamics > JointCarryGMMPtr
Definition: DSJointCarryController.h:46
armarx::control::ds_controller::DSJointCarryControllerControlData
Definition: DSJointCarryController.h:154
SensorValue1DoFActuator.h
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::TripleBuffer< DSJointCarryControllerSensorData >