Skip to content

Commit

Permalink
Attempting to revive the cartpole iLQR demo
Browse files Browse the repository at this point in the history
  • Loading branch information
keenon committed Dec 2, 2024
1 parent 73619fb commit 0d34899
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 3 deletions.
2 changes: 1 addition & 1 deletion data/skel/cartpole.skel
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<physics>
<time_step>0.01</time_step>
<gravity>0 -9.81 0</gravity>
<collision_detector>bullet</collision_detector>
<collision_detector>dart</collision_detector>
</physics>

<skeleton name="pendulum">
Expand Down
8 changes: 6 additions & 2 deletions unittests/comprehensive/test_iLQRCartpole.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,6 +293,10 @@ TEST(REALTIME, CARTPOLE_MPC)
finalStateWeight(1) = 50.0;
finalStateWeight(2) = 50.0;
finalStateWeight(3) = 50.0;
runningStateWeight(0) = 0.1;
runningStateWeight(1) = 0.5;
runningStateWeight(2) = 0.01;
runningStateWeight(3) = 0.01;
runningActionWeight(0) = 0.01;

std::shared_ptr<TargetReachingCost> costFn
Expand All @@ -309,8 +313,8 @@ TEST(REALTIME, CARTPOLE_MPC)

mpcLocal.setCostFn(costFn);
mpcLocal.setSilent(true);
mpcLocal.setMaxIterations(5);
mpcLocal.setEnableLineSearch(false);
mpcLocal.setMaxIterations(20);
mpcLocal.setEnableLineSearch(true);
mpcLocal.setEnableOptimizationGuards(true);
mpcLocal.setPredictUsingFeedback(false);
mpcLocal.setPatience(3);
Expand Down

0 comments on commit 0d34899

Please sign in to comment.