ImpedanceController.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
10 #include <rtm/CorbaNaming.h>
11 #include <hrpModel/Link.h>
12 #include <hrpModel/Sensor.h>
13 #include <hrpModel/ModelLoaderUtil.h>
14 #include "ImpedanceController.h"
15 #include "JointPathEx.h"
16 #include <hrpModel/JointPath.h>
17 #include <hrpUtil/MatrixSolvers.h>
18 #include "hrpsys/util/Hrpsys.h"
19 #include <boost/assign.hpp>
20 
21 #define MAX_TRANSITION_COUNT (static_cast<int>(2/m_dt))
23 
24 // Module specification
25 // <rtc-template block="module_spec">
26 static const char* impedancecontroller_spec[] =
27  {
28  "implementation_id", "ImpedanceController",
29  "type_name", "ImpedanceController",
30  "description", "impedance controller component",
31  "version", HRPSYS_PACKAGE_VERSION,
32  "vendor", "AIST",
33  "category", "example",
34  "activity_type", "DataFlowComponent",
35  "max_instance", "10",
36  "language", "C++",
37  "lang_type", "compile",
38  // Configuration variables
39  "conf.default.debugLevel", "0",
40  ""
41  };
42 // </rtc-template>
43 
45  : RTC::DataFlowComponentBase(manager),
46  // <rtc-template block="initializer">
47  m_qCurrentIn("qCurrent", m_qCurrent),
48  m_qRefIn("qRef", m_qRef),
49  m_basePosIn("basePosIn", m_basePos),
50  m_baseRpyIn("baseRpyIn", m_baseRpy),
51  m_rpyIn("rpy", m_rpy),
52  m_qOut("q", m_q),
53  m_ImpedanceControllerServicePort("ImpedanceControllerService"),
54  // </rtc-template>
55  m_robot(hrp::BodyPtr()),
56  m_debugLevel(0),
57  dummy(0),
58  use_sh_base_pos_rpy(false)
59 {
60  m_service0.impedance(this);
61 }
62 
64 {
65 }
66 
67 
69 {
70  std::cerr << "[" << m_profile.instance_name << "] onInitialize()" << std::endl;
71  bindParameter("debugLevel", m_debugLevel, "0");
72 
73  // Registration: InPort/OutPort/Service
74  // <rtc-template block="registration">
75  // Set InPort buffers
76  addInPort("qCurrent", m_qCurrentIn);
77  addInPort("qRef", m_qRefIn);
78  addInPort("basePosIn", m_basePosIn);
79  addInPort("baseRpyIn", m_baseRpyIn);
80  addInPort("rpy", m_rpyIn);
81 
82  // Set OutPort buffer
83  addOutPort("q", m_qOut);
84 
85  // Set service provider to Ports
86  m_ImpedanceControllerServicePort.registerProvider("service0", "ImpedanceControllerService", m_service0);
87 
88  // Set service consumers to Ports
89 
90  // Set CORBA Service Ports
92 
93  // </rtc-template>
94  // <rtc-template block="bind_config">
95  // Bind variables and configuration variable
96 
97  // </rtc-template>
98 
100  coil::stringTo(m_dt, prop["dt"].c_str());
101 
102  m_robot = hrp::BodyPtr(new hrp::Body());
103 
104  RTC::Manager& rtcManager = RTC::Manager::instance();
105  std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
106  int comPos = nameServer.find(",");
107  if (comPos < 0){
108  comPos = nameServer.length();
109  }
110  nameServer = nameServer.substr(0, comPos);
111  RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
112  if (!loadBodyFromModelLoader(m_robot, prop["model"].c_str(),
113  CosNaming::NamingContext::_duplicate(naming.getRootContext())
114  )){
115  std::cerr << "[" << m_profile.instance_name << "] failed to load model[" << prop["model"] << "]" << std::endl;
116  return RTC::RTC_ERROR;
117  }
118 
119 
120  // Setting for wrench data ports (real + virtual)
121  std::vector<std::string> fsensor_names;
122  // find names for real force sensors
123  unsigned int npforce = m_robot->numSensors(hrp::Sensor::FORCE);
124  for (unsigned int i=0; i<npforce; i++){
125  fsensor_names.push_back(m_robot->sensor(hrp::Sensor::FORCE, i)->name);
126  }
127  // load virtual force sensors
128  readVirtualForceSensorParamFromProperties(m_vfs, m_robot, prop["virtual_force_sensor"], std::string(m_profile.instance_name));
129  unsigned int nvforce = m_vfs.size();
130  for (unsigned int i=0; i<nvforce; i++){
131  for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it = m_vfs.begin(); it != m_vfs.end(); it++ ) {
132  if (it->second.id == (int)i) fsensor_names.push_back(it->first);
133  }
134  }
135  // add ports for all force sensors
136  unsigned int nforce = npforce + nvforce;
137  m_force.resize(nforce);
138  m_forceIn.resize(nforce);
139  m_ref_force.resize(nforce);
140  m_ref_forceIn.resize(nforce);
141  std::cerr << "[" << m_profile.instance_name << "] force sensor ports" << std::endl;
142  for (unsigned int i=0; i<nforce; i++){
143  // actual inport
144  m_forceIn[i] = new InPort<TimedDoubleSeq>(fsensor_names[i].c_str(), m_force[i]);
145  m_force[i].data.length(6);
146  registerInPort(fsensor_names[i].c_str(), *m_forceIn[i]);
147  // ref inport
148  m_ref_force[i].data.length(6);
149  for (unsigned int j=0; j<6; j++) m_ref_force[i].data[j] = 0.0;
150  m_ref_forceIn[i] = new InPort<TimedDoubleSeq>(std::string("ref_"+fsensor_names[i]+"In").c_str(), m_ref_force[i]);
151  registerInPort(std::string("ref_"+fsensor_names[i]+"In").c_str(), *m_ref_forceIn[i]);
152  std::cerr << "[" << m_profile.instance_name << "] name = " << fsensor_names[i] << std::endl;
153  }
154 
155  for (unsigned int i=0; i<m_forceIn.size(); i++){
156  abs_forces.insert(std::pair<std::string, hrp::Vector3>(m_forceIn[i]->name(), hrp::Vector3::Zero()));
157  abs_moments.insert(std::pair<std::string, hrp::Vector3>(m_forceIn[i]->name(), hrp::Vector3::Zero()));
158  }
159 
160  unsigned int dof = m_robot->numJoints();
161  for ( unsigned int i = 0 ; i < dof; i++ ){
162  if ( (int)i != m_robot->joint(i)->jointId ) {
163  std::cerr << "[" << m_profile.instance_name << "] jointId is not equal to the index number" << std::endl;
164  return RTC::RTC_ERROR;
165  }
166  }
167 
168  // setting from conf file
169  // rleg,TARGET_LINK,BASE_LINK,x,y,z,rx,ry,rz,rth #<=pos + rot (axis+angle)
170  coil::vstring end_effectors_str = coil::split(prop["end_effectors"], ",");
171  std::map<std::string, std::string> base_name_map;
172  if (end_effectors_str.size() > 0) {
173  size_t prop_num = 10;
174  size_t num = end_effectors_str.size()/prop_num;
175  for (size_t i = 0; i < num; i++) {
176  std::string ee_name, ee_target, ee_base;
177  coil::stringTo(ee_name, end_effectors_str[i*prop_num].c_str());
178  coil::stringTo(ee_target, end_effectors_str[i*prop_num+1].c_str());
179  coil::stringTo(ee_base, end_effectors_str[i*prop_num+2].c_str());
180  ee_trans eet;
181  for (size_t j = 0; j < 3; j++) {
182  coil::stringTo(eet.localPos(j), end_effectors_str[i*prop_num+3+j].c_str());
183  }
184  double tmpv[4];
185  for (int j = 0; j < 4; j++ ) {
186  coil::stringTo(tmpv[j], end_effectors_str[i*prop_num+6+j].c_str());
187  }
188  eet.localR = Eigen::AngleAxis<double>(tmpv[3], hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix(); // rotation in VRML is represented by axis + angle
189  eet.target_name = ee_target;
190  ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
191  base_name_map.insert(std::pair<std::string, std::string>(ee_name, ee_base));
192  std::cerr << "[" << m_profile.instance_name << "] End Effector [" << ee_name << "]" << ee_target << " " << ee_base << std::endl;
193  std::cerr << "[" << m_profile.instance_name << "] target = " << ee_target << ", base = " << ee_base << std::endl;
194  std::cerr << "[" << m_profile.instance_name << "] localPos = " << eet.localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
195  std::cerr << "[" << m_profile.instance_name << "] localR = " << eet.localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "\n", " [", "]")) << std::endl;
196  }
197  }
198 
199  // initialize impedance params
200  std::cerr << "[" << m_profile.instance_name << "] Add impedance params" << std::endl;
201  for (unsigned int i=0; i<m_forceIn.size(); i++){
202  std::string sensor_name = m_forceIn[i]->name();
203  hrp::ForceSensor* sensor = m_robot->sensor<hrp::ForceSensor>(sensor_name);
204  std::string sensor_link_name;
205  if ( sensor ) {
206  // real force sensor
207  sensor_link_name = sensor->link->name;
208  } else if ( m_vfs.find(sensor_name) != m_vfs.end()) {
209  // virtual force sensor
210  sensor_link_name = m_vfs[sensor_name].link->name;
211  } else {
212  std::cerr << "[" << m_profile.instance_name << "] unknown force param" << std::endl;
213  continue;
214  }
215  // 1. Check whether adequate ee_map exists for the sensor.
216  std::string ee_name;
217  bool is_ee_exists = false;
218  for ( std::map<std::string, ee_trans>::iterator it = ee_map.begin(); it != ee_map.end(); it++ ) {
219  hrp::Link* alink = m_robot->link(it->second.target_name);
220  std::string tmp_base_name = base_name_map[it->first];
221  while (alink != NULL && alink->name != tmp_base_name && !is_ee_exists) {
222  if ( alink->name == sensor_link_name ) {
223  is_ee_exists = true;
224  ee_name = it->first;
225  }
226  alink = alink->parent;
227  }
228  }
229  if (!is_ee_exists) {
230  std::cerr << "[" << m_profile.instance_name << "] No such ee setting for " << sensor_name << " and " << sensor_link_name << "!!. Impedance param for " << sensor_name << " cannot be added!!" << std::endl;
231  continue;
232  }
233  // 2. Check whether already impedance param exists, which has the same target link as the sensor.
234  if (m_impedance_param.find(ee_name) != m_impedance_param.end()) {
235  std::cerr << "[" << m_profile.instance_name << "] Already impedance param (target_name=" << sensor_link_name << ", ee_name=" << ee_name << ") exists!!. Impedance param for " << sensor_name << " cannot be added!!" << std::endl;
236  continue;
237  }
238  // 3. Check whether joint path is adequate.
239  hrp::Link* target_link = m_robot->link(ee_map[ee_name].target_name);
240  ImpedanceParam p;
241  p.manip = hrp::JointPathExPtr(new hrp::JointPathEx(m_robot, m_robot->link(base_name_map[ee_name]), target_link, m_dt, false, std::string(m_profile.instance_name)));
242  if ( ! p.manip ) {
243  std::cerr << "[" << m_profile.instance_name << "] Invalid joint path from " << base_name_map[ee_name] << " to " << target_link->name << "!! Impedance param for " << sensor_name << " cannot be added!!" << std::endl;
244  continue;
245  }
246  // 4. Set impedance param
247  p.transition_joint_q.resize(m_robot->numJoints());
248  p.sensor_name = sensor_name;
249  m_impedance_param[ee_name] = p;
250  std::cerr << "[" << m_profile.instance_name << "] sensor = " << sensor_name << ", sensor-link = " << sensor_link_name << ", ee_name = " << ee_name << ", ee-link = " << target_link->name << std::endl;
251  }
252 
253  std::vector<std::pair<hrp::Link*, hrp::Link*> > interlocking_joints;
254  readInterlockingJointsParamFromProperties(interlocking_joints, m_robot, prop["interlocking_joints"], std::string(m_profile.instance_name));
255  if (interlocking_joints.size() > 0) {
256  for ( std::map<std::string, ImpedanceParam>::iterator it = m_impedance_param.begin(); it != m_impedance_param.end(); it++ ) {
257  std::cerr << "[" << m_profile.instance_name << "] Interlocking Joints for [" << it->first << "]" << std::endl;
258  it->second.manip->setInterlockingJointPairIndices(interlocking_joints, std::string(m_profile.instance_name));
259  }
260  }
261 
262  // allocate memory for outPorts
263  m_q.data.length(dof);
264  qrefv.resize(dof);
265  loop = 0;
266 
267  return RTC::RTC_OK;
268 }
269 
270 
271 
273 {
274  return RTC::RTC_OK;
275 }
276 
277 /*
278  RTC::ReturnCode_t ImpedanceController::onStartup(RTC::UniqueId ec_id)
279  {
280  return RTC::RTC_OK;
281  }
282 */
283 
284 /*
285  RTC::ReturnCode_t ImpedanceController::onShutdown(RTC::UniqueId ec_id)
286  {
287  return RTC::RTC_OK;
288  }
289 */
290 
292 {
293  std::cerr << "[" << m_profile.instance_name<< "] onActivated(" << ec_id << ")" << std::endl;
294 
295  return RTC::RTC_OK;
296 }
297 
299 {
300  std::cerr << "[" << m_profile.instance_name<< "] onDeactivated(" << ec_id << ")" << std::endl;
301  for ( std::map<std::string, ImpedanceParam>::iterator it = m_impedance_param.begin(); it != m_impedance_param.end(); it++ ) {
302  if (it->second.is_active) {
304  it->second.transition_count = 1;
305  }
306  }
307  return RTC::RTC_OK;
308 }
309 
310 #define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 )
312 {
313  //std::cout << "ImpedanceController::onExecute(" << ec_id << ")" << std::endl;
314  loop ++;
315 
316  // check dataport input
317  for (unsigned int i=0; i<m_forceIn.size(); i++){
318  if ( m_forceIn[i]->isNew() ) {
319  m_forceIn[i]->read();
320  }
321  if ( m_ref_forceIn[i]->isNew() ) {
322  m_ref_forceIn[i]->read();
323  }
324  }
325  if (m_basePosIn.isNew()) {
326  m_basePosIn.read();
327  }
328  if (m_baseRpyIn.isNew()) {
329  m_baseRpyIn.read();
330  }
331  if (m_rpyIn.isNew()) {
332  m_rpyIn.read();
333  }
334  if (m_qCurrentIn.isNew()) {
335  m_qCurrentIn.read();
336  }
337  if (m_qRefIn.isNew()) {
338  m_qRefIn.read();
339  m_q.tm = m_qRef.tm;
340  }
341  if ( m_qRef.data.length() == m_robot->numJoints() &&
342  m_qCurrent.data.length() == m_robot->numJoints() ) {
343 
344  if ( DEBUGP ) {
345  std::cerr << "[" << m_profile.instance_name << "] qRef = ";
346  for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
347  std::cerr << " " << m_qRef.data[i];
348  }
349  std::cerr << std::endl;
350  }
351 
352  Guard guard(m_mutex);
353 
354  {
355  // Store current robot state
356  hrp::dvector qorg(m_robot->numJoints());
357  for ( unsigned int i = 0; i < m_robot->numJoints(); i++ ){
358  qorg[i] = m_robot->joint(i)->q;
359  }
360  // Get target parameters mainly from SequencePlayer
362  // Calculate act/ref absolute force/moment
363  calcForceMoment();
364  // back to impedance robot model (only for controlled joint)
365  for ( std::map<std::string, ImpedanceParam>::iterator it = m_impedance_param.begin(); it != m_impedance_param.end(); it++ ) {
366  ImpedanceParam& param = it->second;
367  if (param.is_active) {
368  for ( unsigned int j = 0; j < param.manip->numJoints(); j++ ){
369  int i = param.manip->joint(j)->jointId;
370  m_robot->joint(i)->q = qorg[i];
371  }
372  }
373  }
374  m_robot->calcForwardKinematics();
375 
376  }
377 
378  // Check if all limb is non-is_active mode.
379  bool is_active = false;
380  for ( std::map<std::string, ImpedanceParam>::iterator it = m_impedance_param.begin(); it != m_impedance_param.end(); it++ ) {
381  is_active = is_active || it->second.is_active;
382  }
383  if ( !is_active ) {
384  for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
385  m_q.data[i] = m_qRef.data[i];
386  m_robot->joint(i)->q = m_qRef.data[i];
387  }
388  m_qOut.write();
389  return RTC_OK;
390  }
391 
392  // Caculate ImpedanceControl and solve IK
394 
395  // Output
396  if ( m_q.data.length() != 0 ) { // initialized
397  for ( unsigned int i = 0; i < m_robot->numJoints(); i++ ){
398  m_q.data[i] = m_robot->joint(i)->q;
399  }
400  m_qOut.write();
401  if ( DEBUGP ) {
402  std::cerr << "[" << m_profile.instance_name << "] q = ";
403  for ( unsigned int i = 0; i < m_q.data.length(); i++ ){
404  std::cerr << " " << m_q.data[i];
405  }
406  std::cerr << std::endl;
407  }
408  }
409  } else {
410  if ( DEBUGP || loop % 100 == 0 ) {
411  std::cerr << "ImpedanceController is not working..." << std::endl;
412  std::cerr << " m_qRef " << m_qRef.data.length() << std::endl;
413  std::cerr << " m_qCurrent " << m_qCurrent.data.length() << std::endl;
414  }
415  }
416  return RTC::RTC_OK;
417 }
418 
419 /*
420  RTC::ReturnCode_t ImpedanceController::onAborting(RTC::UniqueId ec_id)
421  {
422  return RTC::RTC_OK;
423  }
424 */
425 
426 /*
427  RTC::ReturnCode_t ImpedanceController::onError(RTC::UniqueId ec_id)
428  {
429  return RTC::RTC_OK;
430  }
431 */
432 
433 /*
434  RTC::ReturnCode_t ImpedanceController::onReset(RTC::UniqueId ec_id)
435  {
436  return RTC::RTC_OK;
437  }
438 */
439 
440 /*
441  RTC::ReturnCode_t ImpedanceController::onStateUpdate(RTC::UniqueId ec_id)
442  {
443  return RTC::RTC_OK;
444  }
445 */
446 
447 /*
448  RTC::ReturnCode_t ImpedanceController::onRateChanged(RTC::UniqueId ec_id)
449  {
450  return RTC::RTC_OK;
451  }
452 */
453 
455 {
456  // Get reference robot state
457  for ( unsigned int i = 0; i < m_robot->numJoints(); i++ ){
458  m_robot->joint(i)->q = m_qRef.data[i];
459  qrefv[i] = m_qRef.data[i];
460  }
461  m_robot->rootLink()->p = hrp::Vector3(m_basePos.data.x, m_basePos.data.y, m_basePos.data.z);
462  m_robot->rootLink()->R = hrp::rotFromRpy(m_baseRpy.data.r, m_baseRpy.data.p, m_baseRpy.data.y);
463  m_robot->calcForwardKinematics();
464  // Fix leg for legged robot
465  if ( (ee_map.find("rleg") != ee_map.end() && ee_map.find("lleg") != ee_map.end()) // if legged robot
466  && !use_sh_base_pos_rpy ) {
467  // TODO
468  // Tempolarily modify root coords to fix foot pos rot
469  // This will be removed after seq outputs adequate waistRPY discussed in https://github.com/fkanehiro/hrpsys-base/issues/272
470 
471  // get current foot mid pos + rot
472  std::vector<hrp::Vector3> foot_pos;
473  std::vector<hrp::Matrix33> foot_rot;
474  std::vector<std::string> leg_names;
475  leg_names.push_back("rleg");
476  leg_names.push_back("lleg");
477  for (size_t i = 0; i < leg_names.size(); i++) {
478  hrp::Link* target_link = m_robot->link(ee_map[leg_names[i]].target_name);
479  foot_pos.push_back(target_link->p + target_link->R * ee_map[leg_names[i]].localPos);
480  foot_rot.push_back(target_link->R * ee_map[leg_names[i]].localR);
481  }
482  hrp::Vector3 current_foot_mid_pos ((foot_pos[0]+foot_pos[1])/2.0);
483  hrp::Matrix33 current_foot_mid_rot;
484  rats::mid_rot(current_foot_mid_rot, 0.5, foot_rot[0], foot_rot[1]);
485  // calculate fix pos + rot
486  hrp::Vector3 new_foot_mid_pos(current_foot_mid_pos);
487  hrp::Matrix33 new_foot_mid_rot;
488  {
489  hrp::Vector3 ex = hrp::Vector3::UnitX();
490  hrp::Vector3 ez = hrp::Vector3::UnitZ();
491  hrp::Vector3 xv1 (current_foot_mid_rot * ex);
492  xv1(2) = 0.0;
493  xv1.normalize();
494  hrp::Vector3 yv1(ez.cross(xv1));
495  new_foot_mid_rot(0,0) = xv1(0); new_foot_mid_rot(1,0) = xv1(1); new_foot_mid_rot(2,0) = xv1(2);
496  new_foot_mid_rot(0,1) = yv1(0); new_foot_mid_rot(1,1) = yv1(1); new_foot_mid_rot(2,1) = yv1(2);
497  new_foot_mid_rot(0,2) = ez(0); new_foot_mid_rot(1,2) = ez(1); new_foot_mid_rot(2,2) = ez(2);
498  }
499  // fix root pos + rot to fix "coords" = "current_foot_mid_xx"
500  hrp::Matrix33 tmpR (new_foot_mid_rot * current_foot_mid_rot.transpose());
501  m_robot->rootLink()->p = new_foot_mid_pos + tmpR * (m_robot->rootLink()->p - current_foot_mid_pos);
502  rats::rotm3times(m_robot->rootLink()->R, tmpR, m_robot->rootLink()->R);
503  m_robot->calcForwardKinematics();
504  }
505 
506  // Set sequencer position and orientation to target_p0 and target_r0
507  for ( std::map<std::string, ImpedanceParam>::iterator it = m_impedance_param.begin(); it != m_impedance_param.end(); it++ ) {
508  ImpedanceParam& param = it->second;
509  std::string target_name = ee_map[it->first].target_name;
510  param.target_p0 = m_robot->link(target_name)->p + m_robot->link(target_name)->R * ee_map[it->first].localPos;
511  param.target_r0 = m_robot->link(target_name)->R * ee_map[it->first].localR;
513  }
514 };
515 
517 {
518  for (unsigned int i=0; i<m_forceIn.size(); i++){
519  if ( m_force[i].data.length()==6 ) {
520  std::string sensor_name = m_forceIn[i]->name();
521  hrp::ForceSensor* sensor = m_robot->sensor<hrp::ForceSensor>(sensor_name);
522  hrp::Vector3 data_p(m_force[i].data[0], m_force[i].data[1], m_force[i].data[2]);
523  hrp::Vector3 data_r(m_force[i].data[3], m_force[i].data[4], m_force[i].data[5]);
524  hrp::Vector3 ref_data_p(m_ref_force[i].data[0], m_ref_force[i].data[1], m_ref_force[i].data[2]);
525  hrp::Vector3 ref_data_r(m_ref_force[i].data[3], m_ref_force[i].data[4], m_ref_force[i].data[5]);
526  if ( DEBUGP ) {
527  std::cerr << "[" << m_profile.instance_name << "] force and moment [" << sensor_name << "]" << std::endl;
528  std::cerr << "[" << m_profile.instance_name << "] sensor force = " << data_p.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[N]" << std::endl;
529  std::cerr << "[" << m_profile.instance_name << "] sensor moment = " << data_r.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[Nm]" << std::endl;
530  std::cerr << "[" << m_profile.instance_name << "] reference force = " << ref_data_p.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[N]" << std::endl;
531  std::cerr << "[" << m_profile.instance_name << "] reference moment = " << ref_data_r.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[Nm]" << std::endl;
532  }
533  hrp::Matrix33 sensorR;
534  hrp::Vector3 sensorPos, eePos;
535  if ( sensor ) {
536  // real force sensor
537  sensorR = sensor->link->R * sensor->localR;
538  sensorPos = sensor->link->p + sensorR * sensor->localPos;
539  } else if ( m_vfs.find(sensor_name) != m_vfs.end()) {
540  // virtual force sensor
541  if ( DEBUGP ) {
542  std::cerr << "[" << m_profile.instance_name << "] sensorR = " << m_vfs[sensor_name].localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "\n", " [", "]")) << std::endl;
543  }
544  sensorR = m_vfs[sensor_name].link->R * m_vfs[sensor_name].localR;
545  sensorPos = m_vfs[sensor_name].link->p + m_vfs[sensor_name].link->R * m_vfs[sensor_name].localPos;
546  } else {
547  std::cerr << "[" << m_profile.instance_name << "] unknown force param" << std::endl;
548  }
549  abs_forces[sensor_name] = sensorR * data_p;
550  for ( std::map<std::string, ImpedanceParam>::iterator it = m_impedance_param.begin(); it != m_impedance_param.end(); it++ ) {
551  if ( it->second.sensor_name == sensor_name ) eePos = it->second.target_p0;
552  }
553  abs_moments[sensor_name] = sensorR * data_r + (sensorPos - eePos).cross(abs_forces[sensor_name]);
554  // End effector local frame
555  // hrp::Matrix33 eeR (parentlink->R * ee_map[parentlink->name].localR);
556  // abs_ref_forces[sensor_name] = eeR * ref_data_p;
557  // abs_ref_moments[sensor_name] = eeR * ref_data_r;
558  // World frame
559  abs_ref_forces[sensor_name] = ref_data_p;
560  abs_ref_moments[sensor_name] = ref_data_r;
561  if ( DEBUGP ) {
562  std::cerr << "[" << m_profile.instance_name << "] abs force = " << abs_forces[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[N]" << std::endl;
563  std::cerr << "[" << m_profile.instance_name << "] abs moment = " << abs_moments[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[Nm]" << std::endl;
564  std::cerr << "[" << m_profile.instance_name << "] abs ref force = " << abs_ref_forces[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[N]" << std::endl;
565  std::cerr << "[" << m_profile.instance_name << "] abs ref moment = " << abs_ref_moments[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[Nm]" << std::endl;
566  }
567  }
568  }
569 };
570 
572 {
573  std::map<std::string, ImpedanceParam>::iterator it = m_impedance_param.begin();
574  while(it != m_impedance_param.end()){
575  ImpedanceParam& param = it->second;
576  if (param.is_active) {
577  if (DEBUGP) {
578  std::cerr << "[" << m_profile.instance_name << "] impedance mode " << it->first << " transition count = " << param.transition_count << ", ";
579  std::cerr << "MDK = " << param.M_p << " " << param.D_p << " " << param.K_p << ", ";
580  std::cerr << "MDK = " << param.M_r << " " << param.D_r << " " << param.K_r << ", ";
581  std::cerr << "ref_force = " << param.ref_force[0] << " " << param.ref_force[1] << " " << param.ref_force[2] << ", ";
582  std::cerr << "ref_moment = " << param.ref_moment[0] << " " << param.ref_moment[1] << " " << param.ref_moment[2] << std::endl;
583  }
584  if ( param.transition_count > 0 ) {
585  // set m_robot to qRef when deleting status
586  hrp::JointPathExPtr manip = param.manip;
587  // transition_smooth_gain moves from 0 to 1
588  // (/ (log (/ (- 1 0.99) 0.99)) 0.5)
589  double transition_smooth_gain = 1/(1+exp(-9.19*((static_cast<double>(MAX_TRANSITION_COUNT - param.transition_count) / MAX_TRANSITION_COUNT) - 0.5)));
590  for ( unsigned int j = 0; j < manip->numJoints(); j++ ) {
591  int i = manip->joint(j)->jointId; // index in robot model
592  hrp::Link* joint = m_robot->joint(i);
593  joint->q = ( m_qRef.data[i] - param.transition_joint_q[i] ) * transition_smooth_gain + param.transition_joint_q[i];
594  }
595  // transition_count update
596  param.transition_count--;
597  if(param.transition_count <= 0){ // erase impedance param
598  std::cerr << "[" << m_profile.instance_name << "] Finished cleanup and erase impedance param " << it->first << std::endl;
599  param.is_active = false;
600  }
601  } else {
602  // use impedance model
603 
604  hrp::Link* target = m_robot->link(ee_map[it->first].target_name);
605  assert(target);
606  param.current_p1 = target->p + target->R * ee_map[it->first].localPos;
607  param.current_r1 = target->R * ee_map[it->first].localR;
609 
610  hrp::Vector3 vel_p, vel_r;
611  //std::cerr << "MDK = " << param.M_p << " " << param.D_p << " " << param.K_p << std::endl;
612  //std::cerr << "MDK = " << param.M_r << " " << param.D_r << " " << param.K_r << std::endl;
613  // std::cerr << "ref_force = " << param.ref_force[0] << " " << param.ref_force[1] << " " << param.ref_force[2] << std::endl;
614  // std::cerr << "ref_moment = " << param.ref_moment[0] << " " << param.ref_moment[1] << " " << param.ref_moment[2] << std::endl;
615 
616  // ref_force/ref_moment and force_gain/moment_gain are expressed in global coordinates.
617  hrp::Matrix33 eeR = target->R * ee_map[it->first].localR;
618  hrp::Vector3 force_diff = abs_forces[it->second.sensor_name] - abs_ref_forces[it->second.sensor_name];
619  hrp::Vector3 moment_diff = abs_moments[it->second.sensor_name] - abs_ref_moments[it->second.sensor_name];
620  param.calcTargetVelocity(vel_p, vel_r, eeR, force_diff, moment_diff, m_dt,
621  DEBUGP, std::string(m_profile.instance_name), it->first);
622 
623  // Solve ik
624  hrp::JointPathExPtr manip = param.manip;
625  assert(manip);
626  //const int n = manip->numJoints();
627  manip->calcInverseKinematics2Loop(param.getOutputPos(), param.getOutputRot(), 1.0, param.avoid_gain, param.reference_gain, &qrefv, 1.0,
628  ee_map[it->first].localPos, ee_map[it->first].localR);
629  // transition_count update
630  if ( param.transition_count < 0 ) {
631  param.transition_count++;
632  }
633  } // else
634  }
635  it++;
636  } // while
637 };
638 
639 //
641 {
642  // Lock Mutex
643  {
644  Guard guard(m_mutex);
645  if ( m_impedance_param.find(i_name_) == m_impedance_param.end() ) {
646  std::cerr << "[" << m_profile.instance_name << "] Could not found impedance controller param [" << i_name_ << "]" << std::endl;
647  return false;
648  }
649  if ( m_impedance_param[i_name_].is_active ) {
650  std::cerr << "[" << m_profile.instance_name << "] Impedance control [" << i_name_ << "] is already started" << std::endl;
651  return false;
652  }
653  std::cerr << "[" << m_profile.instance_name << "] Start impedance control [" << i_name_ << "]" << std::endl;
654  m_impedance_param[i_name_].is_active = true;
655  m_impedance_param[i_name_].transition_count = -MAX_TRANSITION_COUNT; // when start impedance, count up to 0
656  }
657  return true;
658 }
659 
660  bool ImpedanceController::startImpedanceController(const std::string& i_name_)
661  {
662  bool ret = startImpedanceControllerNoWait(i_name_);
664  return ret;
665  }
666 
668 {
669  // Lock Mutex
670  {
671  Guard guard(m_mutex);
672  if ( m_impedance_param.find(i_name_) == m_impedance_param.end() ) {
673  std::cerr << "[" << m_profile.instance_name << "] Could not found impedance controller param [" << i_name_ << "]" << std::endl;
674  return false;
675  }
676  if ( !m_impedance_param[i_name_].is_active ) {
677  std::cerr << "[" << m_profile.instance_name << "] Impedance control [" << i_name_ << "] is already stopped" << std::endl;
678  return false;
679  }
680  std::cerr << "[" << m_profile.instance_name << "] Stop impedance control [" << i_name_ << "]" << std::endl;
681  for (unsigned int i = 0; i < m_robot->numJoints(); i++ ) {
682  m_impedance_param[i_name_].transition_joint_q[i] = m_robot->joint(i)->q;
683  }
684  m_impedance_param[i_name_].transition_count = MAX_TRANSITION_COUNT; // when stop impedance, count down to 0
685  }
686  return true;
687 }
688 
689 bool ImpedanceController::stopImpedanceController(const std::string& i_name_)
690 {
691  bool ret = stopImpedanceControllerNoWait(i_name_);
693  return ret;
694 }
695 
696 bool ImpedanceController::setImpedanceControllerParam(const std::string& i_name_, OpenHRP::ImpedanceControllerService::impedanceParam i_param_)
697 {
698  // Lock Mutex
699  {
700  Guard guard(m_mutex);
701  std::string name = std::string(i_name_);
702  if ( m_impedance_param.find(name) == m_impedance_param.end() ) {
703  std::cerr << "[" << m_profile.instance_name << "] Could not found impedance controller param [" << name << "]" << std::endl;
704  return false;
705  }
706 
707  std::cerr << "[" << m_profile.instance_name << "] Update impedance parameters" << std::endl;
708 
709  m_impedance_param[name].sr_gain = i_param_.sr_gain;
710  m_impedance_param[name].avoid_gain = i_param_.avoid_gain;
711  m_impedance_param[name].reference_gain = i_param_.reference_gain;
712  m_impedance_param[name].manipulability_limit = i_param_.manipulability_limit;
713  m_impedance_param[name].manip->setSRGain(m_impedance_param[name].sr_gain);
714  m_impedance_param[name].manip->setManipulabilityLimit(m_impedance_param[name].manipulability_limit);
715 
716  m_impedance_param[name].M_p = i_param_.M_p;
717  m_impedance_param[name].D_p = i_param_.D_p;
718  m_impedance_param[name].K_p = i_param_.K_p;
719  m_impedance_param[name].M_r = i_param_.M_r;
720  m_impedance_param[name].D_r = i_param_.D_r;
721  m_impedance_param[name].K_r = i_param_.K_r;
722 
723  m_impedance_param[name].force_gain = hrp::Vector3(i_param_.force_gain[0], i_param_.force_gain[1], i_param_.force_gain[2]).asDiagonal();
724  m_impedance_param[name].moment_gain = hrp::Vector3(i_param_.moment_gain[0], i_param_.moment_gain[1], i_param_.moment_gain[2]).asDiagonal();
725 
726  std::vector<double> ov;
727  ov.resize(m_impedance_param[name].manip->numJoints());
728  for (size_t i = 0; i < m_impedance_param[name].manip->numJoints(); i++) {
729  ov[i] = i_param_.ik_optional_weight_vector[i];
730  }
731  m_impedance_param[name].manip->setOptionalWeightVector(ov);
732  use_sh_base_pos_rpy = i_param_.use_sh_base_pos_rpy;
733 
734  std::cerr << "[" << m_profile.instance_name << "] set parameters" << std::endl;
735  std::cerr << "[" << m_profile.instance_name << "] name : " << name << std::endl;
736  std::cerr << "[" << m_profile.instance_name << "] M, D, K (pos) : " << m_impedance_param[name].M_p << " " << m_impedance_param[name].D_p << " " << m_impedance_param[name].K_p << std::endl;
737  std::cerr << "[" << m_profile.instance_name << "] M, D, K (rot) : " << m_impedance_param[name].M_r << " " << m_impedance_param[name].D_r << " " << m_impedance_param[name].K_r << std::endl;
738  std::cerr << "[" << m_profile.instance_name << "] force_gain : " << m_impedance_param[name].force_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "\n", " [", "]")) << std::endl;
739  std::cerr << "[" << m_profile.instance_name << "] moment_gain : " << m_impedance_param[name].moment_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "\n", " [", "]")) << std::endl;
740  std::cerr << "[" << m_profile.instance_name << "] manip_limit : " << m_impedance_param[name].manipulability_limit << std::endl;
741  std::cerr << "[" << m_profile.instance_name << "] sr_gain : " << m_impedance_param[name].sr_gain << std::endl;
742  std::cerr << "[" << m_profile.instance_name << "] avoid_gain : " << m_impedance_param[name].avoid_gain << std::endl;
743  std::cerr << "[" << m_profile.instance_name << "] reference_gain : " << m_impedance_param[name].reference_gain << std::endl;
744  std::cerr << "[" << m_profile.instance_name << "] use_sh_base_pos_rpy : " << (use_sh_base_pos_rpy?"true":"false") << std::endl;
745  }
746  return true;
747 }
748 
749 void ImpedanceController::copyImpedanceParam (ImpedanceControllerService::impedanceParam& i_param_, const ImpedanceParam& param)
750 {
751  i_param_.M_p = param.M_p;
752  i_param_.D_p = param.D_p;
753  i_param_.K_p = param.K_p;
754  i_param_.M_r = param.M_r;
755  i_param_.D_r = param.D_r;
756  i_param_.K_r = param.K_r;
757  for (size_t i = 0; i < 3; i++) i_param_.force_gain[i] = param.force_gain(i,i);
758  for (size_t i = 0; i < 3; i++) i_param_.moment_gain[i] = param.moment_gain(i,i);
759  i_param_.sr_gain = param.sr_gain;
760  i_param_.avoid_gain = param.avoid_gain;
761  i_param_.reference_gain = param.reference_gain;
762  i_param_.manipulability_limit = param.manipulability_limit;
763  if (param.is_active) i_param_.controller_mode = OpenHRP::ImpedanceControllerService::MODE_IMP;
764  else i_param_.controller_mode = OpenHRP::ImpedanceControllerService::MODE_IDLE;
765  if (param.manip == NULL) i_param_.ik_optional_weight_vector.length(0);
766  else {
767  i_param_.ik_optional_weight_vector.length(param.manip->numJoints());
768  std::vector<double> ov;
769  ov.resize(param.manip->numJoints());
770  param.manip->getOptionalWeightVector(ov);
771  for (size_t i = 0; i < param.manip->numJoints(); i++) {
772  i_param_.ik_optional_weight_vector[i] = ov[i];
773  }
774  }
775 }
776 
777 void ImpedanceController::updateRootLinkPosRot (TimedOrientation3D tmprpy)
778 {
779  if ( m_robot->numSensors(hrp::Sensor::ACCELERATION) > 0) {
780  hrp::Sensor *sensor = m_robot->sensor(hrp::Sensor::ACCELERATION, 0);
781  hrp::Matrix33 tmpr;
782  rats::rotm3times(tmpr, hrp::Matrix33(sensor->link->R*sensor->localR).transpose(), m_robot->rootLink()->R);
783  rats::rotm3times(m_robot->rootLink()->R, hrp::rotFromRpy(tmprpy.data.r, tmprpy.data.p, tmprpy.data.y), tmpr);
784  }
785 }
786 
787 bool ImpedanceController::getImpedanceControllerParam(const std::string& i_name_, ImpedanceControllerService::impedanceParam& i_param_)
788 {
789  if ( m_impedance_param.find(i_name_) == m_impedance_param.end() ) {
790  std::cerr << "[" << m_profile.instance_name << "] Could not found impedance controller param [" << i_name_ << "]" << std::endl;
791  // if impedance param of i_name_ is not found, return default impedance parameter ;; default parameter is specified ImpedanceParam struct's default constructer
792  copyImpedanceParam(i_param_, ImpedanceParam());
793  i_param_.use_sh_base_pos_rpy = use_sh_base_pos_rpy;
794  return false;
795  }
796  copyImpedanceParam(i_param_, m_impedance_param[i_name_]);
797  i_param_.use_sh_base_pos_rpy = use_sh_base_pos_rpy;
798  return true;
799 }
800 
802 {
803  while (m_impedance_param.find(i_name_) != m_impedance_param.end() &&
804  m_impedance_param[i_name_].transition_count != 0) {
805  usleep(10);
806  }
807  return;
808 }
809 
810 extern "C"
811 {
812 
814  {
816  manager->registerFactory(profile,
817  RTC::Create<ImpedanceController>,
818  RTC::Delete<ImpedanceController>);
819  }
820 
821 };
ComponentProfile m_profile
png_infop png_charpp int png_charpp profile
void updateRootLinkPosRot(TimedOrientation3D tmprpy)
std::map< std::string, ImpedanceParam > m_impedance_param
void readInterlockingJointsParamFromProperties(std::vector< std::pair< Link *, Link * > > &pairs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
#define DEBUGP
TimedOrientation3D m_baseRpy
bool stringTo(To &val, const char *str)
#define MAX_TRANSITION_COUNT
const hrp::Vector3 & getOutputPos()
std::vector< TimedDoubleSeq > m_ref_force
png_infop png_charpp name
std::map< std::string, hrp::Vector3 > abs_ref_moments
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
std::map< std::string, hrp::Vector3 > abs_moments
InPort< TimedOrientation3D > m_rpyIn
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
bool startImpedanceController(const std::string &i_name_)
CORBA::ORB_ptr getORB()
boost::shared_ptr< JointPathEx > JointPathExPtr
Definition: JointPathEx.h:67
RTC::CorbaPort m_ImpedanceControllerServicePort
png_uint_32 i
Eigen::VectorXd dvector
coil::Properties & getProperties()
InPort< TimedDoubleSeq > m_qRefIn
static Manager & instance()
Matrix33 localR
bool addOutPort(const char *name, OutPortBase &outport)
boost::shared_ptr< Body > BodyPtr
ImpedanceControllerService_impl m_service0
impedance control component
Eigen::Vector3d Vector3
RTC_OK
std::map< std::string, hrp::VirtualForceSensorParam > m_vfs
void ImpedanceControllerInit(RTC::Manager *manager)
Matrix33 rotFromRpy(const Vector3 &rpy)
Eigen::Matrix3d Matrix33
std::vector< std::string > vstring
coil::Properties & getConfig()
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
void rotm3times(hrp::Matrix33 &m12, const hrp::Matrix33 &m1, const hrp::Matrix33 &m2)
Definition: RatsMatrix.cpp:31
InPort< TimedPoint3D > m_basePosIn
void impedance(ImpedanceController *i_impedance)
ExecutionContextHandle_t UniqueId
std::map< std::string, hrp::Vector3 > abs_ref_forces
InPort< TimedDoubleSeq > m_qCurrentIn
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
def j(str, encoding="cp932")
Vector3 localPos
std::vector< InPort< TimedDoubleSeq > * > m_forceIn
bool stopImpedanceControllerNoWait(const std::string &i_name_)
void waitImpedanceControllerTransition(std::string i_name_)
int loadBodyFromModelLoader(::World *world, const char *name, const char *url, CosNaming::NamingContext_var cxt)
OutPort< TimedDoubleSeq > m_qOut
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onFinalize()
std::vector< TimedDoubleSeq > m_force
prop
void readVirtualForceSensorParamFromProperties(std::map< std::string, hrp::VirtualForceSensorParam > &vfs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
naming
Vector3 cross(const Vector3 &v1, const Vector3 &v2)
bool startImpedanceControllerNoWait(const std::string &i_name_)
bool setImpedanceControllerParam(const std::string &i_name_, OpenHRP::ImpedanceControllerService::impedanceParam i_param_)
void registerInPort(const char *name, InPortBase &inport)
virtual bool isNew()
bool addPort(PortBase &port)
virtual bool write(DataType &value)
std::map< std::string, ee_trans > ee_map
static const char * impedancecontroller_spec[]
hrp::BodyPtr m_robot
coil::Guard< coil::Mutex > Guard
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
JSAMPIMAGE data
int num
InPort< TimedOrientation3D > m_baseRpyIn
bool addInPort(const char *name, InPortBase &inport)
const hrp::Matrix33 & getOutputRot()
ImpedanceController(RTC::Manager *manager)
void mid_rot(hrp::Matrix33 &mid_rot, const double p, const hrp::Matrix33 &rot1, const hrp::Matrix33 &rot2, const double eps)
Definition: RatsMatrix.cpp:46
std::vector< InPort< TimedDoubleSeq > * > m_ref_forceIn
bool getImpedanceControllerParam(const std::string &i_name_, OpenHRP::ImpedanceControllerService::impedanceParam &i_param_)
void copyImpedanceParam(OpenHRP::ImpedanceControllerService::impedanceParam &i_param_, const ImpedanceParam &param)
std::map< std::string, hrp::Vector3 > abs_forces
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
bool stopImpedanceController(const std::string &i_name_)
int usleep(useconds_t usec)
bool registerProvider(const char *instance_name, const char *type_name, PortableServer::RefCountServantBase &provider)
void calcTargetVelocity(hrp::Vector3 &vel_p, hrp::Vector3 &vel_r, const hrp::Matrix33 &eeR, const hrp::Vector3 &force_diff, const hrp::Vector3 &moment_diff, const double _dt, const bool printp=false, const std::string &print_str="", const std::string &ee_name="")
virtual RTC::ReturnCode_t onInitialize()


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:50