NTRT Simulator  Version: Master
 All Classes Namespaces Files Functions Variables Typedefs Friends Pages
JSONStatsFeedbackControl.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 JSONQuadCPGControl::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 JSONQuadCPGControl(config, args, resourcePath),
109 m_config(config)
110 {
111  // Path and filename handled by base class
112 
113 }
114 
115 JSONStatsFeedbackControl::~JSONStatsFeedbackControl()
116 {
117  delete nn;
118 }
119 
121 {
122  m_pCPGSys = new CPGEquationsFB(100);
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_4D 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(1){
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> ("spine ");
265 
266  for(std::size_t i=0; i<tmpStrings.size(); i++)
267  {
268  std::cout << "Muscle " << i << ": " << tmpStrings[i]->getTension() << std::endl;
269  }
270 
271  count = 0;
272  }
273  else {
274  count++;
275  }
276  }
277 }
278 
280 {
281  scores.clear();
282  metrics.clear();
283  // @todo - check to make sure we ran for the right amount of time
284 
285  std::vector<double> finalConditions = subject.getSegmentCOM(m_config.segmentNumber);
286 
287  const double newX = finalConditions[0];
288  const double newZ = finalConditions[2];
289  const double oldX = initConditions[0];
290  const double oldZ = initConditions[2];
291 
292  const double distanceMoved = sqrt((newX-oldX) * (newX-oldX) +
293  (newZ-oldZ) * (newZ-oldZ));
294 
295  if (bogus)
296  {
297  scores.push_back(-1.0);
298  }
299  else
300  {
301  scores.push_back(distanceMoved);
302  }
303 
306  double totalEnergySpent=0;
307 
308  std::vector<tgSpringCableActuator* > tmpStrings = subject.find<tgSpringCableActuator> ("spine ");
309 
310  for(std::size_t i=0; i<tmpStrings.size(); i++)
311  {
312  tgSpringCableActuator::SpringCableActuatorHistory stringHist = tmpStrings[i]->getHistory();
313 
314  for(std::size_t j=1; j<stringHist.tensionHistory.size(); j++)
315  {
316  const double previousTension = stringHist.tensionHistory[j-1];
317  const double previousLength = stringHist.restLengths[j-1];
318  const double currentLength = stringHist.restLengths[j];
319  //TODO: examine this assumption - free spinning motor may require more power
320  double motorSpeed = (currentLength-previousLength);
321  if(motorSpeed > 0) // Vestigial code
322  motorSpeed = 0;
323  const double workDone = previousTension * motorSpeed;
324  totalEnergySpent += workDone;
325  }
326  }
327 
328  scores.push_back(totalEnergySpent);
329 
330  //Getting the center of mass of the entire structure.
331  std::vector<double> structureCOM = subject.getCOM(m_config.segmentNumber);
332 
333  for(std::size_t i=0; i<3; i++)
334  {
335  metrics.push_back(structureCOM[i]);
336  }
337 
338  std::cout << "Dist travelled " << scores[0] << std::endl;
339 
340  Json::Value root; // will contain the root value after parsing.
341  Json::Reader reader;
342 
343  bool parsingSuccessful = reader.parse( FileHelpers::getFileString(controlFilename.c_str()), root );
344  if ( !parsingSuccessful )
345  {
346  // report to the user the failure and their locations in the document.
347  std::cout << "Failed to parse configuration\n"
348  << reader.getFormattedErrorMessages();
349  throw std::invalid_argument("Bad filename for JSON");
350  }
351 
352  Json::Value prevScores = root.get("scores", Json::nullValue);
353  Json::Value prevMetrics = root.get("metrics", Json::nullValue);
354 
355  Json::Value subScores;
356  subScores["distance"] = scores[0];
357  subScores["energy"] = scores[1];
358 
359  Json::Value subMetrics;
360  subMetrics["final COM x"] = metrics[0];
361  subMetrics["final COM y"] = metrics[1];
362  subMetrics["final COM z"] = metrics[2];
363 
364  prevScores.append(subScores);
365  prevMetrics.append(subMetrics);
366 
367  root["scores"] = prevScores;
368  root["metrics"] = prevMetrics;
369 
370  ofstream payloadLog;
371  payloadLog.open(controlFilename.c_str(),ofstream::out);
372 
373  payloadLog << root << std::endl;
374 
375  delete m_pCPGSys;
376  m_pCPGSys = NULL;
377 
378  for(size_t i = 0; i < m_spineControllers.size(); i++)
379  {
380  delete m_spineControllers[i];
381  }
382  m_spineControllers.clear();
383 }
384 
385 void JSONStatsFeedbackControl::setupCPGs(BaseQuadModelLearning& subject, array_2D nodeActions, array_4D edgeActions)
386 {
387 
388  std::vector <tgSpringCableActuator*> spineMuscles = subject.find<tgSpringCableActuator> ("spine ");
389 
390  CPGEquationsFB& m_CPGFBSys = *(tgCast::cast<CPGEquations, CPGEquationsFB>(m_pCPGSys));
391 
392  for (std::size_t i = 0; i < spineMuscles.size(); i++)
393  {
394 
395  tgPIDController::Config config(20000.0, 0.0, 5.0, true); // Non backdrivable
396  tgCPGCableControl* pStringControl = new tgCPGCableControl(config);
397 
398  spineMuscles[i]->attach(pStringControl);
399 
400  // First assign node numbers
401  pStringControl->assignNodeNumberFB(m_CPGFBSys, nodeActions);
402 
403  m_spineControllers.push_back(pStringControl);
404  }
405 
406  // Then determine connectivity and setup string
407  for (std::size_t i = 0; i < m_spineControllers.size(); i++)
408  {
409  tgCPGActuatorControl * const pStringInfo = m_spineControllers[i];
410  assert(pStringInfo != NULL);
411  pStringInfo->setConnectivity(m_spineControllers, edgeActions);
412 
413  //String will own this pointer
414  tgImpedanceController* p_ipc = new tgImpedanceController( m_config.tension,
415  m_config.kPosition,
416  m_config.kVelocity);
417  if (m_config.useDefault)
418  {
419  pStringInfo->setupControl(*p_ipc);
420  }
421  else
422  {
423  pStringInfo->setupControl(*p_ipc, m_config.controlLength);
424  }
425  }
426 
427 }
428 
429 array_2D JSONStatsFeedbackControl::scaleNodeActions (Json::Value actions)
430 {
431  std::size_t numControllers = actions.size();
432  std::size_t numActions = actions[0].size();
433 
434  array_2D nodeActions(boost::extents[numControllers][numActions]);
435 
436  array_2D limits(boost::extents[2][numActions]);
437 
438  // Check if we need to update limits
439  assert(numActions == 5);
440 
441  limits[0][0] = m_config.lowFreq;
442  limits[1][0] = m_config.highFreq;
443  limits[0][1] = m_config.lowAmp;
444  limits[1][1] = m_config.highAmp;
445  limits[0][2] = m_config.freqFeedbackMin;
446  limits[1][2] = m_config.freqFeedbackMax;
447  limits[0][3] = m_config.ampFeedbackMin;
448  limits[1][3] = m_config.ampFeedbackMax;
449  limits[0][4] = m_config.phaseFeedbackMin;
450  limits[1][4] = m_config.phaseFeedbackMax;
451 
452  Json::Value::iterator nodeIt = actions.begin();
453 
454  // This one is square
455  for( std::size_t i = 0; i < numControllers; i++)
456  {
457  Json::Value nodeParam = *nodeIt;
458  for( std::size_t j = 0; j < numActions; j++)
459  {
460  nodeActions[i][j] = ( (nodeParam.get(j, 0.0)).asDouble() *
461  (limits[1][j] - limits[0][j])) + limits[0][j];
462  }
463  nodeIt++;
464  }
465 
466  return nodeActions;
467 }
468 
469 std::vector<double> JSONStatsFeedbackControl::getFeedback(BaseQuadModelLearning& subject)
470 {
471  // Placeholder
472  std::vector<double> feedback;
473 
474  const std::vector<tgSpringCableActuator*>& spineCables = subject.find<tgSpringCableActuator> ("spine ");
475 
476  double *inputs = new double[m_config.numStates];
477 
478  std::size_t n = spineCables.size();
479  for(std::size_t i = 0; i != n; i++)
480  {
481  std::vector< std::vector<double> > actions;
482 
483  const tgSpringCableActuator& cable = *(spineCables[i]);
484  std::vector<double > state = getCableState(cable);
485 
486  // Rescale to 0 to 1 (consider doing this inside getState
487  for (std::size_t i = 0; i < state.size(); i++)
488  {
489  inputs[i]=state[i] / 2.0 + 0.5;
490  }
491 
492  double *output = nn->feedForwardPattern(inputs);
493  vector<double> tmpAct;
494  for(int j=0;j<m_config.numActions;j++)
495  {
496  tmpAct.push_back(output[j]);
497  }
498  actions.push_back(tmpAct);
499 
500  std::vector<double> cableFeedback = transformFeedbackActions(actions);
501 
502  feedback.insert(feedback.end(), cableFeedback.begin(), cableFeedback.end());
503  }
504 
505 
506  return feedback;
507 }
508 
509 std::vector<double> JSONStatsFeedbackControl::getCableState(const tgSpringCableActuator& cable)
510 {
511  // For each string, scale value from -1 to 1 based on initial length or max tension of motor
512 
513  std::vector<double> state;
514 
515  // Scale length by starting length
516  const double startLength = cable.getStartLength();
517  state.push_back((cable.getCurrentLength() - startLength) / startLength);
518 
519  const double maxTension = cable.getConfig().maxTens;
520  state.push_back((cable.getTension() - maxTension / 2.0) / maxTension);
521 
522  return state;
523 }
524 
525 std::vector<double> JSONStatsFeedbackControl::transformFeedbackActions(std::vector< std::vector<double> >& actions)
526 {
527  // Placeholder
528  std::vector<double> feedback;
529 
530  // Leave in place for generalization later
531  const std::size_t numControllers = 1;
532  const std::size_t numActions = m_config.numActions;
533 
534  assert( actions.size() == numControllers);
535  assert( actions[0].size() == numActions);
536 
537  // Scale values back to -1 to +1
538  for( std::size_t i = 0; i < numControllers; i++)
539  {
540  for( std::size_t j = 0; j < numActions; j++)
541  {
542  feedback.push_back(actions[i][j] * 2.0 - 1.0);
543  }
544  }
545 
546  return feedback;
547 }
548 
Contains the definition of class ImpedanceControl. $Id$.
JSONStatsFeedbackControl(JSONStatsFeedbackControl::Config config, std::string args, std::string resourcePath="")
void update(std::vector< double > &descCom, double dt)
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)
virtual const double getTension() const
virtual const double getStartLength() const
virtual void onStep(BaseQuadModelLearning &subject, double dt)
void setConnectivity(const std::vector< tgCPGActuatorControl * > &allStrings, array_4D edgeParams)
virtual void onSetup(BaseQuadModelLearning &subject)
Definition of the tgCPGStringControl observer class.
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.
Contains the definition of class AnnealEvolution. Adapting NeuroEvolution to do Simulated Annealing...
Contains the definition of class tgBasicActuator.
A controller for the template class BaseSpineModelLearning more metrics, such as center of mass of e...
const Config & getConfig() const
std::vector< T * > find(const tgTagSearch &tagSearch)
Definition: tgModel.h:128
virtual void onStep(tgModel &model, double dt)
virtual array_4D scaleEdgeActions(Json::Value edgeParam)
Definition of class CPGEquationsFB.
virtual void onSetup(tgModel &model)
virtual const double getCurrentLength() const
void assignNodeNumberFB(CPGEquationsFB &CPGSys, array_2D nodeParams)