NTRT Simulator  Version: Master
 All Classes Namespaces Files Functions Variables Typedefs Friends Pages
JSONAOHierarchyControl.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 
28 #include "JSONAOHierarchyControl.h"
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 //#define PRINT_METRICS
60 
61 using namespace std;
62 
64  int tm,
65  int om,
66  int param,
67  int segnum,
68  double ct,
69  double la,
70  double ha,
71  double lp,
72  double hp,
73  double kt,
74  double kp,
75  double kv,
76  bool def,
77  double cl,
78  double lf,
79  double hf,
80  double ffMin,
81  double ffMax,
82  double afMin,
83  double afMax,
84  double pfMin,
85  double pfMax,
86  double maxH,
87  double minH,
88  /*int ohm,
89  int thm,
90  int olm,
91  int tlm,
92  int oam,
93  int tam,*/
94  int ohighm,
95  int thighm,
96  double hf2,
97  double ffMax2) :
98 JSONQuadCPGControl::Config::Config(ss, tm, om, param, segnum, ct, la, ha,
99  lp, hp, kt, kp, kv, def, cl, lf, hf),
100 freqFeedbackMin(ffMin),
101 freqFeedbackMax(ffMax),
102 ampFeedbackMin(afMin),
103 ampFeedbackMax(afMax),
104 phaseFeedbackMin(pfMin),
105 phaseFeedbackMax(pfMax),
106 maxHeight(maxH),
107 minHeight(minH),
108 /*ourHipMuscles(ohm),
109 theirHipMuscles(thm),
110 ourLegMuscles(olm),
111 theirLegMuscles(tlm),
112 ourAchillesMuscles(oam),
113 theirAchillesMuscles(tam),
114 ourHighMuscles(ohighm),
115 theirHighMuscles(thighm),*/
116 highFreq2(hf2),
117 freqFeedbackMax2(ffMax2)
118 {
119 
120 }
127  std::string args,
128  std::string resourcePath) :
129 JSONQuadCPGControl(config, args, resourcePath),
130 m_config(config)
131 {
132  // Path and filename handled by base class
133 
134 }
135 
136 JSONAOHierarchyControl::~JSONAOHierarchyControl()
137 {
138  //delete nn;
139 }
140 
142 {
143  m_pCPGSys = new CPGEquationsFB(500);
144 
145  Json::Value root; // will contains the root value after parsing.
146  Json::Reader reader;
147 
148  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
149  if ( !parsingSuccessful )
150  {
151  // report to the user the failure and their locations in the document.
152  std::cout << "Failed to parse configuration\n"
153  << reader.getFormattedErrorMessages();
154  throw std::invalid_argument("Bad filename for JSON");
155  }
156  // Get the value of the member of root named 'encoding', return 'UTF-8' if there is no
157  // such member.
158  // Lower level CPG node and edge params:
159  /*Json::Value spineNodeVals = root.get("spineNodeVals", "UTF-8");
160  Json::Value legNodeVals = root.get("legNodeVals", "UTF-8");
161  Json::Value spineEdgeVals = root.get("spineEdgeVals", "UTF-8");
162  Json::Value hipEdgeVals = root.get("hipEdgeVals", "UTF-8");
163  Json::Value legEdgeVals = root.get("legEdgeVals", "UTF-8");*/
164  Json::Value achillesNodeVals = root.get("achillesNodeVals", "UTF-8");
165  Json::Value achillesEdgeVals = root.get("achillesEdgeVals", "UTF-8");
166 
167  std::cout << achillesNodeVals << std::endl;
168 
169  /*spineNodeVals = spineNodeVals.get("params", "UTF-8");
170  legNodeVals = legNodeVals.get("params", "UTF-8");
171  spineEdgeVals = spineEdgeVals.get("params", "UTF-8");
172  hipEdgeVals = hipEdgeVals.get("params", "UTF-8");
173  legEdgeVals = legEdgeVals.get("params", "UTF-8");*/
174  achillesNodeVals = achillesNodeVals.get("params", "UTF-8");
175  achillesEdgeVals = achillesEdgeVals.get("params", "UTF-8");
176 
177  // A painful way of reducing the solution space... had to rewrite scaleEdgeActions() to take in a couple more parameters.
178  //array_4D spineEdgeParams = scaleEdgeActions(spineEdgeVals,m_config.segmentSpan,m_config.theirMuscles,m_config.ourMuscles);
179  //array_4D hipEdgeParams = scaleEdgeActions(hipEdgeVals,m_config.segmentSpan,m_config.theirHipMuscles,m_config.ourHipMuscles);
180  //array_4D legEdgeParams = scaleEdgeActions(legEdgeVals,m_config.segmentSpan,m_config.theirLegMuscles,m_config.ourLegMuscles);
181  array_4D achillesEdgeParams = scaleEdgeActions(achillesEdgeVals,m_config.segmentSpan,m_config.theirMuscles,m_config.ourMuscles);
182  //array_2D spineNodeParams = scaleNodeActions(spineNodeVals, m_config.highFreq, m_config.freqFeedbackMax);
183  //array_2D legNodeParams = scaleNodeActions(legNodeVals, m_config.highFreq, m_config.freqFeedbackMax);
184  array_2D achillesNodeParams = scaleNodeActions(achillesNodeVals, m_config.highFreq, m_config.freqFeedbackMax);
185 
186  // Setup the lower level of CPGs
187  setupCPGs(subject, achillesNodeParams, achillesEdgeParams);
188 
189  Json::Value feedbackParams = root.get("feedbackVals", "UTF-8");
190  feedbackParams = feedbackParams.get("params", "UTF-8");
191 
192  // Setup neural network
193  m_config.numStates = feedbackParams.get("numStates", "UTF-8").asInt();
194  m_config.numActions = feedbackParams.get("numActions", "UTF-8").asInt();
195  //m_config.numHidden = feedbackParams.get("numHidden", "UTF-8").asInt();
196 
197  std::string nnFile = controlFilePath + feedbackParams.get("neuralFilename", "UTF-8").asString();
198 
199  nn = new neuralNetwork(m_config.numStates, m_config.numStates*2, m_config.numActions);
200 
201  nn->loadWeights(nnFile.c_str());
202 
203  initConditions = subject.getSegmentCOM(m_config.segmentNumber);
204  for (int i = 0; i < initConditions.size(); i++)
205  {
206  std::cout << initConditions[i] << " ";
207  }
208  std::cout << std::endl;
209 #ifdef LOGGING // Conditional compile for data logging
210  m_dataObserver.onSetup(subject);
211 #endif
212 
213 #if (0) // Conditional Compile for debug info
214  std::cout << *m_pCPGSys << std::endl;
215 #endif
216  m_updateTime = 0.0;
217  m_totalTime = 0.0; //For metrics.
218  bogus = false;
219 
220  metrics.clear();
221 
222  //Getting the center of mass of the entire structure.
223  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
224 
225  for(std::size_t i=0; i<3; i++)
226  {
227  metrics.push_back(structureCOM[i]);
228  }
229 
230  //"metrics" is a new section of the controller's JSON file that is
231  //added in the getNewFile function in evolution_job_master.py
232  Json::Value prevMetrics = root.get("metrics", Json::nullValue);
233 
234  Json::Value subMetrics;
235  subMetrics["initial COM x"] = metrics[0];
236  subMetrics["initial COM y"] = metrics[1];
237  subMetrics["initial COM z"] = metrics[2];
238 
239  prevMetrics.append(subMetrics);
240  root["metrics"] = prevMetrics;
241 
242  ofstream payloadLog;
243  payloadLog.open(controlFilename.c_str(),ofstream::out);
244 
245  payloadLog << root << std::endl;
246 
247 
248 #if(1)
249  Json::Value PVal = root.get("propVals", "UTF-8");
250  Json::Value DVal = root.get("derVals", "UTF-8");
251 
252  cout << PVal << endl;
253 
254  // Keep drilling if necessary
255  PVal = PVal.get("params", "UTF-8");
256  DVal = DVal.get("params", "UTF-8");
257 
258  if (PVal[0].isArray())
259  {
260  PVal = PVal[0];
261  }
262  if (DVal[0].isArray())
263  {
264  DVal = DVal[0];
265  }
266 
267  int j = 0;
268  P = (PVal.get(j, 0.0)).asDouble();
269  D = (DVal.get(j, 0.0)).asDouble();
270 #endif
271 
272 }
273 
275 {
276  m_updateTime += dt;
277  m_totalTime += dt;
278  if (m_updateTime >= m_config.controlTime)
279  {
280 #if (1)
281  std::vector<double> desComs = getFeedback(subject);
282 
283 #else
284  std::size_t numControllers = subject.getNumberofMuslces() * 3;
285 
286  double descendingCommand = 0.0;
287  std::vector<double> desComs (numControllers, descendingCommand);
288 #endif
289  try
290  {
291  m_pCPGSys->update(desComs, m_updateTime);
292  }
293  catch (std::runtime_error& e)
294  {
295  // Stops the trial immediately, lets teardown know it broke
296  bogus = true;
297  throw (e);
298  }
299 
300 #ifdef LOGGING // Conditional compile for data logging
301  m_dataObserver.onStep(subject, m_updateTime);
302 #endif
303  notifyStep(m_updateTime);
304  m_updateTime = 0;
305  }
306 
307  double currentHeight = subject.getSegmentCOM(m_config.segmentNumber)[1];
308  double currentHeightRear = subject.getSegmentCOM(6)[1];
309 
311  if (currentHeight > m_config.maxHeight || currentHeight < m_config.minHeight || currentHeightRear > m_config.maxHeight || currentHeightRear < m_config.minHeight)
312  {
314  bogus = true;
315  throw std::runtime_error("Height out of range");
316  }
317 
318 }
319 
321 {
322  scores.clear();
323  metrics.clear();
324  // @todo - check to make sure we ran for the right amount of time
325 
326  std::vector<double> finalConditions = subject.getSegmentCOM(m_config.segmentNumber);
327 
328  const double newX = finalConditions[0];
329  const double newZ = finalConditions[2];
330  const double oldX = initConditions[0];
331  const double oldZ = initConditions[2];
332 
333  const double distanceMoved = sqrt((newX-oldX) * (newX-oldX) +
334  (newZ-oldZ) * (newZ-oldZ));
335 
336  if (bogus)
337  {
338  scores.push_back(-1.0);
339  }
340  else
341  {
342  scores.push_back(distanceMoved);
343  }
344 
347  double totalEnergySpent=0;
348 
349  std::vector<tgSpringCableActuator* > tmpStrings = subject.find<tgSpringCableActuator> ("only ");
350 
351  for(std::size_t i=0; i<tmpStrings.size(); i++)
352  {
353  tgSpringCableActuator::SpringCableActuatorHistory stringHist = tmpStrings[i]->getHistory();
354 
355  for(std::size_t j=1; j<stringHist.tensionHistory.size(); j++)
356  {
357  const double previousTension = stringHist.tensionHistory[j-1];
358  const double previousLength = stringHist.restLengths[j-1];
359  const double currentLength = stringHist.restLengths[j];
360  //TODO: examine this assumption - free spinning motor may require more power
361  double motorSpeed = (currentLength-previousLength);
362  if(motorSpeed > 0) // Vestigial code
363  motorSpeed = 0;
364  const double workDone = previousTension * motorSpeed;
365  totalEnergySpent += workDone;
366  }
367  }
368 
369  scores.push_back(totalEnergySpent);
370 
371  //Getting the center of mass of the entire structure.
372  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
373 
374  for(std::size_t i=0; i<3; i++)
375  {
376  metrics.push_back(structureCOM[i]);
377  }
378 
379  std::cout << "Dist travelled " << scores[0] << std::endl;
380 
381  Json::Value root; // will contain the root value after parsing.
382  Json::Reader reader;
383 
384  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
385  if ( !parsingSuccessful )
386  {
387  // report to the user the failure and their locations in the document.
388  std::cout << "Failed to parse configuration\n"
389  << reader.getFormattedErrorMessages();
390  throw std::invalid_argument("Bad filename for JSON");
391  }
392 
393  Json::Value prevScores = root.get("scores", Json::nullValue);
394  Json::Value prevMetrics = root.get("metrics", Json::nullValue);
395 
396  Json::Value subScores;
397  subScores["distance"] = scores[0];
398  subScores["energy"] = scores[1];
399 
400  Json::Value subMetrics;
401  subMetrics["final COM x"] = metrics[0];
402  subMetrics["final COM y"] = metrics[1];
403  subMetrics["final COM z"] = metrics[2];
404 
405  prevScores.append(subScores);
406  prevMetrics.append(subMetrics);
407 
408  root["scores"] = prevScores;
409  root["metrics"] = prevMetrics;
410 
411  ofstream payloadLog;
412  payloadLog.open(controlFilename.c_str(),ofstream::out);
413 
414  payloadLog << root << std::endl;
415 
416  delete m_pCPGSys;
417  m_pCPGSys = NULL;
418 
419  // This is ugly, will clean up later:
420 
421  //Achilles controllers
422  for(size_t i = 0; i < m_leftFrontAchillesControllers.size(); i++)
423  {
424  delete m_leftFrontAchillesControllers[i];
425  }
426  m_leftFrontAchillesControllers.clear();
427 
428  for(size_t i = 0; i < m_rightFrontAchillesControllers.size(); i++)
429  {
430  delete m_rightFrontAchillesControllers[i];
431  }
432  m_rightFrontAchillesControllers.clear();
433 
434  for(size_t i = 0; i < m_leftRearAchillesControllers.size(); i++)
435  {
436  delete m_leftRearAchillesControllers[i];
437  }
438  m_leftRearAchillesControllers.clear();
439 
440  for(size_t i = 0; i < m_rightRearAchillesControllers.size(); i++)
441  {
442  delete m_rightRearAchillesControllers[i];
443  }
444  m_rightRearAchillesControllers.clear();
445 
446  // Trying to delete here instead, to fix the leak
447  delete nn;
448 
449 }
450 
451 //Note: Will make a more compact, reuseable function later when I decide on how want to handle m_xControllers for different body parts
452 //Perhaps a vector of vectors can be created, so looping can be done instead, or the function can be reused.
453 //For now, I'll settle for horrendous but works.
454 //This way makes it easier to grab the right node numbers again when doing high-low couplings.
455 void JSONAOHierarchyControl::setupCPGs(BaseQuadModelLearning& subject, array_2D achillesNodeActions, array_4D achillesEdgeActions)
456 {
457 
458  // Achilles muscles
459  std::vector <tgSpringCableActuator*> leftFrontAchillesMuscles = subject.find<tgSpringCableActuator> ("left_front_achilles_tendon");
460  std::vector <tgSpringCableActuator*> rightFrontAchillesMuscles = subject.find<tgSpringCableActuator> ("right_front_achilles_tendon");
461 
462  std::vector <tgSpringCableActuator*> leftRearAchillesMuscles = subject.find<tgSpringCableActuator> ("left_rear_achilles_tendon");
463  std::vector <tgSpringCableActuator*> rightRearAchillesMuscles = subject.find<tgSpringCableActuator> ("right_rear_achilles_tendon");
464 
465  CPGEquationsFB& m_CPGFBSys = *(tgCast::cast<CPGEquations, CPGEquationsFB>(m_pCPGSys));
466 
467 
468 
469  /*
470  * ACHILLES START HERE
471  */
472  // Left front achilles first
473  for (std::size_t i = 0; i < leftFrontAchillesMuscles.size(); i++)
474  {
475 
476  tgPIDController::Config config(P, 0.0, D, true); // Non backdrivable
477  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
478 
479  leftFrontAchillesMuscles[i]->attach(pStringControl);
480 
481  // First assign node numbers
482  pStringControl->assignNodeNumberFB(m_CPGFBSys, achillesNodeActions);
483 
484  m_leftFrontAchillesControllers.push_back(pStringControl);
485  }
486 
487  // Then determine connectivity and setup string
488  for (std::size_t i = 0; i < m_leftFrontAchillesControllers.size(); i++)
489  {
490  tgCPGActuatorControl * const pStringInfo = m_leftFrontAchillesControllers[i];
491  assert(pStringInfo != NULL);
492  pStringInfo->setConnectivity(m_leftFrontAchillesControllers, achillesEdgeActions);
493 
494  //String will own this pointer
495  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
496  m_config.kPosition,
497  m_config.kVelocity);
498  if (m_config.useDefault)
499  {
500  pStringInfo->setupControl(*p_ipc);
501  }
502  else
503  {
504  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
505  }
506  }
507 
508  // Now right front achilles
509  for (std::size_t i = 0; i < rightFrontAchillesMuscles.size(); i++)
510  {
511 
512  tgPIDController::Config config(P, 0.0, D, true); // Non backdrivable
513  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
514 
515  rightFrontAchillesMuscles[i]->attach(pStringControl);
516 
517  // First assign node numbers
518  pStringControl->assignNodeNumberFB(m_CPGFBSys, achillesNodeActions);
519 
520  m_rightFrontAchillesControllers.push_back(pStringControl);
521  }
522 
523  // Then determine connectivity and setup string
524  for (std::size_t i = 0; i < m_rightFrontAchillesControllers.size(); i++)
525  {
526  tgCPGActuatorControl * const pStringInfo = m_rightFrontAchillesControllers[i];
527  assert(pStringInfo != NULL);
528  pStringInfo->setConnectivity(m_rightFrontAchillesControllers, achillesEdgeActions);
529 
530  //String will own this pointer
531  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
532  m_config.kPosition,
533  m_config.kVelocity);
534  if (m_config.useDefault)
535  {
536  pStringInfo->setupControl(*p_ipc);
537  }
538  else
539  {
540  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
541  }
542  }
543 
544  // Now left rear achilles
545  for (std::size_t i = 0; i < leftRearAchillesMuscles.size(); i++)
546  {
547 
548  tgPIDController::Config config(P, 0.0, D, true); // Non backdrivable
549  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
550 
551  leftRearAchillesMuscles[i]->attach(pStringControl);
552 
553  // First assign node numbers
554  pStringControl->assignNodeNumberFB(m_CPGFBSys, achillesNodeActions);
555 
556  m_leftRearAchillesControllers.push_back(pStringControl);
557  }
558 
559  // Then determine connectivity and setup string
560  for (std::size_t i = 0; i < m_leftRearAchillesControllers.size(); i++)
561  {
562  tgCPGActuatorControl * const pStringInfo = m_leftRearAchillesControllers[i];
563  assert(pStringInfo != NULL);
564  pStringInfo->setConnectivity(m_leftRearAchillesControllers, achillesEdgeActions);
565 
566  //String will own this pointer
567  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
568  m_config.kPosition,
569  m_config.kVelocity);
570  if (m_config.useDefault)
571  {
572  pStringInfo->setupControl(*p_ipc);
573  }
574  else
575  {
576  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
577  }
578  }
579 
580  // Finally, right rear achilles
581  for (std::size_t i = 0; i < rightRearAchillesMuscles.size(); i++)
582  {
583 
584  tgPIDController::Config config(P, 0.0, D, true); // Non backdrivable
585  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
586 
587  rightRearAchillesMuscles[i]->attach(pStringControl);
588 
589  // First assign node numbers
590  pStringControl->assignNodeNumberFB(m_CPGFBSys, achillesNodeActions);
591 
592  m_rightRearAchillesControllers.push_back(pStringControl);
593  }
594 
595  // Then determine connectivity and setup string
596  for (std::size_t i = 0; i < m_rightRearAchillesControllers.size(); i++)
597  {
598  tgCPGActuatorControl * const pStringInfo = m_rightRearAchillesControllers[i];
599  assert(pStringInfo != NULL);
600  pStringInfo->setConnectivity(m_rightRearAchillesControllers, achillesEdgeActions);
601 
602  //String will own this pointer
603  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
604  m_config.kPosition,
605  m_config.kVelocity);
606  if (m_config.useDefault)
607  {
608  pStringInfo->setupControl(*p_ipc);
609  }
610  else
611  {
612  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
613  }
614  }
615 
616 }
617 
618 array_2D JSONAOHierarchyControl::scaleNodeActions (Json::Value actions, double highFreq, double freqFeedbackMax)
619 {
620  std::size_t numControllers = actions.size();
621  std::size_t numActions = actions[0].size();
622 
623  array_2D nodeActions(boost::extents[numControllers][numActions]);
624 
625  array_2D limits(boost::extents[2][numActions]);
626 
627  // Check if we need to update limits
628  assert(numActions == 5);
629 
630  limits[0][0] = m_config.lowFreq;
631  limits[1][0] = highFreq;
632  limits[0][1] = m_config.lowAmp;
633  limits[1][1] = m_config.highAmp;
634  limits[0][2] = m_config.freqFeedbackMin;
635  limits[1][2] = freqFeedbackMax;
636  limits[0][3] = m_config.ampFeedbackMin;
637  limits[1][3] = m_config.ampFeedbackMax;
638  limits[0][4] = m_config.phaseFeedbackMin;
639  limits[1][4] = m_config.phaseFeedbackMax;
640 
641  Json::Value::iterator nodeIt = actions.begin();
642 
643  // This one is square
644  for( std::size_t i = 0; i < numControllers; i++)
645  {
646  Json::Value nodeParam = *nodeIt;
647  for( std::size_t j = 0; j < numActions; j++)
648  {
649  nodeActions[i][j] = ( (nodeParam.get(j, 0.0)).asDouble() *
650  (limits[1][j] - limits[0][j])) + limits[0][j];
651  }
652  nodeIt++;
653  }
654 
655  return nodeActions;
656 }
657 
659  (Json::Value edgeParam, int segmentSpan, int theirMuscles, int ourMuscles)
660 {
661  assert(edgeParam[0].size() == 2);
662 
663  double lowerLimit = m_config.lowPhase;
664  double upperLimit = m_config.highPhase;
665  double range = upperLimit - lowerLimit;
666 
667  array_4D actionList(boost::extents[segmentSpan][theirMuscles][ourMuscles][m_config.params]);
668 
669  /* Horrid while loop to populate upper diagonal of matrix, since
670  * its symmetric and we want to minimze parameters used in learing
671  * note that i==1, j==k will refer to the same muscle
672  * @todo use boost to set up array so storage is only allocated for
673  * elements that are used
674  */
675  int i = 0;
676  int j = 0;
677  int k = 0;
678 
679  // Quirk of the old learning code. Future examples can move forward
680  Json::Value::iterator edgeIt = edgeParam.end();
681 
682  int count = 0;
683 
684  while (i < segmentSpan)
685  {
686  while(j < theirMuscles)
687  {
688  while(k < ourMuscles)
689  {
690  if (edgeIt == edgeParam.begin())
691  {
692  std::cout << "ran out before table populated!"
693  << std::endl;
695  break;
696  }
697  else
698  {
699  if (i == 1 && j == k)
700  {
701  // std::cout << "Skipped identical muscle" << std::endl;
702  //Skip since its the same muscle
703  }
704  else
705  {
706  edgeIt--;
707  Json::Value edgeParam = *edgeIt;
708  assert(edgeParam.size() == 2);
709  // Weight from 0 to 1
710  actionList[i][j][k][0] = edgeParam[0].asDouble();
711  //std::cout << actionList[i][j][k][0] << " ";
712  // Phase offset from -pi to pi
713  actionList[i][j][k][1] = edgeParam[1].asDouble() *
714  (range) + lowerLimit;
715  //std::cout << actionList[i][j][k][1] << std::endl;
716  count++;
717  }
718  }
719  k++;
720  }
721  j++;
722  k = j;
723 
724  }
725  j = 0;
726  k = 0;
727  i++;
728  }
729 
730  std::cout<< "Params used: " << count << std::endl;
731 
732  assert(edgeParam.begin() == edgeIt);
733 
734  return actionList;
735 }
736 
737 std::vector<double> JSONAOHierarchyControl::getFeedback(BaseQuadModelLearning& subject)
738 {
739  // Placeholder
740  std::vector<double> feedback;
741 
742  const std::vector<tgSpringCableActuator*>& allCables = subject.find<tgSpringCableActuator> ("only ");
743 
744  double *inputs = new double[m_config.numStates];
745 
746  std::size_t n = allCables.size();
747  for(std::size_t i = 0; i != n; i++)
748  {
749  std::vector< std::vector<double> > actions;
750 
751  const tgSpringCableActuator& cable = *(allCables[i]);
752  std::vector<double > state = getCableState(cable);
753 
754  // Rescale to 0 to 1 (consider doing this inside getState
755  for (std::size_t i = 0; i < state.size(); i++)
756  {
757  inputs[i]=state[i] / 2.0 + 0.5;
758  }
759 
760  double *output = nn->feedForwardPattern(inputs);
761  vector<double> tmpAct;
762  for(int j=0;j<m_config.numActions;j++)
763  {
764  tmpAct.push_back(output[j]);
765  }
766  actions.push_back(tmpAct);
767 
768  std::vector<double> cableFeedback = transformFeedbackActions(actions);
769 
770  feedback.insert(feedback.end(), cableFeedback.begin(), cableFeedback.end());
771  }
772 
773  return feedback;
774 }
775 
776 std::vector<double> JSONAOHierarchyControl::getCableState(const tgSpringCableActuator& cable)
777 {
778  // For each string, scale value from -1 to 1 based on initial length or max tension of motor
779 
780  std::vector<double> state;
781 
782  // Scale length by starting length
783  const double startLength = cable.getStartLength();
784  state.push_back((cable.getCurrentLength() - startLength) / startLength);
785 
786  const double maxTension = cable.getConfig().maxTens;
787  state.push_back((cable.getTension() - maxTension / 2.0) / maxTension);
788 
789  return state;
790 }
791 
792 std::vector<double> JSONAOHierarchyControl::transformFeedbackActions(std::vector< std::vector<double> >& actions)
793 {
794  // Placeholder
795  std::vector<double> feedback;
796 
797  // Leave in place for generalization later
798  const std::size_t numControllers = 1;
799  const std::size_t numActions = m_config.numActions;
800 
801  assert( actions.size() == numControllers);
802  assert( actions[0].size() == numActions);
803 
804  // Scale values back to -1 to +1
805  for( std::size_t i = 0; i < numControllers; i++)
806  {
807  for( std::size_t j = 0; j < numActions; j++)
808  {
809  feedback.push_back(actions[i][j] * 2.0 - 1.0);
810  }
811  }
812 
813  return feedback;
814 }
Contains the definition of class ImpedanceControl. $Id$.
JSONAOHierarchyControl(JSONAOHierarchyControl::Config config, std::string args, std::string resourcePath="")
void update(std::vector< double > &descCom, double dt)
virtual const double getTension() const
virtual const double getStartLength() const
void setConnectivity(const std::vector< tgCPGActuatorControl * > &allStrings, array_4D edgeParams)
Definition of the tgCPGStringControl observer class.
virtual void onSetup(BaseQuadModelLearning &subject)
A class to read a learning configuration from a .ini file.
Contains the definition of abstract base class tgSpringCableActuator. Assumes that the string is line...
virtual void onTeardown(BaseQuadModelLearning &subject)
A series of functions to assist with file input/output.
virtual array_4D scaleEdgeActions(Json::Value actions, int segmentSpan, int theirMuscles, int ourMuscles)
virtual void onStep(BaseQuadModelLearning &subject, double dt)
Contains the definition of class AnnealEvolution. Adapting NeuroEvolution to do Simulated Annealing...
Contains the definition of class tgBasicActuator.
const Config & getConfig() const
A controller for the template class BaseQuadModelLearning Implementing a CPG hierachy for MountainGoa...
std::vector< T * > find(const tgTagSearch &tagSearch)
Definition: tgModel.h:128
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 ohighm=5, int thighm=5, double hf2=20.0, double ffMax2=0.0)
virtual void onStep(tgModel &model, double dt)
Definition of class CPGEquationsFB.
virtual void onSetup(tgModel &model)
virtual const double getCurrentLength() const
void assignNodeNumberFB(CPGEquationsFB &CPGSys, array_2D nodeParams)