NTRT Simulator  Version: Master
 All Classes Namespaces Files Functions Variables Typedefs Friends Pages
JSONMGFeedbackControl.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 "JSONMGFeedbackControl.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"
37 #include "tgCPGMGActuatorControl.h"
38 #include "tgCPGMGCableControl.h"
39 
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 JSONMGCPGGeneralControl::Config::Config(ss, tm, om, param, segnum, ct, la, ha,
88  lp, hp, kt, kp, kv, def, cl, lf, hf),
89 freqFeedbackMin(ffMin),
90 freqFeedbackMax(ffMax),
91 ampFeedbackMin(afMin),
92 ampFeedbackMax(afMax),
93 phaseFeedbackMin(pfMin),
94 phaseFeedbackMax(pfMax),
95 maxHeight(maxH),
96 minHeight(minH)
97 {
98 
99 }
106  std::string args,
107  std::string resourcePath) :
108 JSONMGCPGGeneralControl(config, args, resourcePath),
109 m_config(config)
110 {
111  // Path and filename handled by base class
112 
113 }
114 
115 JSONMGFeedbackControl::~JSONMGFeedbackControl()
116 {
117  delete nn;
118 }
119 
121 {
122  m_pCPGSys = new CPGEquationsFB(1000000);
123 
124  Json::Value root; // will contains the root value after parsing.
125  Json::Reader reader;
126 
127  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
128  if ( !parsingSuccessful )
129  {
130  // report to the user the failure and their locations in the document.
131  std::cout << "Failed to parse configuration\n"
132  << reader.getFormattedErrorMessages();
133  throw std::invalid_argument("Bad filename for JSON");
134  }
135  // Get the value of the member of root named 'encoding', return 'UTF-8' if there is no
136  // such member.
137  Json::Value nodeVals = root.get("nodeVals", "UTF-8");
138  Json::Value edgeVals = root.get("edgeVals", "UTF-8");
139 
140  std::cout << nodeVals << std::endl;
141 
142  nodeVals = nodeVals.get("params", "UTF-8");
143  edgeVals = edgeVals.get("params", "UTF-8");
144 
145  array_3D edgeParams = scaleEdgeActions(edgeVals);
146  array_2D nodeParams = scaleNodeActions(nodeVals);
147 
148  setupCPGs(subject, nodeParams, edgeParams);
149 
150  Json::Value feedbackParams = root.get("feedbackVals", "UTF-8");
151  feedbackParams = feedbackParams.get("params", "UTF-8");
152 
153  // Setup neural network
154  m_config.numStates = feedbackParams.get("numStates", "UTF-8").asInt();
155  m_config.numActions = feedbackParams.get("numActions", "UTF-8").asInt();
156  //m_config.numHidden = feedbackParams.get("numHidden", "UTF-8").asInt();
157 
158  std::string nnFile = controlFilePath + feedbackParams.get("neuralFilename", "UTF-8").asString();
159 
160  nn = new neuralNetwork(m_config.numStates, m_config.numStates*2, m_config.numActions);
161 
162  nn->loadWeights(nnFile.c_str());
163 
164  initConditions = subject.getSegmentCOM(m_config.segmentNumber);
165  for (int i = 0; i < initConditions.size(); i++)
166  {
167  std::cout << initConditions[i] << " ";
168  }
169  std::cout << std::endl;
170 #ifdef LOGGING // Conditional compile for data logging
171  m_dataObserver.onSetup(subject);
172 #endif
173 
174 #if (0) // Conditional Compile for debug info
175  std::cout << *m_pCPGSys << std::endl;
176 #endif
177  m_updateTime = 0.0;
178  m_totalTime = 0.0; //For metrics.
179  bogus = false;
180 
181  metrics.clear();
182 
183  //Getting the center of mass of the entire structure.
184  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
185 
186  for(std::size_t i=0; i<3; i++)
187  {
188  metrics.push_back(structureCOM[i]);
189  }
190 
191  //"metrics" is a new section of the controller's JSON file that is
192  //added in the getNewFile function in evolution_job_master.py
193  Json::Value prevMetrics = root.get("metrics", Json::nullValue);
194 
195  Json::Value subMetrics;
196  subMetrics["initial COM x"] = metrics[0];
197  subMetrics["initial COM y"] = metrics[1];
198  subMetrics["initial COM z"] = metrics[2];
199 
200  prevMetrics.append(subMetrics);
201  root["metrics"] = prevMetrics;
202 
203  ofstream payloadLog;
204  payloadLog.open(controlFilename.c_str(),ofstream::out);
205 
206  payloadLog << root << std::endl;
207 }
208 
210 {
211  m_updateTime += dt;
212  m_totalTime += dt;
213  if (m_updateTime >= m_config.controlTime)
214  {
215 #if (1)
216  std::vector<double> desComs = getFeedback(subject);
217 
218 #else
219  std::size_t numControllers = subject.getNumberofMuslces() * 3;
220 
221  double descendingCommand = 0.0;
222  std::vector<double> desComs (numControllers, descendingCommand);
223 #endif
224  try
225  {
226  m_pCPGSys->update(desComs, m_updateTime);
227  }
228  catch (std::runtime_error& e)
229  {
230  // Stops the trial immediately, lets teardown know it broke
231  bogus = true;
232  throw (e);
233  }
234 
235 #ifdef LOGGING // Conditional compile for data logging
236  m_dataObserver.onStep(subject, m_updateTime);
237 #endif
238  notifyStep(m_updateTime);
239  m_updateTime = 0;
240  }
241 
242  double currentHeight = subject.getSegmentCOM(m_config.segmentNumber)[1];
243 
245  if (currentHeight > m_config.maxHeight || currentHeight < m_config.minHeight)
246  {
248  bogus = true;
249  throw std::runtime_error("Height out of range");
250  }
251  //every 100 steps, get the COM and tensions of active muscles and store them in the JSON file.
252  if(0){
253  static int count = 0;
254  if(count > 100) {
255  std::cout << m_totalTime << std::endl;
256 
257  //Getting the center of mass of the entire structure.
258  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
259  std::cout << "COM: " << structureCOM[0] << " " << structureCOM[1] << " " << structureCOM[2] << " ";
260  std::cout << std::endl;
261  //Clear the metrics vector for ease of adding tensions.
262  //metrics.clear();
263 
264  std::vector<tgSpringCableActuator* > tmpStrings = subject.find<tgSpringCableActuator> ("all ");
265 
266  for(std::size_t i=0; i<tmpStrings.size(); i++)
267  {
268  std::cout << "Muscle Tension " << i << ": " << tmpStrings[i]->getTension() << std::endl;
269  }
270  std::cout << std::endl;
271 
272  for(std::size_t i=0; i<tmpStrings.size(); i++)
273  {
274  std::cout << "Muscle Length " << i << ": " << tmpStrings[i]->getCurrentLength() << std::endl;
275  }
276  std::cout << std::endl;
277 
278  count = 0;
279  }
280  else {
281  count++;
282  }
283  }
284 }
285 
287 {
288  scores.clear();
289  metrics.clear();
290  // @todo - check to make sure we ran for the right amount of time
291 
292  std::vector<double> finalConditions = subject.getSegmentCOM(m_config.segmentNumber);
293 
294  const double newX = finalConditions[0];
295  const double newZ = finalConditions[2];
296  const double oldX = initConditions[0];
297  const double oldZ = initConditions[2];
298 
299  const double distanceMoved = sqrt((newX-oldX) * (newX-oldX) +
300  (newZ-oldZ) * (newZ-oldZ));
301 
302  if (bogus)
303  {
304  scores.push_back(-1.0);
305  }
306  else
307  {
308  scores.push_back(distanceMoved);
309  }
310 
313  double totalEnergySpent=0;
314 
315  std::vector<tgSpringCableActuator* > tmpStrings = subject.find<tgSpringCableActuator> ("all ");
316 
317  for(std::size_t i=0; i<tmpStrings.size(); i++)
318  {
319  tgSpringCableActuator::SpringCableActuatorHistory stringHist = tmpStrings[i]->getHistory();
320 
321  for(std::size_t j=1; j<stringHist.tensionHistory.size(); j++)
322  {
323  const double previousTension = stringHist.tensionHistory[j-1];
324  const double previousLength = stringHist.restLengths[j-1];
325  const double currentLength = stringHist.restLengths[j];
326  //TODO: examine this assumption - free spinning motor may require more power
327  double motorSpeed = (currentLength-previousLength);
328  if(motorSpeed > 0) // Vestigial code
329  motorSpeed = 0;
330  const double workDone = previousTension * motorSpeed;
331  totalEnergySpent += workDone;
332  }
333  }
334 
335  scores.push_back(totalEnergySpent);
336 
337  //Getting the center of mass of the entire structure.
338  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
339 
340  for(std::size_t i=0; i<3; i++)
341  {
342  metrics.push_back(structureCOM[i]);
343  }
344 
345  std::cout << "Dist travelled " << scores[0] << std::endl;
346 
347  Json::Value root; // will contain the root value after parsing.
348  Json::Reader reader;
349 
350  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
351  if ( !parsingSuccessful )
352  {
353  // report to the user the failure and their locations in the document.
354  std::cout << "Failed to parse configuration\n"
355  << reader.getFormattedErrorMessages();
356  throw std::invalid_argument("Bad filename for JSON");
357  }
358 
359  Json::Value prevScores = root.get("scores", Json::nullValue);
360  Json::Value prevMetrics = root.get("metrics", Json::nullValue);
361 
362  Json::Value subScores;
363  subScores["distance"] = scores[0];
364  subScores["energy"] = scores[1];
365 
366  Json::Value subMetrics;
367  subMetrics["final COM x"] = metrics[0];
368  subMetrics["final COM y"] = metrics[1];
369  subMetrics["final COM z"] = metrics[2];
370 
371  prevScores.append(subScores);
372  prevMetrics.append(subMetrics);
373 
374  root["scores"] = prevScores;
375  root["metrics"] = prevMetrics;
376 
377  ofstream payloadLog;
378  payloadLog.open(controlFilename.c_str(),ofstream::out);
379 
380  payloadLog << root << std::endl;
381 
382  delete m_pCPGSys;
383  m_pCPGSys = NULL;
384 
385  for(size_t i = 0; i < m_spineControllers.size(); i++)
386  {
387  delete m_spineControllers[i];
388  }
389  m_spineControllers.clear();
390 }
391 
392 void JSONMGFeedbackControl::setupCPGs(BaseQuadModelLearning& subject, array_2D nodeActions, array_3D edgeActions)
393 {
394 
395  std::vector <tgSpringCableActuator*> spineMuscles = subject.find<tgSpringCableActuator> ("all ");
396 
397  CPGEquationsFB& m_CPGFBSys = *(tgCast::cast<CPGEquations, CPGEquationsFB>(m_pCPGSys));
398 
399  for (std::size_t i = 0; i < spineMuscles.size(); i++)
400  {
401 
402  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
403  tgCPGMGCableControl* pStringControl = new tgCPGMGCableControl(config);
404 
405  spineMuscles[i]->attach(pStringControl);
406 
407  // First assign node numbers
408  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
409 
410  m_spineControllers.push_back(pStringControl);
411  }
412 
413  // Then determine connectivity and setup string
414  for (std::size_t i = 0; i < m_spineControllers.size(); i++)
415  {
416  tgCPGMGActuatorControl * const pStringInfo = m_spineControllers[i];
417  assert(pStringInfo != NULL);
418  pStringInfo->setConnectivity(m_spineControllers, edgeActions); //May need a new function, written in a subclass, to deal with the long muscles, though this will be fine for segments 1 through 5.
419 
420  //String will own this pointer
421  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
422  m_config.kPosition,
423  m_config.kVelocity);
424  if (m_config.useDefault)
425  {
426  pStringInfo->setupControl(*p_ipc);
427  }
428  else
429  {
430  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
431  }
432  }
433 
434 }
435 
436 array_2D JSONMGFeedbackControl::scaleNodeActions (Json::Value actions)
437 {
438  std::size_t numControllers = actions.size();
439  std::size_t numActions = actions[0].size();
440 
441  array_2D nodeActions(boost::extents[numControllers][numActions]);
442 
443  array_2D limits(boost::extents[2][numActions]);
444 
445  // Check if we need to update limits
446  assert(numActions == 5);
447 
448  limits[0][0] = m_config.lowFreq;
449  limits[1][0] = m_config.highFreq;
450  limits[0][1] = m_config.lowAmp;
451  limits[1][1] = m_config.highAmp;
452  limits[0][2] = m_config.freqFeedbackMin;
453  limits[1][2] = m_config.freqFeedbackMax;
454  limits[0][3] = m_config.ampFeedbackMin;
455  limits[1][3] = m_config.ampFeedbackMax;
456  limits[0][4] = m_config.phaseFeedbackMin;
457  limits[1][4] = m_config.phaseFeedbackMax;
458 
459  Json::Value::iterator nodeIt = actions.begin();
460 
461  // This one is square
462  for( std::size_t i = 0; i < numControllers; i++)
463  {
464  Json::Value nodeParam = *nodeIt;
465  for( std::size_t j = 0; j < numActions; j++)
466  {
467  nodeActions[i][j] = ( (nodeParam.get(j, 0.0)).asDouble() *
468  (limits[1][j] - limits[0][j])) + limits[0][j];
469  }
470  nodeIt++;
471  }
472 
473  return nodeActions;
474 }
475 
476 
478  (Json::Value edgeParam)
479 {
480  assert(edgeParam[0].size() == 2);
481 
482  double lowerLimit = m_config.lowPhase;
483  double upperLimit = m_config.highPhase;
484  double range = upperLimit - lowerLimit;
485 
486  array_3D actionList(boost::extents[m_config.theirMuscles]
487  [m_config.ourMuscles]
488  [m_config.params]);
489 
490  /* Horrid while loop to populate upper diagonal of matrix, since
491  * its symmetric and we want to minimze parameters used in learing
492  * note that i==1, j==k will refer to the same muscle
493  * @todo use boost to set up array so storage is only allocated for
494  * elements that are used
495  */
496  int j = 0;
497  int k = 0;
498 
499  // Quirk of the old learning code. Future examples can move forward
500  Json::Value::iterator edgeIt = edgeParam.end();
501 
502  int count = 0;
503 
504  while(j < m_config.theirMuscles)
505  {
506  while(k < m_config.ourMuscles)
507  {
508  if (edgeIt == edgeParam.begin())
509  {
510  std::cout << "ran out before table populated!"
511  << std::endl;
513  break;
514  }
515  else
516  {
517  if (j == k)
518  {
519  // std::cout << "Skipped identical muscle" << std::endl;
520  //Skip since its the same muscle
521  }
522  else
523  {
524  edgeIt--;
525  Json::Value edgeParam = *edgeIt;
526  assert(edgeParam.size() == 2);
527  // Weight from 0 to 1
528  actionList[j][k][0] = edgeParam[0].asDouble();
529  //std::cout << actionList[j][k][0] << " ";
530  // Phase offset from -pi to pi
531  actionList[j][k][1] = edgeParam[1].asDouble() *
532  (range) + lowerLimit;
533  //std::cout << actionList[j][k][1] << std::endl;
534  count++;
535  }
536  }
537  k++;
538  }
539  j++;
540  k = j;
541 
542  }
543 
544 
545  std::cout<< "Params used: " << count << std::endl;
546 
547  assert(edgeParam.begin() == edgeIt);
548 
549  return actionList;
550 }
551 std::vector<double> JSONMGFeedbackControl::getFeedback(BaseQuadModelLearning& subject)
552 {
553  // Placeholder
554  std::vector<double> feedback;
555 
556  const std::vector<tgSpringCableActuator*>& spineCables = subject.find<tgSpringCableActuator> ("all ");
557 
558  double *inputs = new double[m_config.numStates];
559 
560  std::size_t n = spineCables.size();
561  for(std::size_t i = 0; i != n; i++)
562  {
563  std::vector< std::vector<double> > actions;
564 
565  const tgSpringCableActuator& cable = *(spineCables[i]);
566  std::vector<double > state = getCableState(cable);
567 
568  // Rescale to 0 to 1 (consider doing this inside getState
569  for (std::size_t i = 0; i < state.size(); i++)
570  {
571  inputs[i]=state[i] / 2.0 + 0.5;
572  }
573 
574  double *output = nn->feedForwardPattern(inputs);
575  vector<double> tmpAct;
576  for(int j=0;j<m_config.numActions;j++)
577  {
578  tmpAct.push_back(output[j]);
579  }
580  actions.push_back(tmpAct);
581 
582  std::vector<double> cableFeedback = transformFeedbackActions(actions);
583 
584  feedback.insert(feedback.end(), cableFeedback.begin(), cableFeedback.end());
585  }
586 
587 
588  return feedback;
589 }
590 
591 std::vector<double> JSONMGFeedbackControl::getCableState(const tgSpringCableActuator& cable)
592 {
593  // For each string, scale value from -1 to 1 based on initial length or max tension of motor
594 
595  std::vector<double> state;
596 
597  // Scale length by starting length
598  const double startLength = cable.getStartLength();
599  state.push_back((cable.getCurrentLength() - startLength) / startLength);
600 
601  const double maxTension = cable.getConfig().maxTens;
602  state.push_back((cable.getTension() - maxTension / 2.0) / maxTension);
603 
604  return state;
605 }
606 
607 std::vector<double> JSONMGFeedbackControl::transformFeedbackActions(std::vector< std::vector<double> >& actions)
608 {
609  // Placeholder
610  std::vector<double> feedback;
611 
612  // Leave in place for generalization later
613  const std::size_t numControllers = 1;
614  const std::size_t numActions = m_config.numActions;
615 
616  assert( actions.size() == numControllers);
617  assert( actions[0].size() == numActions);
618 
619  // Scale values back to -1 to +1
620  for( std::size_t i = 0; i < numControllers; i++)
621  {
622  for( std::size_t j = 0; j < numActions; j++)
623  {
624  feedback.push_back(actions[i][j] * 2.0 - 1.0);
625  }
626  }
627 
628  return feedback;
629 }
630 
Contains the definition of class ImpedanceControl. $Id$.
Definition of the tgCPGStringControl observer class.
void update(std::vector< double > &descCom, double dt)
virtual void onSetup(BaseQuadModelLearning &subject)
Implementing the Flemons quadruped model (roughly), but as a subclass of Brian's BaseSpineModelLearni...
virtual const double getTension() const
virtual const double getStartLength() const
void setConnectivity(const std::vector< tgCPGMGActuatorControl * > &allStrings, array_3D edgeParams)
virtual void onStep(BaseQuadModelLearning &subject, double dt)
A class to read a learning configuration from a .ini file.
virtual array_3D scaleEdgeActions(Json::Value edgeParam)
Contains the definition of abstract base class tgSpringCableActuator. Assumes that the string is line...
A series of functions to assist with file input/output.
Contains the definition of class AnnealEvolution. Adapting NeuroEvolution to do Simulated Annealing...
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.
virtual void onSetup(tgModel &model)
virtual void onTeardown(BaseQuadModelLearning &subject)
JSONMGFeedbackControl(JSONMGFeedbackControl::Config config, std::string args, std::string resourcePath="")
virtual const double getCurrentLength() const
void assignNodeNumberFB(CPGEquationsFB &CPGSys, array_2D nodeParams)
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)