NTRT Simulator  Version: Master
 All Classes Namespaces Files Functions Variables Typedefs Friends Pages
JSONSegmentsFeedbackControl.cpp
Go to the documentation of this file.
1 /*
2  * Copyright © 2012, United States Government, as represented by the
3  * Administrator of the National Aeronautics and Space Administration.
4  * All rights reserved.
5  *
6  * The NASA Tensegrity Robotics Toolkit (NTRT) v1 platform is licensed
7  * under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  * http://www.apache.org/licenses/LICENSE-2.0.
11  *
12  * Unless required by applicable law or agreed to in writing,
13  * software distributed under the License is distributed on an
14  * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
15  * either express or implied. See the License for the specific language
16  * governing permissions and limitations under the License.
17 */
18 
29 
30 
31 // Should include tgString, but compiler complains since its been
32 // included from BaseSpineModelLearning. Perhaps we should move things
33 // to a cpp over there
35 #include "core/tgBasicActuator.h"
38 #include "examples/learningSpines/tgCPGCableControl.h"
39 
40 #include "dev/dhustigschultz/BigPuppy_SpineOnly_Stats/BaseQuadModelLearning.h"
41 #include "helpers/FileHelpers.h"
42 
45 
46 #include "util/CPGEquationsFB.h"
47 #include "examples/learningSpines/tgCPGCableControl.h"
48 
49 #include "neuralNet/Neural Network v2/neuralNetwork.h"
50 
51 #include <json/json.h>
52 
53 #include <string>
54 #include <iostream>
55 #include <vector>
56 
57 //#define LOGGING
58 #define USE_KINEMATIC
59 
60 using namespace std;
61 
63  int tm,
64  int om,
65  int param,
66  int segnum,
67  double ct,
68  double la,
69  double ha,
70  double lp,
71  double hp,
72  double kt,
73  double kp,
74  double kv,
75  bool def,
76  double cl,
77  double lf,
78  double hf,
79  double ffMin,
80  double ffMax,
81  double afMin,
82  double afMax,
83  double pfMin,
84  double pfMax,
85  double maxH,
86  double minH,
87  int ohm,
88  int thm,
89  int olm,
90  int tlm) :
91 JSONQuadCPGControl::Config::Config(ss, tm, om, param, segnum, ct, la, ha,
92  lp, hp, kt, kp, kv, def, cl, lf, hf),
93 freqFeedbackMin(ffMin),
94 freqFeedbackMax(ffMax),
95 ampFeedbackMin(afMin),
96 ampFeedbackMax(afMax),
97 phaseFeedbackMin(pfMin),
98 phaseFeedbackMax(pfMax),
99 maxHeight(maxH),
100 minHeight(minH),
101 ourHipMuscles(ohm),
102 theirHipMuscles(thm),
103 ourLegMuscles(olm),
104 theirLegMuscles(tlm)
105 {
106 
107 }
114  std::string args,
115  std::string resourcePath) :
116 JSONQuadCPGControl(config, args, resourcePath),
117 m_config(config)
118 {
119  // Path and filename handled by base class
120 
121 }
122 
123 JSONSegmentsFeedbackControl::~JSONSegmentsFeedbackControl()
124 {
125  delete nn;
126 }
127 
129 {
130  m_pCPGSys = new CPGEquationsFB(5000);
131 
132  Json::Value root; // will contains the root value after parsing.
133  Json::Reader reader;
134 
135  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
136  if ( !parsingSuccessful )
137  {
138  // report to the user the failure and their locations in the document.
139  std::cout << "Failed to parse configuration\n"
140  << reader.getFormattedErrorMessages();
141  throw std::invalid_argument("Bad filename for JSON");
142  }
143  // Get the value of the member of root named 'encoding', return 'UTF-8' if there is no
144  // such member.
145  Json::Value nodeVals = root.get("nodeVals", "UTF-8");
146  Json::Value edgeVals = root.get("edgeVals", "UTF-8");
147  //New sets of -Vals for hips/shoulders and legs:
148  Json::Value hipEdgeVals = root.get("hipEdgeVals", "UTF-8");
149  Json::Value legEdgeVals = root.get("legEdgeVals", "UTF-8");
150 
151  std::cout << nodeVals << std::endl;
152 
153  nodeVals = nodeVals.get("params", "UTF-8");
154  edgeVals = edgeVals.get("params", "UTF-8");
155  //New sets of -Vals for hips/shoulders and legs:
156  hipEdgeVals = hipEdgeVals.get("params", "UTF-8");
157  legEdgeVals = legEdgeVals.get("params", "UTF-8");
158 
159  array_4D edgeParams = scaleEdgeActions(edgeVals,m_config.theirMuscles,m_config.ourMuscles);
160  //New sets of Params for hips/shoulders and legs:
161  array_4D hipEdgeParams = scaleEdgeActions(hipEdgeVals,m_config.theirHipMuscles,m_config.ourHipMuscles);
162  array_4D legEdgeParams = scaleEdgeActions(legEdgeVals,m_config.theirLegMuscles,m_config.ourLegMuscles);
163 
164  array_2D nodeParams = scaleNodeActions(nodeVals);
165 
166  setupCPGs(subject, nodeParams, edgeParams, hipEdgeParams, legEdgeParams);
167 
168  Json::Value feedbackParams = root.get("feedbackVals", "UTF-8");
169  feedbackParams = feedbackParams.get("params", "UTF-8");
170 
171  // Setup neural network
172  m_config.numStates = feedbackParams.get("numStates", "UTF-8").asInt();
173  m_config.numActions = feedbackParams.get("numActions", "UTF-8").asInt();
174  //m_config.numHidden = feedbackParams.get("numHidden", "UTF-8").asInt();
175 
176  std::string nnFile = controlFilePath + feedbackParams.get("neuralFilename", "UTF-8").asString();
177 
178  nn = new neuralNetwork(m_config.numStates, m_config.numStates*2, m_config.numActions);
179 
180  nn->loadWeights(nnFile.c_str());
181 
182  initConditions = subject.getSegmentCOM(m_config.segmentNumber);
183  for (int i = 0; i < initConditions.size(); i++)
184  {
185  std::cout << initConditions[i] << " ";
186  }
187  std::cout << std::endl;
188 #ifdef LOGGING // Conditional compile for data logging
189  m_dataObserver.onSetup(subject);
190 #endif
191 
192 #if (0) // Conditional Compile for debug info
193  std::cout << *m_pCPGSys << std::endl;
194 #endif
195  m_updateTime = 0.0;
196  m_totalTime = 0.0; //For metrics.
197  bogus = false;
198 
199  metrics.clear();
200 
201  //Getting the center of mass of the entire structure.
202  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
203 
204  for(std::size_t i=0; i<3; i++)
205  {
206  metrics.push_back(structureCOM[i]);
207  }
208 
209  //"metrics" is a new section of the controller's JSON file that is
210  //added in the getNewFile function in evolution_job_master.py
211  Json::Value prevMetrics = root.get("metrics", Json::nullValue);
212 
213  Json::Value subMetrics;
214  subMetrics["initial COM x"] = metrics[0];
215  subMetrics["initial COM y"] = metrics[1];
216  subMetrics["initial COM z"] = metrics[2];
217 
218  prevMetrics.append(subMetrics);
219  root["metrics"] = prevMetrics;
220 
221  ofstream payloadLog;
222  payloadLog.open(controlFilename.c_str(),ofstream::out);
223 
224  payloadLog << root << std::endl;
225 }
226 
228 {
229  m_updateTime += dt;
230  m_totalTime += dt;
231  if (m_updateTime >= m_config.controlTime)
232  {
233 #if (1)
234  std::vector<double> desComs = getFeedback(subject);
235 
236 #else
237  std::size_t numControllers = subject.getNumberofMuslces() * 3;
238 
239  double descendingCommand = 0.0;
240  std::vector<double> desComs (numControllers, descendingCommand);
241 #endif
242  try
243  {
244  m_pCPGSys->update(desComs, m_updateTime);
245  }
246  catch (std::runtime_error& e)
247  {
248  // Stops the trial immediately, lets teardown know it broke
249  bogus = true;
250  throw (e);
251  }
252 
253 #ifdef LOGGING // Conditional compile for data logging
254  m_dataObserver.onStep(subject, m_updateTime);
255 #endif
256  notifyStep(m_updateTime);
257  m_updateTime = 0;
258  }
259 
260  double currentHeight = subject.getSegmentCOM(m_config.segmentNumber)[1];
261 
263  if (currentHeight > m_config.maxHeight || currentHeight < m_config.minHeight)
264  {
266  bogus = true;
267  throw std::runtime_error("Height out of range");
268  }
269  //every 100 steps, get the COM and tensions of active muscles and store them in the JSON file.
270  if(1){
271  static int count = 0;
272  if(count > 100) {
273  std::cout << m_totalTime << std::endl;
274 
275  //Getting the center of mass of the entire structure.
276  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
277  std::cout << "COM: " << structureCOM[0] << " " << structureCOM[1] << " " << structureCOM[2] << " ";
278  std::cout << std::endl;
279  //Clear the metrics vector for ease of adding tensions.
280  //metrics.clear();
281 
282  //Print out all spine tensions and lengths:
283  std::vector<tgSpringCableActuator* > tmpStrings = subject.find<tgSpringCableActuator> ("spine ");
284 
285  for(std::size_t i=0; i<tmpStrings.size(); i++)
286  {
287  std::cout << "Spine Muscle Tension " << i << ": " << tmpStrings[i]->getTension() << std::endl;
288  }
289  std::cout << std::endl;
290 
291  for(std::size_t i=0; i<tmpStrings.size(); i++)
292  {
293  std::cout << "Spine Muscle Length " << i << ": " << tmpStrings[i]->getCurrentLength() << std::endl;
294  }
295  std::cout << std::endl;
296 
297  //Print out all hip tensions and lengths:
298  std::vector<tgSpringCableActuator* > tmpHipStrings = subject.find<tgSpringCableActuator> ("hip ");
299 
300  for(std::size_t i=0; i<tmpHipStrings.size(); i++)
301  {
302  std::cout << "Hip Muscle Tension " << i << ": " << tmpHipStrings[i]->getTension() << std::endl;
303  }
304  std::cout << std::endl;
305 
306  for(std::size_t i=0; i<tmpHipStrings.size(); i++)
307  {
308  std::cout << "Hip Muscle Length " << i << ": " << tmpHipStrings[i]->getCurrentLength() << std::endl;
309  }
310  std::cout << std::endl;
311 
312  //Print out all leg tensions and lengths:
313  std::vector<tgSpringCableActuator* > tmpLegStrings = subject.find<tgSpringCableActuator> ("leg ");
314 
315  for(std::size_t i=0; i<tmpLegStrings.size(); i++)
316  {
317  std::cout << "Leg Muscle Tension " << i << ": " << tmpLegStrings[i]->getTension() << std::endl;
318  }
319  std::cout << std::endl;
320 
321  for(std::size_t i=0; i<tmpLegStrings.size(); i++)
322  {
323  std::cout << "Leg Muscle Length " << i << ": " << tmpLegStrings[i]->getCurrentLength() << std::endl;
324  }
325  std::cout << std::endl;
326 
327  count = 0;
328  }
329  else {
330  count++;
331  }
332  }
333 }
334 
336 {
337  scores.clear();
338  metrics.clear();
339  // @todo - check to make sure we ran for the right amount of time
340 
341  std::vector<double> finalConditions = subject.getSegmentCOM(m_config.segmentNumber);
342 
343  const double newX = finalConditions[0];
344  const double newZ = finalConditions[2];
345  const double oldX = initConditions[0];
346  const double oldZ = initConditions[2];
347 
348  const double distanceMoved = sqrt((newX-oldX) * (newX-oldX) +
349  (newZ-oldZ) * (newZ-oldZ));
350 
351  if (bogus)
352  {
353  scores.push_back(-1.0);
354  }
355  else
356  {
357  scores.push_back(distanceMoved);
358  }
359 
362  double totalEnergySpent=0;
363 
364  //Calculating total enery for spine:
365  std::vector<tgSpringCableActuator* > tmpStrings = subject.find<tgSpringCableActuator> ("spine ");
366 
367  for(std::size_t i=0; i<tmpStrings.size(); i++)
368  {
369  tgSpringCableActuator::SpringCableActuatorHistory stringHist = tmpStrings[i]->getHistory();
370 
371  for(std::size_t j=1; j<stringHist.tensionHistory.size(); j++)
372  {
373  const double previousTension = stringHist.tensionHistory[j-1];
374  const double previousLength = stringHist.restLengths[j-1];
375  const double currentLength = stringHist.restLengths[j];
376  //TODO: examine this assumption - free spinning motor may require more power
377  double motorSpeed = (currentLength-previousLength);
378  if(motorSpeed > 0) // Vestigial code
379  motorSpeed = 0;
380  const double workDone = previousTension * motorSpeed;
381  totalEnergySpent += workDone;
382  }
383  }
384 
385  //Repeating the process for hips:
386  std::vector<tgSpringCableActuator* > tmpHipStrings = subject.find<tgSpringCableActuator> ("hip ");
387 
388  for(std::size_t i=0; i<tmpHipStrings.size(); i++)
389  {
390  tgSpringCableActuator::SpringCableActuatorHistory stringHipHist = tmpHipStrings[i]->getHistory();
391 
392  for(std::size_t j=1; j<stringHipHist.tensionHistory.size(); j++)
393  {
394  const double previousTension = stringHipHist.tensionHistory[j-1];
395  const double previousLength = stringHipHist.restLengths[j-1];
396  const double currentLength = stringHipHist.restLengths[j];
397  //TODO: examine this assumption - free spinning motor may require more power
398  double motorSpeed = (currentLength-previousLength);
399  if(motorSpeed > 0) // Vestigial code
400  motorSpeed = 0;
401  const double workDone = previousTension * motorSpeed;
402  totalEnergySpent += workDone;
403  }
404  }
405 
406  //Repeating the process for legs:
407  std::vector<tgSpringCableActuator* > tmpLegStrings = subject.find<tgSpringCableActuator> ("leg ");
408 
409  for(std::size_t i=0; i<tmpLegStrings.size(); i++)
410  {
411  tgSpringCableActuator::SpringCableActuatorHistory stringLegHist = tmpLegStrings[i]->getHistory();
412 
413  for(std::size_t j=1; j<stringLegHist.tensionHistory.size(); j++)
414  {
415  const double previousTension = stringLegHist.tensionHistory[j-1];
416  const double previousLength = stringLegHist.restLengths[j-1];
417  const double currentLength = stringLegHist.restLengths[j];
418  //TODO: examine this assumption - free spinning motor may require more power
419  double motorSpeed = (currentLength-previousLength);
420  if(motorSpeed > 0) // Vestigial code
421  motorSpeed = 0;
422  const double workDone = previousTension * motorSpeed;
423  totalEnergySpent += workDone;
424  }
425  }
426 
427  scores.push_back(totalEnergySpent);
428 
429  //Getting the center of mass of the entire structure.
430  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
431 
432  for(std::size_t i=0; i<3; i++)
433  {
434  metrics.push_back(structureCOM[i]);
435  }
436 
437  std::cout << "Dist travelled " << scores[0] << std::endl;
438 
439  Json::Value root; // will contain the root value after parsing.
440  Json::Reader reader;
441 
442  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
443  if ( !parsingSuccessful )
444  {
445  // report to the user the failure and their locations in the document.
446  std::cout << "Failed to parse configuration\n"
447  << reader.getFormattedErrorMessages();
448  throw std::invalid_argument("Bad filename for JSON");
449  }
450 
451  Json::Value prevScores = root.get("scores", Json::nullValue);
452  Json::Value prevMetrics = root.get("metrics", Json::nullValue);
453 
454  Json::Value subScores;
455  subScores["distance"] = scores[0];
456  subScores["energy"] = scores[1];
457 
458  Json::Value subMetrics;
459  subMetrics["final COM x"] = metrics[0];
460  subMetrics["final COM y"] = metrics[1];
461  subMetrics["final COM z"] = metrics[2];
462 
463  prevScores.append(subScores);
464  prevMetrics.append(subMetrics);
465 
466  root["scores"] = prevScores;
467  root["metrics"] = prevMetrics;
468 
469  ofstream payloadLog;
470  payloadLog.open(controlFilename.c_str(),ofstream::out);
471 
472  payloadLog << root << std::endl;
473 
474  delete m_pCPGSys;
475  m_pCPGSys = NULL;
476 
477  for(size_t i = 0; i < m_spineControllers.size(); i++)
478  {
479  delete m_spineControllers[i];
480  }
481  m_spineControllers.clear();
482 }
483 
484 void JSONSegmentsFeedbackControl::setupCPGs(BaseQuadModelLearning& subject, array_2D nodeActions, array_4D edgeActions, array_4D hipEdgeActions, array_4D legEdgeActions)
485 {
486 
487  std::vector <tgSpringCableActuator*> spineMuscles = subject.find<tgSpringCableActuator> ("spine ");
488  std::vector <tgSpringCableActuator*> hipMuscles = subject.find<tgSpringCableActuator> ("hip ");
489  //std::vector <tgSpringCableActuator*> legMuscles = subject.find<tgSpringCableActuator> ("legAct ");
490 
491  CPGEquationsFB& m_CPGFBSys = *(tgCast::cast<CPGEquations, CPGEquationsFB>(m_pCPGSys));
492 
493  for (std::size_t i = 0; i < spineMuscles.size(); i++)
494  {
495 
496  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
497  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
498 
499  spineMuscles[i]->attach(pStringControl);
500 
501  // First assign node numbers
502  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
503 
504  m_spineControllers.push_back(pStringControl);
505  }
506 
507  // Then determine connectivity and setup string
508  for (std::size_t i = 0; i < m_spineControllers.size(); i++)
509  {
510  tgCPGActuatorControl * const pStringInfo = m_spineControllers[i];
511  assert(pStringInfo != NULL);
512  pStringInfo->setConnectivity(m_spineControllers, edgeActions);
513 
514  //String will own this pointer
515  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
516  m_config.kPosition,
517  m_config.kVelocity);
518  if (m_config.useDefault)
519  {
520  pStringInfo->setupControl(*p_ipc);
521  }
522  else
523  {
524  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
525  }
526  }
527 
528  for (std::size_t i = 0; i < hipMuscles.size(); i++)
529  {
530 
531  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
532  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
533 
534  hipMuscles[i]->attach(pStringControl);
535 
536  // First assign node numbers
537  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
538 
539  m_hipControllers.push_back(pStringControl);
540  }
541 
542  // Then determine connectivity and setup string
543  for (std::size_t i = 0; i < m_hipControllers.size(); i++)
544  {
545  tgCPGActuatorControl * const pStringInfo = m_hipControllers[i];
546  assert(pStringInfo != NULL);
547  pStringInfo->setConnectivity(m_hipControllers, hipEdgeActions);
548 
549  //String will own this pointer
550  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
551  m_config.kPosition,
552  m_config.kVelocity);
553  if (m_config.useDefault)
554  {
555  pStringInfo->setupControl(*p_ipc);
556  }
557  else
558  {
559  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
560  }
561  }
562 
563  /*for (std::size_t i = 0; i < legMuscles.size(); i++)
564  {
565 
566  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
567  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
568 
569  legMuscles[i]->attach(pStringControl);
570 
571  // First assign node numbers
572  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
573 
574  m_legControllers.push_back(pStringControl);
575  }
576 
577  // Then determine connectivity and setup string
578  for (std::size_t i = 0; i < m_legControllers.size(); i++)
579  {
580  tgCPGActuatorControl * const pStringInfo = m_legControllers[i];
581  assert(pStringInfo != NULL);
582  pStringInfo->setConnectivity(m_legControllers, legEdgeActions);
583 
584  //String will own this pointer
585  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
586  m_config.kPosition,
587  m_config.kVelocity);
588  if (m_config.useDefault)
589  {
590  pStringInfo->setupControl(*p_ipc);
591  }
592  else
593  {
594  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
595  }
596  }*/
597 
598 }
599 
601  (Json::Value edgeParam, int theirMuscles, int ourMuscles)
602 {
603  assert(edgeParam[0].size() == 2);
604 
605  double lowerLimit = m_config.lowPhase;
606  double upperLimit = m_config.highPhase;
607  double range = upperLimit - lowerLimit;
608 
609  array_4D actionList(boost::extents[m_config.segmentSpan][theirMuscles][ourMuscles][m_config.params]);
610 
611  /* Horrid while loop to populate upper diagonal of matrix, since
612  * its symmetric and we want to minimze parameters used in learing
613  * note that i==1, j==k will refer to the same muscle
614  * @todo use boost to set up array so storage is only allocated for
615  * elements that are used
616  */
617  int i = 0;
618  int j = 0;
619  int k = 0;
620 
621  // Quirk of the old learning code. Future examples can move forward
622  Json::Value::iterator edgeIt = edgeParam.end();
623 
624  int count = 0;
625 
626  while (i < m_config.segmentSpan)
627  {
628  while(j < theirMuscles)
629  {
630  while(k < ourMuscles)
631  {
632  if (edgeIt == edgeParam.begin())
633  {
634  std::cout << "ran out before table populated!"
635  << std::endl;
637  break;
638  }
639  else
640  {
641  if (i == 1 && j == k)
642  {
643  // std::cout << "Skipped identical muscle" << std::endl;
644  //Skip since its the same muscle
645  }
646  else
647  {
648  edgeIt--;
649  Json::Value edgeParam = *edgeIt;
650  assert(edgeParam.size() == 2);
651  // Weight from 0 to 1
652  actionList[i][j][k][0] = edgeParam[0].asDouble();
653  //std::cout << actionList[i][j][k][0] << " ";
654  // Phase offset from -pi to pi
655  actionList[i][j][k][1] = edgeParam[1].asDouble() *
656  (range) + lowerLimit;
657  //std::cout << actionList[i][j][k][1] << std::endl;
658  count++;
659  }
660  }
661  k++;
662  }
663  j++;
664  k = j;
665 
666  }
667  j = 0;
668  k = 0;
669  i++;
670  }
671 
672  std::cout<< "Params used: " << count << std::endl;
673 
674  assert(edgeParam.begin() == edgeIt);
675 
676  return actionList;
677 }
678 
679 array_2D JSONSegmentsFeedbackControl::scaleNodeActions (Json::Value actions)
680 {
681  std::size_t numControllers = actions.size();
682  std::size_t numActions = actions[0].size();
683 
684  array_2D nodeActions(boost::extents[numControllers][numActions]);
685 
686  array_2D limits(boost::extents[2][numActions]);
687 
688  // Check if we need to update limits
689  assert(numActions == 5);
690 
691  limits[0][0] = m_config.lowFreq;
692  limits[1][0] = m_config.highFreq;
693  limits[0][1] = m_config.lowAmp;
694  limits[1][1] = m_config.highAmp;
695  limits[0][2] = m_config.freqFeedbackMin;
696  limits[1][2] = m_config.freqFeedbackMax;
697  limits[0][3] = m_config.ampFeedbackMin;
698  limits[1][3] = m_config.ampFeedbackMax;
699  limits[0][4] = m_config.phaseFeedbackMin;
700  limits[1][4] = m_config.phaseFeedbackMax;
701 
702  Json::Value::iterator nodeIt = actions.begin();
703 
704  // This one is square
705  for( std::size_t i = 0; i < numControllers; i++)
706  {
707  Json::Value nodeParam = *nodeIt;
708  for( std::size_t j = 0; j < numActions; j++)
709  {
710  nodeActions[i][j] = ( (nodeParam.get(j, 0.0)).asDouble() *
711  (limits[1][j] - limits[0][j])) + limits[0][j];
712  }
713  nodeIt++;
714  }
715 
716  return nodeActions;
717 }
718 
719 std::vector<double> JSONSegmentsFeedbackControl::getFeedback(BaseQuadModelLearning& subject)
720 {
721  // Placeholder
722  std::vector<double> feedback;
723 
724  const std::vector<tgSpringCableActuator*>& spineCables = subject.find<tgSpringCableActuator> ("spine ");
725 
726  double *inputs = new double[m_config.numStates];
727 
728  std::size_t n = spineCables.size();
729  for(std::size_t i = 0; i != n; i++)
730  {
731  std::vector< std::vector<double> > actions;
732 
733  const tgSpringCableActuator& cable = *(spineCables[i]);
734  std::vector<double > state = getCableState(cable);
735 
736  // Rescale to 0 to 1 (consider doing this inside getState
737  for (std::size_t i = 0; i < state.size(); i++)
738  {
739  inputs[i]=state[i] / 2.0 + 0.5;
740  }
741 
742  double *output = nn->feedForwardPattern(inputs);
743  vector<double> tmpAct;
744  for(int j=0;j<m_config.numActions;j++)
745  {
746  tmpAct.push_back(output[j]);
747  }
748  actions.push_back(tmpAct);
749 
750  std::vector<double> cableFeedback = transformFeedbackActions(actions);
751 
752  feedback.insert(feedback.end(), cableFeedback.begin(), cableFeedback.end());
753  }
754 
755  //Doing the same for the hips and legs... consider changing this to allMuscles, by including the short muscles in the spine, to shorten this function.
756  const std::vector<tgSpringCableActuator*>& hipCables = subject.find<tgSpringCableActuator> ("hip ");
757 
758  std::size_t n2 = hipCables.size();
759  for(std::size_t i = 0; i != n2; i++)
760  {
761  std::vector< std::vector<double> > actions;
762 
763  const tgSpringCableActuator& cable = *(hipCables[i]);
764  std::vector<double > state = getCableState(cable);
765 
766  // Rescale to 0 to 1 (consider doing this inside getState
767  for (std::size_t i = 0; i < state.size(); i++)
768  {
769  inputs[i]=state[i] / 2.0 + 0.5;
770  }
771 
772  double *output = nn->feedForwardPattern(inputs);
773  vector<double> tmpAct;
774  for(int j=0;j<m_config.numActions;j++)
775  {
776  tmpAct.push_back(output[j]);
777  }
778  actions.push_back(tmpAct);
779 
780  std::vector<double> cableFeedback = transformFeedbackActions(actions);
781 
782  feedback.insert(feedback.end(), cableFeedback.begin(), cableFeedback.end());
783  }
784 
785  /*const std::vector<tgSpringCableActuator*>& legCables = subject.find<tgSpringCableActuator> ("legAct ");
786 
787  std::size_t n3 = legCables.size();
788  for(std::size_t i = 0; i != n3; i++)
789  {
790  std::vector< std::vector<double> > actions;
791 
792  const tgSpringCableActuator& cable = *(legCables[i]);
793  std::vector<double > state = getCableState(cable);
794 
795  // Rescale to 0 to 1 (consider doing this inside getState
796  for (std::size_t i = 0; i < state.size(); i++)
797  {
798  inputs[i]=state[i] / 2.0 + 0.5;
799  }
800 
801  double *output = nn->feedForwardPattern(inputs);
802  vector<double> tmpAct;
803  for(int j=0;j<m_config.numActions;j++)
804  {
805  tmpAct.push_back(output[j]);
806  }
807  actions.push_back(tmpAct);
808 
809  std::vector<double> cableFeedback = transformFeedbackActions(actions);
810 
811  feedback.insert(feedback.end(), cableFeedback.begin(), cableFeedback.end());
812  }*/
813 
814 
815  return feedback;
816 }
817 
818 std::vector<double> JSONSegmentsFeedbackControl::getCableState(const tgSpringCableActuator& cable)
819 {
820  // For each string, scale value from -1 to 1 based on initial length or max tension of motor
821 
822  std::vector<double> state;
823 
824  // Scale length by starting length
825  const double startLength = cable.getStartLength();
826  state.push_back((cable.getCurrentLength() - startLength) / startLength);
827 
828  const double maxTension = cable.getConfig().maxTens;
829  state.push_back((cable.getTension() - maxTension / 2.0) / maxTension);
830 
831  return state;
832 }
833 
834 std::vector<double> JSONSegmentsFeedbackControl::transformFeedbackActions(std::vector< std::vector<double> >& actions)
835 {
836  // Placeholder
837  std::vector<double> feedback;
838 
839  // Leave in place for generalization later
840  const std::size_t numControllers = 1;
841  const std::size_t numActions = m_config.numActions;
842 
843  assert( actions.size() == numControllers);
844  assert( actions[0].size() == numActions);
845 
846  // Scale values back to -1 to +1
847  for( std::size_t i = 0; i < numControllers; i++)
848  {
849  for( std::size_t j = 0; j < numActions; j++)
850  {
851  feedback.push_back(actions[i][j] * 2.0 - 1.0);
852  }
853  }
854 
855  return feedback;
856 }
857 
Contains the definition of class ImpedanceControl. $Id$.
void update(std::vector< double > &descCom, double dt)
virtual void onSetup(BaseQuadModelLearning &subject)
virtual const double getTension() const
virtual const double getStartLength() const
void setConnectivity(const std::vector< tgCPGActuatorControl * > &allStrings, array_4D edgeParams)
JSONSegmentsFeedbackControl(JSONSegmentsFeedbackControl::Config config, std::string args, std::string resourcePath="")
Definition of the tgCPGStringControl observer class.
virtual array_4D scaleEdgeActions(Json::Value actions, int theirMuscles, int ourMuscles)
A class to read a learning configuration from a .ini file.
A controller for the template class BaseSpineModelLearning more metrics, such as center of mass of e...
Contains the definition of abstract base class tgSpringCableActuator. Assumes that the string is line...
A series of functions to assist with file input/output.
virtual void onStep(BaseQuadModelLearning &subject, double dt)
Contains the definition of class AnnealEvolution. Adapting NeuroEvolution to do Simulated Annealing...
virtual void onTeardown(BaseQuadModelLearning &subject)
Contains the definition of class tgBasicActuator.
const Config & getConfig() const
std::vector< T * > find(const tgTagSearch &tagSearch)
Definition: tgModel.h:128
virtual void onStep(tgModel &model, double dt)
Definition of class CPGEquationsFB.
Config(int ss, int tm, int om, int param, int segnum=6, double ct=0.1, double la=0, double ha=30, double lp=-1 *M_PI, double hp=M_PI, double kt=0.0, double kp=1000.0, double kv=100.0, bool def=true, double cl=10.0, double lf=0.0, double hf=30.0, double ffMin=0.0, double ffMax=0.0, double afMin=0.0, double afMax=0.0, double pfMin=0.0, double pfMax=0.0, double maxH=60.0, double minH=1.0, int ohm=10, int thm=10, int olm=10, int tlm=10)
virtual void onSetup(tgModel &model)
virtual const double getCurrentLength() const
void assignNodeNumberFB(CPGEquationsFB &CPGSys, array_2D nodeParams)