diff --git a/unitree_guide/src/FSM/State_SwingTest.cpp b/unitree_guide/src/FSM/State_SwingTest.cpp index 8695445..e546780 100755 --- a/unitree_guide/src/FSM/State_SwingTest.cpp +++ b/unitree_guide/src/FSM/State_SwingTest.cpp @@ -50,7 +50,7 @@ void State_SwingTest::run(){ } if(_userValue.lx > 0){ - _posGoal(1) = invNormalize(_userValue.lx, _initPos(1, 0), _initPos(1)+_yMax, 0, 1); + _posGoal(1) = invNormalize(_userValue.lx, _initPos(1), _initPos(1)+_yMax, 0, 1); }else{ _posGoal(1) = invNormalize(_userValue.lx, _initPos(1)+_yMin, _initPos(1), -1, 0); } @@ -99,4 +99,4 @@ void State_SwingTest::_torqueCtrl(){ torque.segment(0, 3) = jaco0.transpose() * force0; _lowCmd->setTau(torque); -} \ No newline at end of file +}