File tree Expand file tree Collapse file tree
Expand file tree Collapse file tree Original file line number Diff line number Diff line change 1+ package org .mujoco ;
2+
3+ import org .mujoco .MuJoCoLib .mjData_ ;
4+ import org .mujoco .MuJoCoLib .mjModel_ ;
5+
6+ public interface IMujocoController {
7+ public void controlStep (mjData_ data ,mjModel_ model );
8+ }
Original file line number Diff line number Diff line change @@ -22,6 +22,7 @@ public class MuJoCoModelManager {
2222 private mjModel_ maccessable ;
2323 private mjData_ daccessable ;
2424 private mjOption_ opt ;
25+ private IMujocoController controller = null ;
2526 public MuJoCoModelManager (File config ){
2627 loadFromFile (config );
2728 }
@@ -89,6 +90,8 @@ public void setData(mjData_ daccessable) {
8990 }
9091 public void step () {
9192 stepOne ();
93+ if (controller !=null )
94+ controller .controlStep (daccessable , maccessable );
9295 stepTwo ();
9396 }
9497 public void stepOne () {
@@ -109,4 +112,16 @@ public mjOption_ getOpt() {
109112 public void setOpt (mjOption_ opt ) {
110113 this .opt = opt ;
111114 }
115+ /**
116+ * @return the controller
117+ */
118+ public IMujocoController getController () {
119+ return controller ;
120+ }
121+ /**
122+ * @param controller the controller to set
123+ */
124+ public void setController (IMujocoController controller ) {
125+ this .controller = controller ;
126+ }
112127}
Original file line number Diff line number Diff line change @@ -31,10 +31,12 @@ public void managerTest() throws InterruptedException {
3131 mjModel_ model = m .getModel ();
3232 mjData_ data = m .getData ();
3333 System .out .println ("Run ModelManager for 10 seconds" );
34+ m .setController ((data1 , model1 ) -> {
35+ // apply controls https://mujoco.readthedocs.io/en/stable/programming/simulation.html
36+
37+ });
3438 while (data .time () < 10 ) {
35- m .stepOne ();
36- //apply controls
37- m .stepTwo ();
39+ m .step ();
3840 // sleep
3941 Thread .sleep (m .getTimestepMilliSeconds ());
4042 }
@@ -72,7 +74,9 @@ public void mujocoJNILoadTest() {
7274 try (mjData_ accessable = new mjData_ (d )) {
7375 System .out .println ("Run model for 10 seconds" );
7476 while (accessable .time () < 10 ) {
75- MuJoCoLib .mj_step (m , d );
77+ MuJoCoLib .mj_step1 (m , d );
78+ // apply controls https://mujoco.readthedocs.io/en/stable/programming/simulation.html
79+ MuJoCoLib .mj_step2 (m , d );
7680 double timestep = new mjOption_ (Maccessable .opt ()).timestep ()*1000 ;
7781 Thread .sleep ((long ) timestep );
7882
You can’t perform that action at this time.
0 commit comments