iCub-main
main.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2013 iCub Facility - Istituto Italiano di Tecnologia
3  * Author: Ugo Pattacini
4  * email: ugo.pattacini@iit.it
5  * Permission is granted to copy, distribute, and/or modify this program
6  * under the terms of the GNU General Public License, version 2 or any
7  * later version published by the Free Software Foundation.
8  *
9  * A copy of the license can be found at
10  * http://www.robotcub.org/icub/license/gpl.txt
11  *
12  * This program is distributed in the hope that it will be useful, but
13  * WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
15  * Public License for more details
16 */
17 
86 #include <cmath>
87 #include <string>
88 #include <sstream>
89 #include <fstream>
90 #include <vector>
91 #include <map>
92 
93 #include <yarp/os/all.h>
94 #include <yarp/dev/all.h>
95 #include <yarp/sig/Vector.h>
96 #include <iCub/ctrl/tuning.h>
97 
98 #include "fingersTuner_IDL.h"
99 
100 using namespace std;
101 using namespace yarp::os;
102 using namespace yarp::dev;
103 using namespace yarp::sig;
104 using namespace iCub::ctrl;
105 
106 
107 /************************************************************************/
108 class Tuner
109 {
110 protected:
111  typedef enum { download, upload, synced } pidStatus;
112  struct PidData
113  {
114  double Kp;
115  double Ki;
116  double Kd;
117  double scale;
118  double st_up;
119  double st_down;
120  double encs_ratio;
122  vector<int> idling_joints;
123  PidData() : Kp(0.0), Ki(0.0), Kd(0.0), scale(0.0),
124  st_up(0.0), st_down(0.0), encs_ratio(1.0),
125  status(download) { }
126  void toRobot(Pid &pid)
127  {
128  pid.kp=Kp;
129  pid.ki=Ki;
130  pid.kd=Kd;
131  pid.scale=scale;
132  pid.stiction_up_val=st_up;
133  pid.stiction_down_val=st_down;
134  }
135  void fromRobot(const Pid &pid)
136  {
137  Kp=pid.kp;
138  Ki=pid.ki;
139  Kd=pid.kd;
140  scale=pid.scale;
141  st_up=pid.stiction_up_val;
142  st_down=pid.stiction_down_val;
143  }
144  };
145 
146  static unsigned int instances;
148  string name,robot,part,device;
149  PolyDriver *driver;
150 
151  Bottle rJoints;
152  map<int,PidData> pids;
153  map<string,Bottle> alias;
154 
155  /************************************************************************/
156  PolyDriver *waitPart(const Property &partOpt, const double ping_robot_tmo)
157  {
158  PolyDriver *pDrv=NULL;
159 
160  double t0=Time::now();
161  while (Time::now()-t0<ping_robot_tmo)
162  {
163  if (pDrv!=NULL)
164  delete pDrv;
165 
166  pDrv=new PolyDriver(const_cast<Property&>(partOpt));
167  bool ok=pDrv->isValid();
168 
169  if (ok)
170  {
171  yInfo("Checking if %s is active ... yes",device.c_str());
172  return pDrv;
173  }
174  else
175  {
176  double dt=ping_robot_tmo-(Time::now()-t0);
177  yInfo("Checking if %s is active ... not yet: still %.1f [s] to timeout expiry",
178  device.c_str(),dt>0.0?dt:0.0);
179 
180  double t1=Time::now();
181  while (Time::now()-t1<1.0)
182  Time::delay(0.1);
183  }
184 
185  if (interrupting)
186  break;
187  }
188 
189  return pDrv;
190  }
191 
192  /************************************************************************/
193  PidData getPidData(Bottle &bGroup, const int i)
194  {
195  PidData pid;
196 
197  ostringstream joint;
198  joint<<"joint_"<<i;
199  Bottle &bJoint=bGroup.findGroup(joint.str());
200 
201  pid.Kp=bJoint.check("Kp",Value(0.0)).asFloat64();
202  pid.Ki=bJoint.check("Ki",Value(0.0)).asFloat64();
203  pid.Kd=bJoint.check("Kd",Value(0.0)).asFloat64();
204  pid.scale=bJoint.check("scale",Value(0.0)).asFloat64();
205  pid.st_up=bJoint.check("st_up",Value(0.0)).asFloat64();
206  pid.st_down=bJoint.check("st_down",Value(0.0)).asFloat64();
207  pid.encs_ratio=bJoint.check("encs_ratio",Value(1.0)).asFloat64();
208  pid.status=(bJoint.check("status",Value("download")).asString()=="download"?download:upload);
209  if (bJoint.check("idling"))
210  {
211  if (Bottle *bIdlingJoints=bJoint.find("idling").asList())
212  {
213  pid.idling_joints.clear();
214  for (int j=0; j<bIdlingJoints->size(); j++)
215  {
216  int k=bIdlingJoints->get(j).asInt32();
217 
218  int l;
219  for (l=0; l<rJoints.size(); l++)
220  {
221  if (rJoints.get(l).asInt32()==k)
222  {
223  pid.idling_joints.push_back(k);
224  break;
225  }
226  }
227 
228  if (l>=rJoints.size())
229  yError("unrecognized joint %d to put in idle",k);
230  }
231  }
232  }
233 
234  return pid;
235  }
236 
237  /************************************************************************/
238  void idlingCoupledJoints(const int i, const bool sw)
239  {
240  IControlMode *imod;
241  driver->view(imod);
242 
243  PidData &pid=pids[i];
244  for (size_t j=0; j<pid.idling_joints.size(); j++)
245  imod->setControlMode(pid.idling_joints[j],
246  sw?VOCAB_CM_IDLE:VOCAB_CM_POSITION);
247  }
248 
249  /************************************************************************/
250  bool tune(const int i)
251  {
252  PidData &pid=pids[i];
253 
254  Property pGeneral;
255  pGeneral.put("joint",i);
256  string sGeneral="(general ";
257  sGeneral+=pGeneral.toString();
258  sGeneral+=')';
259 
260  Bottle bGeneral,bPlantEstimation,bStictionEstimation;
261  bGeneral.fromString(sGeneral);
262  bPlantEstimation.fromString("(plant_estimation (Ts 0.01) (Q 1.0) (R 1.0) (P0 100000.0) (tau 1.0) (K 1.0) (max_pwm 800.0))");
263  bStictionEstimation.fromString("(stiction_estimation (Ts 0.01) (T 2.0) (vel_thres 5.0) (e_thres 1.0) (gamma (10.0 10.0)) (stiction (0.0 0.0)))");
264 
265  Bottle bConf=bGeneral;
266  bConf.append(bPlantEstimation);
267  bConf.append(bStictionEstimation);
268 
269  Property pOptions(bConf.toString().c_str());
270  OnlineCompensatorDesign designer;
271  if (!designer.configure(*driver,pOptions))
272  {
273  yError("designer configuration failed!");
274  return false;
275  }
276 
277  idlingCoupledJoints(i,true);
278 
279  Property pPlantEstimation;
280  pPlantEstimation.put("max_time",20.0);
281  pPlantEstimation.put("switch_timeout",2.0);
282  designer.startPlantEstimation(pPlantEstimation);
283 
284  yInfo("Estimating plant for joint %d: max duration = %g seconds",
285  i,pPlantEstimation.find("max_time").asFloat64());
286 
287  double t0=Time::now();
288  while (!designer.isDone())
289  {
290  yInfo("elapsed %d [s]",(int)(Time::now()-t0));
291  Time::delay(1.0);
292  if (interrupting)
293  {
294  idlingCoupledJoints(i,false);
295  return false;
296  }
297  }
298 
299  Property pResults;
300  designer.getResults(pResults);
301  double tau=pResults.find("tau_mean").asFloat64();
302  double K=pResults.find("K_mean").asFloat64();
303  yInfo("plant = %g/s * 1/(1+s*%g)",K,tau);
304 
305  Property pControllerRequirements,pController;
306  pControllerRequirements.put("tau",tau);
307  pControllerRequirements.put("K",K);
308  pControllerRequirements.put("f_c",0.75);
309 
310  if (i!=15)
311  {
312  pControllerRequirements.put("T_dr",1.0);
313  pControllerRequirements.put("type","PI");
314  }
315  else
316  pControllerRequirements.put("type","P");
317 
318  designer.tuneController(pControllerRequirements,pController);
319  yInfo("tuning results: %s",pController.toString().c_str());
320  double Kp=pController.find("Kp").asFloat64();
321  double Ki=pController.find("Ki").asFloat64();
322  pid.scale=4.0;
323  int scale=(int)pid.scale; int shift=1<<scale;
324  double fwKp=floor(Kp*pid.encs_ratio*shift);
325  double fwKi=floor(Ki*pid.encs_ratio*shift/1000.0);
326  pid.Kp=yarp::math::sign(pid.Kp*fwKp)>0.0?fwKp:-fwKp;
327  pid.Ki=yarp::math::sign(pid.Ki*fwKi)>0.0?fwKi:-fwKi;
328  pid.Kd=0.0;
329  yInfo("Kp (FW) = %g; Ki (FW) = %g; Kd (FW) = %g; shift factor = %d",pid.Kp,pid.Ki,pid.Kd,scale);
330 
331  Property pStictionEstimation;
332  pStictionEstimation.put("max_time",60.0);
333  pStictionEstimation.put("Kp",Kp);
334  pStictionEstimation.put("Ki",0.0);
335  pStictionEstimation.put("Kd",0.0);
336  designer.startStictionEstimation(pStictionEstimation);
337 
338  yInfo("Estimating stiction for joint %d: max duration = %g seconds",
339  i,pStictionEstimation.find("max_time").asFloat64());
340 
341  t0=Time::now();
342  while (!designer.isDone())
343  {
344  yInfo("elapsed %d [s]",(int)(Time::now()-t0));
345  Time::delay(1.0);
346  if (interrupting)
347  {
348  idlingCoupledJoints(i,false);
349  return false;
350  }
351  }
352 
353  designer.getResults(pResults);
354  pid.st_up=floor(pResults.find("stiction").asList()->get(0).asFloat64());
355  pid.st_down=floor(pResults.find("stiction").asList()->get(1).asFloat64());
356  yInfo("Stiction values: up = %g; down = %g",pid.st_up,pid.st_down);
357 
358  IControlMode *imod;
359  IPositionControl *ipos;
360  IEncoders *ienc;
361  driver->view(imod);
362  driver->view(ipos);
363  driver->view(ienc);
364  imod->setControlMode(i,VOCAB_CM_POSITION);
365  ipos->setRefSpeed(i,50.0);
366  ipos->positionMove(i,0.0);
367  yInfo("Driving the joint back to rest... ");
368  t0=Time::now();
369  while (Time::now()-t0<5.0)
370  {
371  double enc;
372  ienc->getEncoder(i,&enc);
373  if (fabs(enc)<1.0)
374  break;
375 
376  if (interrupting)
377  {
378  idlingCoupledJoints(i,false);
379  return false;
380  }
381 
382  Time::delay(0.2);
383  }
384  yInfo("done!");
385 
386  idlingCoupledJoints(i,false);
387  return true;
388  }
389 
390 public:
391  /************************************************************************/
392  Tuner() : interrupting(false), driver(NULL)
393  {
394  instances++;
395  }
396 
397  /************************************************************************/
398  bool configure(ResourceFinder &rf, const string &part)
399  {
400  this->part=part;
401  Bottle &bGeneral=rf.findGroup("general");
402  if (bGeneral.isNull())
403  {
404  yError("group [general] is missing!");
405  return false;
406  }
407 
408  Bottle &bPart=rf.findGroup(part);
409  if (bPart.isNull())
410  {
411  yError("group [%s] is missing!",part.c_str());
412  return false;
413  }
414 
415  if (!bPart.check("device"))
416  {
417  yError("\"device\" option is missing!");
418  return false;
419  }
420 
421  name=bGeneral.check("name",Value("fingersTuner")).asString();
422  robot=bGeneral.check("robot",Value("icub")).asString();
423  double ping_robot_tmo=bGeneral.check("ping_robot_tmo",Value(0.0)).asFloat64();
424  device=bPart.find("device").asString();
425 
426  if (Bottle *rj=bGeneral.find("relevantJoints").asList())
427  rJoints=*rj;
428  else
429  {
430  yError("\"relevantJoints\" option is missing!");
431  return false;
432  }
433 
434  int numAlias=bGeneral.check("numAlias",Value(0)).asInt32();
435  for (int i=0; i<numAlias; i++)
436  {
437  ostringstream item;
438  item<<"alias_"<<i;
439  Bottle &bAlias=bGeneral.findGroup(item.str());
440  if (Bottle *joints=bAlias.find("joints").asList())
441  alias[bAlias.find("tag").asString()]=*joints;
442  }
443 
444  // special wildcard to point to all the joints
445  alias["*"]=rJoints;
446 
447  for (int i=0; i<rJoints.size(); i++)
448  {
449  int j=rJoints.get(i).asInt32();
450  pids[j]=getPidData(bPart,j);
451  }
452 
453  ostringstream portsSuffix;
454  portsSuffix<<instances<<"/"<<device;
455 
456  Property option("(device remote_controlboard)");
457  option.put("remote","/"+robot+"/"+device);
458  option.put("local","/"+name+"/"+portsSuffix.str());
459 
460  if (ping_robot_tmo>0.0)
461  driver=waitPart(option,ping_robot_tmo);
462  else
463  driver=new PolyDriver(option);
464 
465  if (!driver->isValid())
466  {
467  yError("%s device driver not available!",device.c_str());
468  return false;
469  }
470 
471  return true;
472  }
473 
474  /************************************************************************/
475  bool sync(const Value &sel)
476  {
477  Bottle joints;
478  if (sel.isInt32())
479  joints.addInt32(sel.asInt32());
480  else if (sel.isString())
481  {
482  map<string,Bottle>::iterator it=alias.find(sel.asString());
483  if (it!=alias.end())
484  joints=it->second;
485  else
486  return false;
487  }
488  else
489  return false;
490 
491  for (int i=0; i<joints.size(); i++)
492  {
493  int j=rJoints.get(i).asInt32();
494  map<int,PidData>::iterator it=pids.find(j);
495  if (it==pids.end())
496  continue;
497 
498  IPidControl *ipid;
499  driver->view(ipid);
500  Pid _pid;
501  ipid->getPid(VOCAB_PIDTYPE_POSITION,j,&_pid);
502 
503  PidData &pid=it->second;
504  if (pid.status==download)
505  pid.fromRobot(_pid);
506  else
507  {
508  pid.toRobot(_pid);
509  ipid->setPid(VOCAB_PIDTYPE_POSITION,j,_pid);
510  }
511 
512  pid.status=synced;
513  }
514 
515  return true;
516  }
517 
518  /************************************************************************/
519  bool tune(const Value &sel)
520  {
521  Bottle joints;
522  if (sel.isInt32())
523  joints.addInt32(sel.asInt32());
524  else if (sel.isString())
525  {
526  map<string,Bottle>::iterator it=alias.find(sel.asString());
527  if (it!=alias.end())
528  joints=it->second;
529  else
530  return false;
531  }
532  else
533  return false;
534 
535  for (int i=0; i<joints.size(); i++)
536  {
537  int j=joints.get(i).asInt32();
538  map<int,PidData>::iterator it=pids.find(j);
539  if (it==pids.end())
540  continue;
541 
542  if (tune(j))
543  {
544  IPidControl *ipid;
545  driver->view(ipid);
546  Pid _pid;
547  ipid->getPid(VOCAB_PIDTYPE_POSITION,j,&_pid);
548 
549  PidData &pid=it->second;
550  pid.toRobot(_pid);
551  ipid->setPid(VOCAB_PIDTYPE_POSITION,j,_pid);
552  pid.status=synced;
553  }
554 
555  if (interrupting)
556  return false;
557  }
558 
559  return true;
560  }
561 
562  /************************************************************************/
563  string toString()
564  {
565  ostringstream stream;
566  stream<<"["<<part<<"]"<<endl;
567  stream<<"device "<<device<<endl;
568 
569  for (int i=0; i<rJoints.size(); i++)
570  {
571  int j=rJoints.get(i).asInt32();
572  PidData &pid=pids[j];
573 
574  Property prop;
575  prop.put("Kp",pid.Kp);
576  prop.put("Ki",pid.Ki);
577  prop.put("Kd",pid.Kd);
578  prop.put("scale",pid.scale);
579  prop.put("st_up",pid.st_up);
580  prop.put("st_down",pid.st_down);
581  prop.put("encs_ratio",pid.encs_ratio);
582  prop.put("status",pid.status==download?"download":"upload");
583 
584  stream<<"joint_"<<j<<" ";
585  stream<<prop.toString()<<endl;
586  }
587 
588  return stream.str();
589  }
590 
591  /************************************************************************/
592  void interrupt()
593  {
594  interrupting=true;
595  }
596 
597  /************************************************************************/
599  {
600  delete driver;
601  }
602 };
603 
604 
605 unsigned int Tuner::instances=0;
606 /************************************************************************/
607 class TunerModule: public RFModule, public fingersTuner_IDL
608 {
609 protected:
610  ResourceFinder *rf;
611  map<string,Tuner*> tuners;
613  bool closing;
614  RpcServer rpcPort;
615 
616 public:
617  /************************************************************************/
618  bool configure(ResourceFinder &rf)
619  {
620  interrupting=false;
621  closing=false;
622  this->rf=&rf;
623 
624  Bottle &bGeneral=rf.findGroup("general");
625  if (bGeneral.isNull())
626  {
627  yError("group [general] is missing!");
628  return false;
629  }
630 
631  string name=bGeneral.check("name",Value("fingersTuner")).asString();
632  setName(name.c_str());
633 
634  if (Bottle *bParts=bGeneral.find("relevantParts").asList())
635  {
636  for (int i=0; (i<bParts->size()) && !interrupting; i++)
637  {
638  string part=bParts->get(i).asString();
639  tuners[part]=new Tuner;
640  Tuner *tuner=tuners[part];
641 
642  if (!tuner->configure(rf,part))
643  {
644  dispose();
645  return false;
646  }
647 
648  tuner->sync(Value("*"));
649  }
650  }
651  else
652  {
653  yError("\"relevantParts\" option is missing!");
654  return false;
655  }
656 
657  rpcPort.open("/"+name+"/rpc");
658  attach(rpcPort);
659 
660  return true;
661  }
662 
663  /************************************************************************/
664  bool attach(RpcServer &source)
665  {
666  return this->yarp().attachAsServer(source);
667  }
668 
669  /************************************************************************/
670  double getPeriod()
671  {
672  return 1.0;
673  }
674 
675  /************************************************************************/
677  {
678  return !closing;
679  }
680 
681  /************************************************************************/
683  {
684  interrupting=true;
685  for (map<string,Tuner*>::iterator it=tuners.begin(); it!=tuners.end(); ++it)
686  it->second->interrupt();
687 
688  return true;
689  }
690 
691  /************************************************************************/
692  void dispose()
693  {
694  for (map<string,Tuner*>::iterator it=tuners.begin(); it!=tuners.end(); ++it)
695  delete it->second;
696  }
697 
698  /************************************************************************/
699  bool sync(const string &part, const Value &val)
700  {
701  map<string,Tuner*>::iterator it=tuners.find(part);
702  if (it!=tuners.end())
703  if (it->second->sync(val))
704  return true;
705 
706  return false;
707  }
708 
709  /************************************************************************/
710  bool tune(const string &part, const Value &val)
711  {
712  map<string,Tuner*>::iterator it=tuners.find(part);
713  if (it!=tuners.end())
714  if (it->second->tune(val))
715  return true;
716 
717  return false;
718  }
719 
720  /************************************************************************/
721  bool save()
722  {
723  string fileName=rf->getHomeContextPath();
724  fileName+="/";
725  fileName+=rf->find("from").asString();
726 
727  ofstream fout;
728  fout.open(fileName.c_str());
729 
730  Bottle &bGeneral=rf->findGroup("general");
731  fout<<"["<<bGeneral.get(0).asString()<<"]"<<endl;
732  for (int i=1; i<bGeneral.size(); i++)
733  fout<<bGeneral.get(i).toString()<<endl;
734 
735  fout<<endl;
736  for (map<string,Tuner*>::iterator it=tuners.begin(); it!=tuners.end(); ++it)
737  fout<<it->second->toString()<<endl;
738 
739  fout.close();
740  return true;
741  }
742 
743  /************************************************************************/
744  bool quit()
745  {
746  return closing=true;
747  }
748 
749  /************************************************************************/
750  bool close()
751  {
752  save();
753  dispose();
754  rpcPort.close();
755  return true;
756  }
757 };
758 
759 
760 /************************************************************************/
761 int main(int argc, char *argv[])
762 {
763  Network yarp;
764  if (!yarp.checkNetwork())
765  {
766  yError("YARP server not available!");
767  return 1;
768  }
769 
770  ResourceFinder rf;
771  rf.setDefaultContext("fingersTuner");
772  rf.setDefaultConfigFile("config.ini");
773  rf.configure(argc,argv);
774 
775  TunerModule mod;
776  return mod.runModule(rf);
777 }
TunerModule::attach
bool attach(RpcServer &source)
Definition: main.cpp:664
Tuner::Tuner
Tuner()
Definition: main.cpp:392
TunerModule::configure
bool configure(ResourceFinder &rf)
Definition: main.cpp:618
Tuner::alias
map< string, Bottle > alias
Definition: main.cpp:153
TunerModule::updateModule
bool updateModule()
Definition: main.cpp:676
Tuner::PidData::st_down
double st_down
Definition: main.cpp:119
Tuner::robot
string robot
Definition: main.cpp:148
TunerModule
Definition: main.cpp:607
main
int main(int argc, char *argv[])
Definition: main.cpp:31
Tuner::pidStatus
pidStatus
Definition: main.cpp:111
Tuner::interrupt
void interrupt()
Definition: main.cpp:592
Tuner::PidData::idling_joints
vector< int > idling_joints
Definition: main.cpp:122
Tuner::PidData::PidData
PidData()
Definition: main.cpp:123
iCub::ctrl::OnlineCompensatorDesign
Definition: tuning.h:347
TunerModule::interrupting
bool interrupting
Definition: main.cpp:612
Tuner::waitPart
PolyDriver * waitPart(const Property &partOpt, const double ping_robot_tmo)
Definition: main.cpp:156
Tuner::PidData::Kp
double Kp
Definition: main.cpp:114
Tuner::tune
bool tune(const Value &sel)
Definition: main.cpp:519
yarp::dev
Definition: DebugInterfaces.h:52
iCub::ctrl::OnlineCompensatorDesign::configure
virtual bool configure(yarp::dev::PolyDriver &driver, const yarp::os::Property &options)
Configure the design.
Definition: tuning.cpp:459
TunerModule::getPeriod
double getPeriod()
Definition: main.cpp:670
Tuner::pids
map< int, PidData > pids
Definition: main.cpp:152
TunerModule::closing
bool closing
Definition: main.cpp:613
iCub::ctrl::OnlineCompensatorDesign::startStictionEstimation
virtual bool startStictionEstimation(const yarp::os::Property &options)
Start off the stiction estimation procedure.
Definition: tuning.cpp:953
TunerModule::tune
bool tune(const string &part, const Value &val)
Definition: main.cpp:710
Tuner::PidData::Ki
double Ki
Definition: main.cpp:115
Tuner::tune
bool tune(const int i)
Definition: main.cpp:250
Tuner::PidData::st_up
double st_up
Definition: main.cpp:118
Tuner::rJoints
Bottle rJoints
Definition: main.cpp:151
iCub::ctrl
Definition: adaptWinPolyEstimator.h:37
iCub::ctrl::OnlineCompensatorDesign::startPlantEstimation
virtual bool startPlantEstimation(const yarp::os::Property &options)
Start off the plant estimation procedure.
Definition: tuning.cpp:891
Tuner::driver
PolyDriver * driver
Definition: main.cpp:149
TunerModule::interruptModule
bool interruptModule()
Definition: main.cpp:682
Tuner::PidData::toRobot
void toRobot(Pid &pid)
Definition: main.cpp:126
state::ok
@ ok
TunerModule::quit
bool quit()
Quit the module.
Definition: main.cpp:744
Tuner::toString
string toString()
Definition: main.cpp:563
Tuner::idlingCoupledJoints
void idlingCoupledJoints(const int i, const bool sw)
Definition: main.cpp:238
Tuner::~Tuner
~Tuner()
Definition: main.cpp:598
Tuner::PidData::scale
double scale
Definition: main.cpp:117
tuning.h
TunerModule::dispose
void dispose()
Definition: main.cpp:692
Tuner::PidData::Kd
double Kd
Definition: main.cpp:116
Tuner
Definition: main.cpp:108
TunerModule::save
bool save()
Save the PID parameters on configuration file.
Definition: main.cpp:721
fingersTuner_IDL
fingersTuner_IDL IDL Interface to fingersTuner services.
Definition: fingersTuner_IDL.h:18
fingersTuner_IDL.h
TunerModule::sync
bool sync(const string &part, const Value &val)
Definition: main.cpp:699
TunerModule::tuners
map< string, Tuner * > tuners
Definition: main.cpp:611
Tuner::PidData::encs_ratio
double encs_ratio
Definition: main.cpp:120
Tuner::getPidData
PidData getPidData(Bottle &bGroup, const int i)
Definition: main.cpp:193
yarp
Copyright (C) 2008 RobotCub Consortium.
Definition: DebugInterfaces.h:51
Tuner::PidData::fromRobot
void fromRobot(const Pid &pid)
Definition: main.cpp:135
scripting.argc
argc
Definition: scripting.py:184
Tuner::sync
bool sync(const Value &sel)
Definition: main.cpp:475
TunerModule::close
bool close()
Definition: main.cpp:750
Tuner::interrupting
bool interrupting
Definition: main.cpp:147
Tuner::instances
static unsigned int instances
Definition: main.cpp:146
Tuner::configure
bool configure(ResourceFinder &rf, const string &part)
Definition: main.cpp:398
Tuner::PidData::status
pidStatus status
Definition: main.cpp:121
iCub::ctrl::OnlineCompensatorDesign::getResults
virtual bool getResults(yarp::os::Property &results)
Retrieve the results of the current ongoing operation.
Definition: tuning.cpp:1048
iCub::ctrl::OnlineCompensatorDesign::tuneController
virtual bool tuneController(const yarp::os::Property &options, yarp::os::Property &results)
Tune the controller once given the plant characteristics.
Definition: tuning.cpp:838
iCub::ctrl::OnlineCompensatorDesign::isDone
virtual bool isDone()
Check the status of the current ongoing operation.
Definition: tuning.cpp:1025
TunerModule::rf
ResourceFinder * rf
Definition: main.cpp:610
Tuner::upload
@ upload
Definition: main.cpp:111
TunerModule::rpcPort
RpcServer rpcPort
Definition: main.cpp:614
Tuner::PidData
Definition: main.cpp:112