NTRT Simulator  Version: Master
 All Classes Namespaces Files Functions Variables Typedefs Friends Pages
JSONMixedLearningControl.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 
29 
30 // Should include tgString, but compiler complains since its been
31 // included from BaseSpineModelLearning. Perhaps we should move things
32 // to a cpp over there
34 #include "core/tgBasicActuator.h"
37 #include "examples/learningSpines/tgCPGCableControl.h"
38 
40 #include "helpers/FileHelpers.h"
41 
44 
45 #include "util/CPGEquationsFB.h"
46 #include "examples/learningSpines/tgCPGCableControl.h"
47 
48 #include "neuralNet/Neural Network v2/neuralNetwork.h"
49 
50 #include <json/json.h>
51 
52 #include <string>
53 #include <iostream>
54 #include <vector>
55 
56 //#define LOGGING
57 #define USE_KINEMATIC
58 
59 using namespace std;
60 
62  int tm,
63  int om,
64  int param,
65  int segnum,
66  double ct,
67  double la,
68  double ha,
69  double lp,
70  double hp,
71  double kt,
72  double kp,
73  double kv,
74  bool def,
75  double cl,
76  double lf,
77  double hf,
78  double ffMin,
79  double ffMax,
80  double afMin,
81  double afMax,
82  double pfMin,
83  double pfMax,
84  double maxH,
85  double minH) :
86 JSONCPGControl::Config::Config(ss, tm, om, param, segnum, ct, la, ha,
87  lp, hp, kt, kp, kv, def, cl, lf, hf),
88 freqFeedbackMin(ffMin),
89 freqFeedbackMax(ffMax),
90 ampFeedbackMin(afMin),
91 ampFeedbackMax(afMax),
92 phaseFeedbackMin(pfMin),
93 phaseFeedbackMax(pfMax),
94 maxHeight(maxH),
95 minHeight(minH)
96 {
97 
98 }
105  std::string args,
106  std::string resourcePath) :
107 JSONCPGControl(config, args, resourcePath),
108 m_config(config)
109 {
110  // Path and filename handled by base class
111 
112 }
113 
114 JSONMixedLearningControl::~JSONMixedLearningControl()
115 {
116  delete nn;
117 }
118 
120 {
121  m_pCPGSys = new CPGEquationsFB(200);
122 
123  Json::Value root; // will contains the root value after parsing.
124  Json::Reader reader;
125 
126  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
127  if ( !parsingSuccessful )
128  {
129  // report to the user the failure and their locations in the document.
130  std::cout << "Failed to parse configuration\n"
131  << reader.getFormattedErrorMessages();
132  throw std::invalid_argument("Bad filename for JSON");
133  }
134  // Get the value of the member of root named 'encoding', return 'UTF-8' if there is no
135  // such member.
136  Json::Value nodeVals = root.get("nodeVals", "UTF-8");
137  Json::Value startingEdgeVals = root.get("startingEdgeVals", "UTF-8");
138  Json::Value middleEdgeVals = root.get("middleEdgeVals", "UTF-8");
139  Json::Value endingEdgeVals = root.get("endingEdgeVals", "UTF-8");
140 
141  std::cout << nodeVals << std::endl;
142 
143  nodeVals = nodeVals.get("params", "UTF-8");
144  startingEdgeVals = startingEdgeVals.get("params", "UTF-8");
145  middleEdgeVals = middleEdgeVals.get("params", "UTF-8");
146  endingEdgeVals = endingEdgeVals.get("params", "UTF-8");
147 
148  array_4D startingEdgeParams = scaleEdgeActions(startingEdgeVals);
149  array_4D middleEdgeParams = scaleEdgeActions(middleEdgeVals);
150  array_4D endingEdgeParams = scaleEdgeActions(endingEdgeVals);
151  array_2D nodeParams = scaleNodeActions(nodeVals);
152 
153  setupCPGs(subject, nodeParams, startingEdgeParams, middleEdgeParams, endingEdgeParams);
154 
155  Json::Value feedbackParams = root.get("feedbackVals", "UTF-8");
156  feedbackParams = feedbackParams.get("params", "UTF-8");
157 
158  // Setup neural network
159  m_config.numStates = feedbackParams.get("numStates", "UTF-8").asInt();
160  m_config.numActions = feedbackParams.get("numActions", "UTF-8").asInt();
161  m_config.numHidden = feedbackParams.get("numHidden", "UTF-8").asInt();
162 
163  std::string nnFile = controlFilePath + feedbackParams.get("neuralFilename", "UTF-8").asString();
164 
165  nn = new neuralNetwork(m_config.numStates, m_config.numHidden, m_config.numActions);
166 
167  nn->loadWeights(nnFile.c_str());
168 
169  initConditions = subject.getSegmentCOM(m_config.segmentNumber);
170  for (int i = 0; i < initConditions.size(); i++)
171  {
172  std::cout << initConditions[i] << " ";
173  }
174  std::cout << std::endl;
175 #ifdef LOGGING // Conditional compile for data logging
176  m_dataObserver.onSetup(subject);
177 #endif
178 
179 #if (0) // Conditional Compile for debug info
180  std::cout << *m_pCPGSys << std::endl;
181 #endif
182  m_updateTime = 0.0;
183  bogus = false;
184 }
185 
187 {
188  m_updateTime += dt;
189  if (m_updateTime >= m_config.controlTime)
190  {
191 #if (1)
192  std::vector<double> desComs = getFeedback(subject);
193 
194 #else
195  std::size_t numControllers = subject.getNumberofMuslces() * 3;
196 
197  double descendingCommand = 0.0;
198  std::vector<double> desComs (numControllers, descendingCommand);
199 #endif
200  try
201  {
202  m_pCPGSys->update(desComs, m_updateTime);
203  }
204  catch (std::runtime_error& e)
205  {
206  // Stops the trial immediately, lets teardown know it broke
207  bogus = true;
208  throw (e);
209  }
210 
211 #ifdef LOGGING // Conditional compile for data logging
212  m_dataObserver.onStep(subject, m_updateTime);
213 #endif
214  notifyStep(m_updateTime);
215  m_updateTime = 0;
216  }
217 
218  double currentHeight = subject.getSegmentCOM(m_config.segmentNumber)[1];
219 
221  if (currentHeight > m_config.maxHeight || currentHeight < m_config.minHeight)
222  {
224  bogus = true;
225  throw std::runtime_error("Height out of range");
226  }
227 }
228 
230 {
231  scores.clear();
232  // @todo - check to make sure we ran for the right amount of time
233 
234  std::vector<double> finalConditions = subject.getSegmentCOM(m_config.segmentNumber);
235 
236  const double newX = finalConditions[0];
237  const double newZ = finalConditions[2];
238  const double oldX = initConditions[0];
239  const double oldZ = initConditions[2];
240 
241  const double distanceMoved = sqrt((newX-oldX) * (newX-oldX) +
242  (newZ-oldZ) * (newZ-oldZ));
243 
244  if (bogus)
245  {
246  scores.push_back(-1.0);
247  }
248  else
249  {
250  scores.push_back(distanceMoved);
251  }
252 
255  double totalEnergySpent=0;
256 
257  std::vector<tgSpringCableActuator* > tmpStrings = subject.getAllMuscles();
258 
259  for(std::size_t i=0; i<tmpStrings.size(); i++)
260  {
261  tgSpringCableActuator::SpringCableActuatorHistory stringHist = tmpStrings[i]->getHistory();
262 
263  for(std::size_t j=1; j<stringHist.tensionHistory.size(); j++)
264  {
265  const double previousTension = stringHist.tensionHistory[j-1];
266  const double previousLength = stringHist.restLengths[j-1];
267  const double currentLength = stringHist.restLengths[j];
268  //TODO: examine this assumption - free spinning motor may require more power
269  double motorSpeed = (currentLength-previousLength);
270  if(motorSpeed > 0) // Vestigial code
271  motorSpeed = 0;
272  const double workDone = previousTension * motorSpeed;
273  totalEnergySpent += workDone;
274  }
275  }
276 
277  scores.push_back(totalEnergySpent);
278 
279  std::cout << "Dist travelled " << scores[0] << std::endl;
280 
281  Json::Value root; // will contains the root value after parsing.
282  Json::Reader reader;
283 
284  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
285  if ( !parsingSuccessful )
286  {
287  // report to the user the failure and their locations in the document.
288  std::cout << "Failed to parse configuration\n"
289  << reader.getFormattedErrorMessages();
290  throw std::invalid_argument("Bad filename for JSON");
291  }
292 
293  Json::Value prevScores = root.get("scores", Json::nullValue);
294 
295  Json::Value subScores;
296  subScores["distance"] = scores[0];
297  subScores["energy"] = totalEnergySpent;
298 
299  prevScores.append(subScores);
300  root["scores"] = prevScores;
301 
302  ofstream payloadLog;
303  payloadLog.open(controlFilename.c_str(),ofstream::out);
304 
305  payloadLog << root << std::endl;
306 
307  delete m_pCPGSys;
308  m_pCPGSys = NULL;
309 
310 
311  for(size_t i = 0; i < m_startingControllers.size(); i++)
312  {
313  delete m_startingControllers[i];
314  }
315  m_startingControllers.clear();
316 
317  for(size_t i = 0; i < m_middleControllers.size(); i++)
318  {
319  delete m_middleControllers[i];
320  }
321  m_middleControllers.clear();
322 
323  for(size_t i = 0; i < m_endingControllers.size(); i++)
324  {
325  delete m_endingControllers[i];
326  }
327  m_endingControllers.clear();
328 }
329 
330 void JSONMixedLearningControl::setupCPGs(BaseSpineModelLearning& subject, array_2D nodeActions, array_4D startingEdgeActions, array_4D middleEdgeActions, array_4D endingEdgeActions)
331 {
332 
333  std::vector <tgSpringCableActuator*> startMuscles = subject.find<tgSpringCableActuator> ("starting");
334  std::vector <tgSpringCableActuator*> middleMuscles = subject.find<tgSpringCableActuator> ("middle");
335  std::vector <tgSpringCableActuator*> endMuscles = subject.find<tgSpringCableActuator> ("ending");
336 
337  CPGEquationsFB& m_CPGFBSys = *(tgCast::cast<CPGEquations, CPGEquationsFB>(m_pCPGSys));
338 
339  for (std::size_t i = 0; i < startMuscles.size(); i++)
340  {
341 
342  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
343  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
344 
345  startMuscles[i]->attach(pStringControl);
346 
347  // First assign node numbers
348  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
349 
350  m_startingControllers.push_back(pStringControl);
351  }
352 
353  // Then determine connectivity and setup string
354  for (std::size_t i = 0; i < m_startingControllers.size(); i++)
355  {
356  tgCPGActuatorControl * const pStringInfo = m_startingControllers[i];
357  assert(pStringInfo != NULL);
358  pStringInfo->setConnectivity(m_startingControllers, startingEdgeActions);
359 
360  //String will own this pointer
361  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
362  m_config.kPosition,
363  m_config.kVelocity);
364  if (m_config.useDefault)
365  {
366  pStringInfo->setupControl(*p_ipc);
367  }
368  else
369  {
370  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
371  }
372  }
373 
374  for (std::size_t i = 0; i < middleMuscles.size(); i++)
375  {
376 
377  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
378  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
379 
380  middleMuscles[i]->attach(pStringControl);
381 
382  // First assign node numbers
383  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
384 
385  m_middleControllers.push_back(pStringControl);
386  }
387 
388  // Then determine connectivity and setup string
389  for (std::size_t i = 0; i < m_middleControllers.size(); i++)
390  {
391  tgCPGActuatorControl * const pStringInfo = m_middleControllers[i];
392  assert(pStringInfo != NULL);
393  pStringInfo->setConnectivity(m_middleControllers, middleEdgeActions);
394 
395  //String will own this pointer
396  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
397  m_config.kPosition,
398  m_config.kVelocity);
399  if (m_config.useDefault)
400  {
401  pStringInfo->setupControl(*p_ipc);
402  }
403  else
404  {
405  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
406  }
407  }
408 
409  for (std::size_t i = 0; i < endMuscles.size(); i++)
410  {
411 
412  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
413  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
414 
415  endMuscles[i]->attach(pStringControl);
416 
417  // First assign node numbers
418  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
419 
420  m_endingControllers.push_back(pStringControl);
421  }
422 
423  // Then determine connectivity and setup string
424  for (std::size_t i = 0; i < m_endingControllers.size(); i++)
425  {
426  tgCPGActuatorControl * const pStringInfo = m_endingControllers[i];
427  assert(pStringInfo != NULL);
428  pStringInfo->setConnectivity(m_endingControllers, endingEdgeActions);
429 
430  //String will own this pointer
431  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
432  m_config.kPosition,
433  m_config.kVelocity);
434  if (m_config.useDefault)
435  {
436  pStringInfo->setupControl(*p_ipc);
437  }
438  else
439  {
440  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
441  }
442  }
443 }
444 
445 array_2D JSONMixedLearningControl::scaleNodeActions (Json::Value actions)
446 {
447  std::size_t numControllers = actions.size();
448  std::size_t numActions = actions[0].size();
449 
450  array_2D nodeActions(boost::extents[numControllers][numActions]);
451 
452  array_2D limits(boost::extents[2][numActions]);
453 
454  // Check if we need to update limits
455  assert(numActions == 5);
456 
457  limits[0][0] = m_config.lowFreq;
458  limits[1][0] = m_config.highFreq;
459  limits[0][1] = m_config.lowAmp;
460  limits[1][1] = m_config.highAmp;
461  limits[0][2] = m_config.freqFeedbackMin;
462  limits[1][2] = m_config.freqFeedbackMax;
463  limits[0][3] = m_config.ampFeedbackMin;
464  limits[1][3] = m_config.ampFeedbackMax;
465  limits[0][4] = m_config.phaseFeedbackMin;
466  limits[1][4] = m_config.phaseFeedbackMax;
467 
468  Json::Value::iterator nodeIt = actions.begin();
469 
470  // This one is square
471  for( std::size_t i = 0; i < numControllers; i++)
472  {
473  Json::Value nodeParam = *nodeIt;
474  for( std::size_t j = 0; j < numActions; j++)
475  {
476  nodeActions[i][j] = ( (nodeParam.get(j, 0.0)).asDouble() *
477  (limits[1][j] - limits[0][j])) + limits[0][j];
478  }
479  nodeIt++;
480  }
481 
482  return nodeActions;
483 }
484 
485 std::vector<double> JSONMixedLearningControl::getFeedback(BaseSpineModelLearning& subject)
486 {
487  // Placeholder
488  std::vector<double> feedback;
489 
490  const std::vector<tgSpringCableActuator*>& allCables = subject.getAllMuscles();
491 
492  double *inputs = new double[m_config.numStates];
493 
494  std::size_t n = allCables.size();
495  for(std::size_t i = 0; i != n; i++)
496  {
497  std::vector< std::vector<double> > actions;
498 
499  const tgSpringCableActuator& cable = *(allCables[i]);
500  std::vector<double > state = getCableState(cable);
501 
502  // Rescale to 0 to 1 (consider doing this inside getState
503  for (std::size_t i = 0; i < state.size(); i++)
504  {
505  inputs[i]=state[i] / 2.0 + 0.5;
506  }
507 
508  double *output = nn->feedForwardPattern(inputs);
509  vector<double> tmpAct;
510  for(int j=0;j<m_config.numActions;j++)
511  {
512  tmpAct.push_back(output[j]);
513  }
514  actions.push_back(tmpAct);
515 
516  std::vector<double> cableFeedback = transformFeedbackActions(actions);
517 
518  feedback.insert(feedback.end(), cableFeedback.begin(), cableFeedback.end());
519  }
520 
521 
522  return feedback;
523 }
524 
525 std::vector<double> JSONMixedLearningControl::getCableState(const tgSpringCableActuator& cable)
526 {
527  // For each string, scale value from -1 to 1 based on initial length or max tension of motor
528 
529  std::vector<double> state;
530 
531  // Scale length by starting length
532  const double startLength = cable.getStartLength();
533  state.push_back((cable.getCurrentLength() - startLength) / startLength);
534 
535  const double maxTension = cable.getConfig().maxTens;
536  state.push_back((cable.getTension() - maxTension / 2.0) / maxTension);
537 
538  return state;
539 }
540 
541 std::vector<double> JSONMixedLearningControl::transformFeedbackActions(std::vector< std::vector<double> >& actions)
542 {
543  // Placeholder
544  std::vector<double> feedback;
545 
546  // Leave in place for generalization later
547  const std::size_t numControllers = 1;
548  const std::size_t numActions = m_config.numActions;
549 
550  assert( actions.size() == numControllers);
551  assert( actions[0].size() == numActions);
552 
553  // Scale values back to -1 to +1
554  for( std::size_t i = 0; i < numControllers; i++)
555  {
556  for( std::size_t j = 0; j < numActions; j++)
557  {
558  feedback.push_back(actions[i][j] * 2.0 - 1.0);
559  }
560  }
561 
562  return feedback;
563 }
Contains the definition of class ImpedanceControl. $Id$.
void update(std::vector< double > &descCom, double dt)
virtual const double getTension() const
virtual const double getStartLength() const
virtual array_4D scaleEdgeActions(Json::Value edgeParam)
void setConnectivity(const std::vector< tgCPGActuatorControl * > &allStrings, array_4D edgeParams)
Definition of the tgCPGStringControl observer class.
A template base class for a tensegrity spine.
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 onSetup(BaseSpineModelLearning &subject)
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.
JSONMixedLearningControl(JSONMixedLearningControl::Config config, std::string args, std::string resourcePath="")
virtual void onTeardown(BaseSpineModelLearning &subject)
const Config & getConfig() const
std::vector< T * > find(const tgTagSearch &tagSearch)
Definition: tgModel.h:128
virtual void onStep(tgModel &model, double dt)
A controller for the template class BaseSpineModelLearning.
Definition of class CPGEquationsFB.
virtual void onSetup(tgModel &model)
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=25.0, double minH=1.0)
virtual const double getCurrentLength() const
virtual void onStep(BaseSpineModelLearning &subject, double dt)
void notifyStep(double dt)
void assignNodeNumberFB(CPGEquationsFB &CPGSys, array_2D nodeParams)