From 7c38b05930e21f7f6bfa23b3eae32fe042bba5bd Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Sun, 21 Apr 2024 10:26:03 -0700 Subject: [PATCH 01/52] ODE4J ball bouncing demo (Does not work yet) --- pom.xml | 14 +- .../com/marginallyclever/ro3/Registry.java | 1 + .../marginallyclever/ro3/apps/RO3Frame.java | 10 +- .../ro3/apps/actions/ExportScene.java | 2 +- .../ro3/apps/ode4j/ODE4JPanel.java | 38 +++ .../ro3/node/nodes/BouncingBallDemo.java | 221 ++++++++++++++++++ 6 files changed, 283 insertions(+), 3 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/BouncingBallDemo.java diff --git a/pom.xml b/pom.xml index 5fe758db4..52a5df170 100644 --- a/pom.xml +++ b/pom.xml @@ -81,6 +81,11 @@ jogamp test mirror https://www.jogamp.org/deployment/maven/ default + + + maven_central + Maven Central + https://repo.maven.apache.org/maven2/ @@ -558,6 +563,13 @@ reflections 0.10.2 + + + + net.lingala.zip4j + zip4j + 2.11.5 + diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index 058e41614..4d3ff2ced 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -60,6 +60,7 @@ public static void start() { behavior.add("Sequence", Sequence::new); } node.add("BehaviorTreeRunner", BehaviorTreeRunner::new); + node.add("BoundingBallDemo", BouncingBallDemo::new); node.add("DHParameter", DHParameter::new); node.add("HingeJoint", HingeJoint::new); node.add("LimbPlanner", LimbPlanner::new); diff --git a/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java b/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java index 63131bbf8..c011dff3b 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java +++ b/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java @@ -19,6 +19,7 @@ import com.marginallyclever.ro3.apps.logpanel.LogPanel; import com.marginallyclever.ro3.apps.nodedetailview.NodeDetailView; import com.marginallyclever.ro3.apps.nodetreeview.NodeTreeView; +import com.marginallyclever.ro3.apps.ode4j.ODE4JPanel; import com.marginallyclever.ro3.apps.shared.PersistentJFileChooser; import com.marginallyclever.ro3.apps.webcampanel.WebCamPanel; import com.marginallyclever.ro3.apps.viewport.OpenGLPanel; @@ -56,6 +57,7 @@ public class RO3Frame extends JFrame { private final EditorPanel editPanel; private final WebCamPanel webCamPanel; private final TextInterfaceToSessionLayer textInterface; + private final ODE4JPanel ode4jPanel; public static final FileNameExtensionFilter FILE_FILTER = new FileNameExtensionFilter("RO files", "RO"); public static String VERSION; @@ -74,6 +76,7 @@ public RO3Frame() { viewportPanel = new Viewport(); webCamPanel = new WebCamPanel(); textInterface = new TextInterfaceToSessionLayer(); + ode4jPanel = new ODE4JPanel(); createDefaultLayout(); resetDefaultLayout(); @@ -272,7 +275,8 @@ private JMenu buildFileMenu() { logPanel, editPanel, webCamPanel, - textInterface + textInterface, + ode4jPanel )); dialog.run(this); }); @@ -346,6 +350,10 @@ private void createDefaultLayout() { webcamView.add(webCamPanel, BorderLayout.CENTER); windows.add(webcamView); + DockingPanel ode4jView = new DockingPanel("801706cf-c346-4229-a39e-b3665e5a0d94", "ODE4J"); + ode4jView.add(ode4jPanel, BorderLayout.CENTER); + windows.add(ode4jView); + DockingPanel textInterfaceView = new DockingPanel("7796a733-8e33-417a-b363-b28174901e40", "Serial Interface"); textInterfaceView.add(textInterface, BorderLayout.CENTER); windows.add(textInterfaceView); diff --git a/src/main/java/com/marginallyclever/ro3/apps/actions/ExportScene.java b/src/main/java/com/marginallyclever/ro3/apps/actions/ExportScene.java index 731708e04..60213491e 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/actions/ExportScene.java +++ b/src/main/java/com/marginallyclever/ro3/apps/actions/ExportScene.java @@ -98,7 +98,7 @@ private void createZipAndAddAssets(String outputZipFile, String json, List pathMapping = new HashMap<>(); String rootFolderName = nameWithoutExtension(new File(outputZipFile)); - String sceneName = rootFolderName+ "." + RO3Frame.FILE_FILTER.getExtensions()[0]; // "ro3" or "r + String sceneName = rootFolderName+ "." + RO3Frame.FILE_FILTER.getExtensions()[0]; // "RO" String newSceneName = rootFolderName+"/"+sceneName; pathMapping.put(sceneName,newSceneName); // reserve this name diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java new file mode 100644 index 000000000..f44c1dee6 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -0,0 +1,38 @@ +package com.marginallyclever.ro3.apps.ode4j; + +import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.apps.App; +import com.marginallyclever.ro3.node.nodes.BouncingBallDemo; + +import javax.swing.*; +import java.awt.*; + +/** + * Actions in this window will control the contents of the {@link com.marginallyclever.ro3.Registry#scene}. + */ +public class ODE4JPanel extends App { + public ODE4JPanel() { + super(new BorderLayout()); + + // add a button to setup the first ODE4J simulation. + JButton button = new JButton("Create ODE4J Simulation"); + button.addActionListener((e)->{ + BouncingBallDemo found = guaranteeBouncingBallDemoExists(); + found.reset(); + + }); + add(button, BorderLayout.NORTH); + + //add(editorPane, BorderLayout.CENTER); + } + + private BouncingBallDemo guaranteeBouncingBallDemoExists() { + BouncingBallDemo found = Registry.getScene().findFirstChild(BouncingBallDemo.class); + if(found==null) { + found = new BouncingBallDemo(); + Registry.getScene().addChild(found); + + } + return found; + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/BouncingBallDemo.java b/src/main/java/com/marginallyclever/ro3/node/nodes/BouncingBallDemo.java new file mode 100644 index 000000000..39d1cd24a --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/BouncingBallDemo.java @@ -0,0 +1,221 @@ +package com.marginallyclever.ro3.node.nodes; + +import com.marginallyclever.ro3.mesh.shapes.Grid; +import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; + +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3C; +import org.ode4j.ode.DGeom.DNearCallback; +import org.ode4j.ode.*; + +import javax.vecmath.Matrix4d; +import java.util.ArrayList; +import java.util.List; + +import static org.ode4j.ode.OdeConstants.*; +import static org.ode4j.ode.OdeHelper.*; + +public class BouncingBallDemo extends Node { + private static final double BALL_RADIUS = 0.2; + private static final double BALL_MASS = 1.0; + private static final int ITERS = 20; + private final int N = 4; + private final DContactBuffer contacts = new DContactBuffer(N); + + private DWorld world; + private DSpace space; + private DBody ballBody; + private DGeom ballGeom; + private DJointGroup contactGroup; + + private Pose ballNode; + + public BouncingBallDemo() { + super("ODE4J"); + } + + public BouncingBallDemo(String name) { + super(name); + } + + protected void onAttach() { + super.onAttach(); + + OdeHelper.initODE2(0); + reset(); + } + + @Override + protected void onDetach() { + super.onDetach(); + stopPhysics(); + } + + // reset demo scene. + public void reset() { + resetPhysics(); + resetScene(); + } + + private void stopPhysics() { + if(world!=null) { + world.destroy(); + world=null; + } + if(space!=null) { + space.destroy(); + space=null; + } + if(contactGroup!=null) { + contactGroup.destroy(); + contactGroup=null; + } + } + + private void resetPhysics() { + stopPhysics(); + startPhysics(); + } + + private void startPhysics() { + contactGroup = OdeHelper.createJointGroup(); + + world = createWorld(); + world.setGravity(0, 0, -9.81); + world.setCFM (1e-5); + world.setERP (0.8); + world.setQuickStepNumIterations (ITERS); + + space = //OdeHelper.createSapSpace( null, DSapSpace.AXES.XYZ ); + OdeHelper.createSimpleSpace(); + + ballBody = OdeHelper.createBody(world); + ballGeom = createSphere(space, BALL_RADIUS); + ballGeom.setBody(ballBody); + DMass m = OdeHelper.createMass(); + m.setSphereTotal(BALL_MASS, BALL_RADIUS); + ballBody.setMass(m); + + ballBody.setPosition(0, 0, 2); + + OdeHelper.createPlane (space,0,0,1,0); + } + + private void resetScene() { + // remove all my children. + List kids = new ArrayList<>(getChildren()); + while(!kids.isEmpty()) { + removeChild(kids.remove(0)); + } + + // add a Node with a MeshInstance to represent the ball. + ballNode = new Pose("Ball"); + addChild(ballNode); + MeshInstance ballMesh = new MeshInstance("Sphere"); + ballNode.addChild(ballMesh); + ballMesh.setMesh(new Sphere()); + Matrix4d m = ballMesh.getLocal(); + m.setScale(BALL_RADIUS); + ballMesh.setLocal(m); + + // add a Node with a MeshInstance to represent the floor. + MeshInstance floorNode = new MeshInstance("Floor"); + addChild(floorNode); + floorNode.setMesh(new Grid()); + } + + @Override + public void update(double dt) { + super.update(dt); + + try { + OdeHelper.spaceCollide(space, null, new DNearCallback() { + @Override + public void call(Object data, DGeom o1, DGeom o2) { + nearCallback(data, o1, o2); + } + }); + } catch(Exception e) { + e.printStackTrace(); + } + try { + world.step(dt); + } catch(Exception e) { + e.printStackTrace(); + } + try { + contactGroup.empty(); + } catch(Exception e) { + e.printStackTrace(); + } + + setBallPose(); + } + + // this is called by dSpaceCollide when two objects in space are + // potentially colliding. + + private void nearCallback(Object data, DGeom o1, DGeom o2) { + int i, n; + + DBody b1 = o1.getBody(); + DBody b2 = o2.getBody(); + if (b1 != null && b2 != null && OdeHelper.areConnected(b1, b2)) + return; + + try { + n = OdeHelper.collide(o1, o2, N, contacts.getGeomBuffer());//[0].geom,sizeof(dContact)); + if (n > 0) { + for (i = 0; i < n; i++) { + DContact contact = contacts.get(i); + contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; + //if (o1 instanceof DSphere || o2 instanceof DSphere) + // contact.surface.mu = 20; + //else + contact.surface.mu = 0.5; + contact.surface.slip1 = 0.0; + contact.surface.slip2 = 0.0; + contact.surface.soft_erp = 0.8; + contact.surface.soft_cfm = 0.01; + contact.surface.bounce = 0.9; + contact.surface.bounce_vel = 0.5; + DJoint contactJoint = OdeHelper.createContactJoint(world, contactGroup, contact); + contactJoint.attach(o1.getBody(), o2.getBody()); + } + } + } catch (Exception e) { + e.printStackTrace(); + } + }; + + + private void setBallPose() { + // adjust the position of the ballNode to match the ballBody. + if(ballNode==null || ballBody==null) return; + + Matrix4d m = new Matrix4d(); + DVector3C translation = ballBody.getPosition(); + DMatrix3C rotation = ballBody.getRotation(); + // assemble matrix from translation and rotation. + m.m00 = rotation.get00(); + m.m01 = rotation.get01(); + m.m02 = rotation.get02(); + m.m03 = translation.get0(); + m.m10 = rotation.get10(); + m.m11 = rotation.get11(); + m.m12 = rotation.get12(); + m.m13 = translation.get1(); + m.m20 = rotation.get20(); + m.m21 = rotation.get21(); + m.m22 = rotation.get22(); + m.m23 = translation.get2(); + m.m30 = 0; + m.m31 = 0; + m.m32 = 0; + m.m33 = 1; + ballNode.setWorld(m); + } +} From 6107a41f06052525ed15ec4e4be65fcea8161c29 Mon Sep 17 00:00:00 2001 From: github-actions <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 21 Apr 2024 17:28:17 +0000 Subject: [PATCH 02/52] commit badge --- .github/badges/branches.svg | 2 +- .github/badges/jacoco.svg | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/badges/branches.svg b/.github/badges/branches.svg index af305baef..6dcfc667e 100644 --- a/.github/badges/branches.svg +++ b/.github/badges/branches.svg @@ -1 +1 @@ -branches18.3% \ No newline at end of file +branches18.2% \ No newline at end of file diff --git a/.github/badges/jacoco.svg b/.github/badges/jacoco.svg index 881851307..59f6c5bf4 100644 --- a/.github/badges/jacoco.svg +++ b/.github/badges/jacoco.svg @@ -1 +1 @@ -coverage19.9% \ No newline at end of file +coverage19.7% \ No newline at end of file From d0cbde89c6f30aca44d7b024c6c0ce3a0befd1a9 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Sun, 21 Apr 2024 19:06:05 -0700 Subject: [PATCH 03/52] Added Cube demo --- pom.xml | 2 +- .../com/marginallyclever/ro3/Registry.java | 2 +- .../ro3/apps/ode4j/ODE4JPanel.java | 34 ++- .../com/marginallyclever/ro3/mesh/Mesh.java | 2 +- .../nodes/{ => ode4j}/BouncingBallDemo.java | 32 +-- .../ro3/node/nodes/ode4j/FallingCubeDemo.java | 218 ++++++++++++++++++ .../ro3/node/nodes/ode4j/ODE4JHelper.java | 52 +++++ src/main/java/module-info.java | 2 +- 8 files changed, 311 insertions(+), 33 deletions(-) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ => ode4j}/BouncingBallDemo.java (87%) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java diff --git a/pom.xml b/pom.xml index 52a5df170..df04a962d 100644 --- a/pom.xml +++ b/pom.xml @@ -481,7 +481,7 @@ org.ode4j core - 0.5.2 + 0.5.3-SNAPSHOT diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index 4d3ff2ced..88e6b4b4c 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -13,6 +13,7 @@ import com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlanner; import com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolver; import com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArm; +import com.marginallyclever.ro3.node.nodes.ode4j.BouncingBallDemo; import com.marginallyclever.ro3.node.nodes.pose.*; import com.marginallyclever.ro3.node.nodes.pose.poses.*; import com.marginallyclever.ro3.texture.TextureFactory; @@ -21,7 +22,6 @@ import javax.vecmath.Vector3d; import java.util.ArrayList; import java.util.List; -import java.util.Locale; /** * {@link Registry} is a place to store global variables. diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index f44c1dee6..e3c444f78 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -2,10 +2,12 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.App; -import com.marginallyclever.ro3.node.nodes.BouncingBallDemo; +import com.marginallyclever.ro3.node.nodes.ode4j.BouncingBallDemo; +import com.marginallyclever.ro3.node.nodes.ode4j.FallingCubeDemo; import javax.swing.*; import java.awt.*; +import java.awt.event.ActionListener; /** * Actions in this window will control the contents of the {@link com.marginallyclever.ro3.Registry#scene}. @@ -14,16 +16,26 @@ public class ODE4JPanel extends App { public ODE4JPanel() { super(new BorderLayout()); - // add a button to setup the first ODE4J simulation. - JButton button = new JButton("Create ODE4J Simulation"); - button.addActionListener((e)->{ + JToolBar toolbar = new JToolBar(); + add(toolbar, BorderLayout.NORTH); + + // demo 1 + addButtonByNameAndCallback(toolbar, "Start Bouncing Ball", (e)->{ BouncingBallDemo found = guaranteeBouncingBallDemoExists(); found.reset(); + }); + // demo 2 + addButtonByNameAndCallback(toolbar, "Start Falling Cube", (e)->{ + FallingCubeDemo found = guaranteeFallingCubeExists(); + found.reset(); }); - add(button, BorderLayout.NORTH); + } - //add(editorPane, BorderLayout.CENTER); + private void addButtonByNameAndCallback(JToolBar toolbar, String title, ActionListener actionListener) { + JButton button = new JButton(title); + button.addActionListener(actionListener); + toolbar.add(button); } private BouncingBallDemo guaranteeBouncingBallDemoExists() { @@ -35,4 +47,14 @@ private BouncingBallDemo guaranteeBouncingBallDemoExists() { } return found; } + + private FallingCubeDemo guaranteeFallingCubeExists() { + FallingCubeDemo found = Registry.getScene().findFirstChild(FallingCubeDemo.class); + if(found==null) { + found = new FallingCubeDemo(); + Registry.getScene().addChild(found); + + } + return found; + } } diff --git a/src/main/java/com/marginallyclever/ro3/mesh/Mesh.java b/src/main/java/com/marginallyclever/ro3/mesh/Mesh.java index c13f311aa..4c00ec472 100644 --- a/src/main/java/com/marginallyclever/ro3/mesh/Mesh.java +++ b/src/main/java/com/marginallyclever/ro3/mesh/Mesh.java @@ -47,7 +47,7 @@ public class Mesh { private transient int[] VBO; public int renderStyle = GL3.GL_TRIANGLES; - private String fileName = null; + private String fileName = ""; // bounding limits protected final AABB boundingBox = new AABB(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/BouncingBallDemo.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/BouncingBallDemo.java similarity index 87% rename from src/main/java/com/marginallyclever/ro3/node/nodes/BouncingBallDemo.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/BouncingBallDemo.java index 39d1cd24a..dd0a3969a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/BouncingBallDemo.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/BouncingBallDemo.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes; +package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.mesh.shapes.Grid; import com.marginallyclever.ro3.mesh.shapes.Sphere; @@ -18,9 +18,12 @@ import static org.ode4j.ode.OdeConstants.*; import static org.ode4j.ode.OdeHelper.*; +/** + * ODE4J Bouncing Ball Demo. + */ public class BouncingBallDemo extends Node { - private static final double BALL_RADIUS = 0.2; - private static final double BALL_MASS = 1.0; + private static final double BALL_RADIUS = 5.0; + private static final double BALL_MASS = 23.0; private static final int ITERS = 20; private final int N = 4; private final DContactBuffer contacts = new DContactBuffer(N); @@ -34,7 +37,7 @@ public class BouncingBallDemo extends Node { private Pose ballNode; public BouncingBallDemo() { - super("ODE4J"); + super("Bouncing Ball"); } public BouncingBallDemo(String name) { @@ -99,7 +102,7 @@ private void startPhysics() { m.setSphereTotal(BALL_MASS, BALL_RADIUS); ballBody.setMass(m); - ballBody.setPosition(0, 0, 2); + ballBody.setPosition(0, 0, BALL_RADIUS*3); OdeHelper.createPlane (space,0,0,1,0); } @@ -196,26 +199,9 @@ private void setBallPose() { // adjust the position of the ballNode to match the ballBody. if(ballNode==null || ballBody==null) return; - Matrix4d m = new Matrix4d(); DVector3C translation = ballBody.getPosition(); DMatrix3C rotation = ballBody.getRotation(); - // assemble matrix from translation and rotation. - m.m00 = rotation.get00(); - m.m01 = rotation.get01(); - m.m02 = rotation.get02(); - m.m03 = translation.get0(); - m.m10 = rotation.get10(); - m.m11 = rotation.get11(); - m.m12 = rotation.get12(); - m.m13 = translation.get1(); - m.m20 = rotation.get20(); - m.m21 = rotation.get21(); - m.m22 = rotation.get22(); - m.m23 = translation.get2(); - m.m30 = 0; - m.m31 = 0; - m.m32 = 0; - m.m33 = 1; + Matrix4d m = ODE4JHelper.assembleMatrix(translation, rotation); ballNode.setWorld(m); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java new file mode 100644 index 000000000..f19e10876 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java @@ -0,0 +1,218 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.helpers.MatrixHelper; +import com.marginallyclever.ro3.mesh.shapes.Box; +import com.marginallyclever.ro3.mesh.shapes.Grid; +import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3C; +import org.ode4j.ode.*; +import org.ode4j.ode.DGeom.DNearCallback; + +import javax.vecmath.Matrix4d; +import java.util.ArrayList; +import java.util.List; + +import static org.ode4j.ode.OdeConstants.*; +import static org.ode4j.ode.OdeHelper.*; + +/** + * * ODE4J Bouncing Cube Demo. + */ +public class FallingCubeDemo extends Node { + private static final double CUBE_SIDE_LENGTH = 5.0; + private static final double CUBE_MASS = 23.0; + private static final int ITERS = 20; + private final int N = 4; + private final DContactBuffer contacts = new DContactBuffer(N); + + private DWorld world; + private DSpace space; + private DBody cubeBody; + private DGeom cubeGeom; + private DJointGroup contactGroup; + + private Pose cubeNode; + + public FallingCubeDemo() { + super("Falling Cube"); + } + + public FallingCubeDemo(String name) { + super(name); + } + + protected void onAttach() { + super.onAttach(); + + OdeHelper.initODE2(0); + reset(); + } + + @Override + protected void onDetach() { + super.onDetach(); + stopPhysics(); + } + + // reset demo scene. + public void reset() { + resetPhysics(); + resetScene(); + } + + private void stopPhysics() { + if(world!=null) { + world.destroy(); + world=null; + } + if(space!=null) { + space.destroy(); + space=null; + } + if(contactGroup!=null) { + contactGroup.destroy(); + contactGroup=null; + } + } + + private void resetPhysics() { + stopPhysics(); + startPhysics(); + } + + private void startPhysics() { + contactGroup = OdeHelper.createJointGroup(); + + // build the world + world = createWorld(); + world.setGravity(0, 0, -9.81); + world.setCFM (1e-5); + world.setERP (0.8); + world.setQuickStepNumIterations (ITERS); + + // setup a space in the world + space = //OdeHelper.createSapSpace( null, DSapSpace.AXES.XYZ ); + OdeHelper.createSimpleSpace(); + + // add scene elements + cubeBody = OdeHelper.createBody(world); + cubeGeom = createBox(space, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); + cubeGeom.setBody(cubeBody); + DMass m = OdeHelper.createMass(); + m.setBoxTotal(CUBE_MASS, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); + cubeBody.setMass(m); + cubeBody.setPosition(0, 0, CUBE_SIDE_LENGTH *3); + + Matrix4d mat = new Matrix4d(); + mat.rotX(Math.toRadians(15)); + mat.rotY(Math.toRadians(22.5)); + DMatrix3C dMatrix3 = ODE4JHelper.convertRotationToODE(mat); + + cubeBody.setRotation(dMatrix3); + + OdeHelper.createPlane (space,0,0,1,0); + } + + private void resetScene() { + // remove all my children. + List kids = new ArrayList<>(getChildren()); + while(!kids.isEmpty()) { + removeChild(kids.remove(0)); + } + + // add a Node with a MeshInstance to represent the cube. + cubeNode = new Pose("cube"); + addChild(cubeNode); + MeshInstance cubeMesh = new MeshInstance("Cube"); + cubeNode.addChild(cubeMesh); + cubeMesh.setMesh(new Box()); + Matrix4d m = cubeMesh.getLocal(); + m.setScale(CUBE_SIDE_LENGTH); + cubeMesh.setLocal(m); + + // add a Node with a MeshInstance to represent the floor. + MeshInstance floorNode = new MeshInstance("Floor"); + addChild(floorNode); + floorNode.setMesh(new Grid()); + } + + @Override + public void update(double dt) { + super.update(dt); + + try { + OdeHelper.spaceCollide(space, null, new DNearCallback() { + @Override + public void call(Object data, DGeom o1, DGeom o2) { + nearCallback(data, o1, o2); + } + }); + } catch(Exception e) { + e.printStackTrace(); + } + try { + world.step(dt); + } catch(Exception e) { + e.printStackTrace(); + } + try { + contactGroup.empty(); + } catch(Exception e) { + e.printStackTrace(); + } + + setCubePose(); + } + + // this is called by dSpaceCollide when two objects in space are + // potentially colliding. + + private void nearCallback(Object data, DGeom o1, DGeom o2) { + int i, n; + + DBody b1 = o1.getBody(); + DBody b2 = o2.getBody(); + if (b1 != null && b2 != null && OdeHelper.areConnected(b1, b2)) + return; + + try { + n = OdeHelper.collide(o1, o2, N, contacts.getGeomBuffer());//[0].geom,sizeof(dContact)); + if (n > 0) { + for (i = 0; i < n; i++) { + DContact contact = contacts.get(i); + contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; + //if (o1 instanceof DSphere || o2 instanceof DSphere) + // contact.surface.mu = 20; + //else + contact.surface.mu = 0.5; + contact.surface.slip1 = 0.0; + contact.surface.slip2 = 0.0; + contact.surface.soft_erp = 0.8; + contact.surface.soft_cfm = 0.01; + contact.surface.bounce = 0.9; + contact.surface.bounce_vel = 0.5; + DJoint contactJoint = OdeHelper.createContactJoint(world, contactGroup, contact); + contactJoint.attach(o1.getBody(), o2.getBody()); + } + } + } catch (Exception e) { + e.printStackTrace(); + } + }; + + + private void setCubePose() { + // adjust the position of the cubeNode to match the cubeBody. + if(cubeNode==null || cubeBody==null) return; + + DVector3C translation = cubeBody.getPosition(); + DMatrix3C rotation = cubeBody.getRotation(); + + Matrix4d m = ODE4JHelper.assembleMatrix(translation, rotation); + cubeNode.setWorld(m); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java new file mode 100644 index 000000000..99751a347 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -0,0 +1,52 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import org.ode4j.math.DMatrix3; +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3C; + +import javax.vecmath.Matrix4d; + +public class ODE4JHelper { + + /** + * Convert an ODE4J translation/rotation pair to a Java3D matrix. + * @param translation the translation component. + * @param rotation the rotation matrix + * @return the Java3D matrix. + */ + static Matrix4d assembleMatrix(DVector3C translation, DMatrix3C rotation) { + // assemble matrix from translation and rotation. + Matrix4d m = new Matrix4d(); + m.m00 = rotation.get00(); + m.m01 = rotation.get01(); + m.m02 = rotation.get02(); + m.m03 = translation.get0(); + m.m10 = rotation.get10(); + m.m11 = rotation.get11(); + m.m12 = rotation.get12(); + m.m13 = translation.get1(); + m.m20 = rotation.get20(); + m.m21 = rotation.get21(); + m.m22 = rotation.get22(); + m.m23 = translation.get2(); + m.m30 = 0; + m.m31 = 0; + m.m32 = 0; + m.m33 = 1; + return m; + } + + /** + * receive a 4x4 matrix. extract the rotation component and store it in a DMatrix3C. + * @param mat the 4x4 matrix. + * @return the rotation component. + */ + public static DMatrix3C convertRotationToODE(Matrix4d mat) { + DMatrix3C rotation = new DMatrix3( + mat.m00, mat.m01, mat.m02, + mat.m10, mat.m11, mat.m12, + mat.m20, mat.m21, mat.m22 + ); + return rotation; + } +} diff --git a/src/main/java/module-info.java b/src/main/java/module-info.java index 9574242dc..e617259bc 100644 --- a/src/main/java/module-info.java +++ b/src/main/java/module-info.java @@ -28,7 +28,7 @@ requires batik.all; requires xml.apis.ext; requires java.datatransfer; - requires core; + requires org.ode4j; requires flexmark.util.ast; requires webcam.capture; requires ch.qos.logback.classic; From 73fa8025bb9915fdab2bbbb939859126a525de3d Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Mon, 22 Apr 2024 09:37:24 -0700 Subject: [PATCH 04/52] Further separating physics components --- .../com/marginallyclever/ro3/Registry.java | 13 +- .../ro3/apps/ode4j/ODE4JPanel.java | 41 ++-- .../ro3/node/nodes/LinearJoint.java | 1 - .../ro3/node/nodes/RigidBody3D.java | 57 ----- .../ro3/node/nodes/RigidBody3DPanel.java | 30 --- .../node/nodes/ode4j/BouncingBallDemo.java | 207 ----------------- .../ro3/node/nodes/ode4j/FallingCubeDemo.java | 218 ------------------ .../ro3/node/nodes/ode4j/ODE4JHelper.java | 26 +++ .../ro3/node/nodes/ode4j/ODEBox.java | 119 ++++++++++ .../ro3/node/nodes/ode4j/ODEPlane.java | 90 ++++++++ .../ro3/node/nodes/ode4j/ODESphere.java | 111 +++++++++ .../ro3/node/nodes/ode4j/ODEWorldSpace.java | 159 +++++++++++++ .../node/nodes/ode4j/icons8-mechanics-16.png | Bin 0 -> 326 bytes 13 files changed, 529 insertions(+), 543 deletions(-) delete mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3D.java delete mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3DPanel.java delete mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/BouncingBallDemo.java delete mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java create mode 100644 src/main/resources/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index 88e6b4b4c..f6a86f5fd 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -13,7 +13,10 @@ import com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlanner; import com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolver; import com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArm; -import com.marginallyclever.ro3.node.nodes.ode4j.BouncingBallDemo; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEBox; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEPlane; +import com.marginallyclever.ro3.node.nodes.ode4j.ODESphere; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.*; import com.marginallyclever.ro3.node.nodes.pose.poses.*; import com.marginallyclever.ro3.texture.TextureFactory; @@ -60,7 +63,6 @@ public static void start() { behavior.add("Sequence", Sequence::new); } node.add("BehaviorTreeRunner", BehaviorTreeRunner::new); - node.add("BoundingBallDemo", BouncingBallDemo::new); node.add("DHParameter", DHParameter::new); node.add("HingeJoint", HingeJoint::new); node.add("LimbPlanner", LimbPlanner::new); @@ -77,6 +79,13 @@ public static void start() { pose.add("LookAt", LookAt::new); pose.add("MeshInstance", MeshInstance::new); } + NodeFactory.Category physics = node.add("Physics", null); + { + physics.add("ODEWorldSpace", ODEWorldSpace::new); + physics.add("ODEBox", ODEBox::new); + physics.add("ODEPlane", ODEPlane::new); + physics.add("ODESphere", ODESphere::new); + } } reset(); } diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index e3c444f78..0ace186a2 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -2,8 +2,10 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.App; -import com.marginallyclever.ro3.node.nodes.ode4j.BouncingBallDemo; -import com.marginallyclever.ro3.node.nodes.ode4j.FallingCubeDemo; +import com.marginallyclever.ro3.node.nodes.ode4j.ODESphere; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEBox; +import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import javax.swing.*; import java.awt.*; @@ -19,16 +21,19 @@ public ODE4JPanel() { JToolBar toolbar = new JToolBar(); add(toolbar, BorderLayout.NORTH); + // demo 1 - addButtonByNameAndCallback(toolbar, "Start Bouncing Ball", (e)->{ - BouncingBallDemo found = guaranteeBouncingBallDemoExists(); - found.reset(); + addButtonByNameAndCallback(toolbar, "Add Sphere", (e)->{ + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODE4JHelper.guaranteeFloor(physics); + Registry.getScene().addChild(new ODESphere()); }); // demo 2 - addButtonByNameAndCallback(toolbar, "Start Falling Cube", (e)->{ - FallingCubeDemo found = guaranteeFallingCubeExists(); - found.reset(); + addButtonByNameAndCallback(toolbar, "Add Box", (e)->{ + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODE4JHelper.guaranteeFloor(physics); + Registry.getScene().addChild(new ODEBox()); }); } @@ -37,24 +42,4 @@ private void addButtonByNameAndCallback(JToolBar toolbar, String title, ActionLi button.addActionListener(actionListener); toolbar.add(button); } - - private BouncingBallDemo guaranteeBouncingBallDemoExists() { - BouncingBallDemo found = Registry.getScene().findFirstChild(BouncingBallDemo.class); - if(found==null) { - found = new BouncingBallDemo(); - Registry.getScene().addChild(found); - - } - return found; - } - - private FallingCubeDemo guaranteeFallingCubeExists() { - FallingCubeDemo found = Registry.getScene().findFirstChild(FallingCubeDemo.class); - if(found==null) { - found = new FallingCubeDemo(); - Registry.getScene().addChild(found); - - } - return found; - } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java b/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java index 916faf510..e8c0faa71 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java @@ -1,6 +1,5 @@ package com.marginallyclever.ro3.node.nodes; -import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.NodePath; import com.marginallyclever.ro3.node.nodes.pose.Pose; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3D.java b/src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3D.java deleted file mode 100644 index ca9469d60..000000000 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3D.java +++ /dev/null @@ -1,57 +0,0 @@ -package com.marginallyclever.ro3.node.nodes; - -import com.marginallyclever.ro3.node.Node; -import org.json.JSONObject; - -import javax.swing.*; -import javax.vecmath.Matrix3d; -import java.util.List; - -/** - * {@link RigidBody3D} is a {@link Node} that represents a rigid body. - */ -public class RigidBody3D extends Node { - private double mass = 0; - private final Matrix3d momentOfIntertia = new Matrix3d(); - - public RigidBody3D() { - this("RigidBody3D"); - } - - public RigidBody3D(String name) { - super(name); - } - - @Override - public void getComponents(List list) { - list.add(new RigidBody3DPanel(this)); - super.getComponents(list); - } - - @Override - public JSONObject toJSON() { - var json = super.toJSON(); - json.put("mass",mass); - return json; - } - - @Override - public void fromJSON(JSONObject json) { - super.fromJSON(json); - mass = json.getDouble("mass"); - } - - public double getMass() { - return mass; - } - - /** - * Set the mass of this rigid body. - * @param mass the mass of this rigid body. - * @throws IllegalArgumentException if mass is less than zero. - */ - public void setMass(double mass) { - if(mass<0) throw new IllegalArgumentException("Mass must be >= 0"); - this.mass = mass; - } -} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3DPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3DPanel.java deleted file mode 100644 index f86ddad26..000000000 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/RigidBody3DPanel.java +++ /dev/null @@ -1,30 +0,0 @@ -package com.marginallyclever.ro3.node.nodes; - -import com.marginallyclever.convenience.swing.NumberFormatHelper; -import com.marginallyclever.ro3.PanelHelper; - -import javax.swing.*; -import java.awt.*; - -public class RigidBody3DPanel extends JPanel { - public RigidBody3DPanel() { - this(new RigidBody3D()); - } - - public RigidBody3DPanel(RigidBody3D rigidBody3D) { - super(new GridLayout(0,2)); - this.setName(RigidBody3D.class.getSimpleName()); - - // mass - var formatter = NumberFormatHelper.getNumberFormatter(); - formatter.setMinimum(0.0); - var massField = new JFormattedTextField(formatter); - massField.setValue(rigidBody3D.getMass()); - massField.addPropertyChangeListener("value", evt -> { - var value = (Number) massField.getValue(); - rigidBody3D.setMass(value.doubleValue()); - }); - - PanelHelper.addLabelAndComponent(this,"Mass",massField); - } -} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/BouncingBallDemo.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/BouncingBallDemo.java deleted file mode 100644 index dd0a3969a..000000000 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/BouncingBallDemo.java +++ /dev/null @@ -1,207 +0,0 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; - -import com.marginallyclever.ro3.mesh.shapes.Grid; -import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.Node; -import com.marginallyclever.ro3.node.nodes.pose.Pose; -import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; - -import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3C; -import org.ode4j.ode.DGeom.DNearCallback; -import org.ode4j.ode.*; - -import javax.vecmath.Matrix4d; -import java.util.ArrayList; -import java.util.List; - -import static org.ode4j.ode.OdeConstants.*; -import static org.ode4j.ode.OdeHelper.*; - -/** - * ODE4J Bouncing Ball Demo. - */ -public class BouncingBallDemo extends Node { - private static final double BALL_RADIUS = 5.0; - private static final double BALL_MASS = 23.0; - private static final int ITERS = 20; - private final int N = 4; - private final DContactBuffer contacts = new DContactBuffer(N); - - private DWorld world; - private DSpace space; - private DBody ballBody; - private DGeom ballGeom; - private DJointGroup contactGroup; - - private Pose ballNode; - - public BouncingBallDemo() { - super("Bouncing Ball"); - } - - public BouncingBallDemo(String name) { - super(name); - } - - protected void onAttach() { - super.onAttach(); - - OdeHelper.initODE2(0); - reset(); - } - - @Override - protected void onDetach() { - super.onDetach(); - stopPhysics(); - } - - // reset demo scene. - public void reset() { - resetPhysics(); - resetScene(); - } - - private void stopPhysics() { - if(world!=null) { - world.destroy(); - world=null; - } - if(space!=null) { - space.destroy(); - space=null; - } - if(contactGroup!=null) { - contactGroup.destroy(); - contactGroup=null; - } - } - - private void resetPhysics() { - stopPhysics(); - startPhysics(); - } - - private void startPhysics() { - contactGroup = OdeHelper.createJointGroup(); - - world = createWorld(); - world.setGravity(0, 0, -9.81); - world.setCFM (1e-5); - world.setERP (0.8); - world.setQuickStepNumIterations (ITERS); - - space = //OdeHelper.createSapSpace( null, DSapSpace.AXES.XYZ ); - OdeHelper.createSimpleSpace(); - - ballBody = OdeHelper.createBody(world); - ballGeom = createSphere(space, BALL_RADIUS); - ballGeom.setBody(ballBody); - DMass m = OdeHelper.createMass(); - m.setSphereTotal(BALL_MASS, BALL_RADIUS); - ballBody.setMass(m); - - ballBody.setPosition(0, 0, BALL_RADIUS*3); - - OdeHelper.createPlane (space,0,0,1,0); - } - - private void resetScene() { - // remove all my children. - List kids = new ArrayList<>(getChildren()); - while(!kids.isEmpty()) { - removeChild(kids.remove(0)); - } - - // add a Node with a MeshInstance to represent the ball. - ballNode = new Pose("Ball"); - addChild(ballNode); - MeshInstance ballMesh = new MeshInstance("Sphere"); - ballNode.addChild(ballMesh); - ballMesh.setMesh(new Sphere()); - Matrix4d m = ballMesh.getLocal(); - m.setScale(BALL_RADIUS); - ballMesh.setLocal(m); - - // add a Node with a MeshInstance to represent the floor. - MeshInstance floorNode = new MeshInstance("Floor"); - addChild(floorNode); - floorNode.setMesh(new Grid()); - } - - @Override - public void update(double dt) { - super.update(dt); - - try { - OdeHelper.spaceCollide(space, null, new DNearCallback() { - @Override - public void call(Object data, DGeom o1, DGeom o2) { - nearCallback(data, o1, o2); - } - }); - } catch(Exception e) { - e.printStackTrace(); - } - try { - world.step(dt); - } catch(Exception e) { - e.printStackTrace(); - } - try { - contactGroup.empty(); - } catch(Exception e) { - e.printStackTrace(); - } - - setBallPose(); - } - - // this is called by dSpaceCollide when two objects in space are - // potentially colliding. - - private void nearCallback(Object data, DGeom o1, DGeom o2) { - int i, n; - - DBody b1 = o1.getBody(); - DBody b2 = o2.getBody(); - if (b1 != null && b2 != null && OdeHelper.areConnected(b1, b2)) - return; - - try { - n = OdeHelper.collide(o1, o2, N, contacts.getGeomBuffer());//[0].geom,sizeof(dContact)); - if (n > 0) { - for (i = 0; i < n; i++) { - DContact contact = contacts.get(i); - contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; - //if (o1 instanceof DSphere || o2 instanceof DSphere) - // contact.surface.mu = 20; - //else - contact.surface.mu = 0.5; - contact.surface.slip1 = 0.0; - contact.surface.slip2 = 0.0; - contact.surface.soft_erp = 0.8; - contact.surface.soft_cfm = 0.01; - contact.surface.bounce = 0.9; - contact.surface.bounce_vel = 0.5; - DJoint contactJoint = OdeHelper.createContactJoint(world, contactGroup, contact); - contactJoint.attach(o1.getBody(), o2.getBody()); - } - } - } catch (Exception e) { - e.printStackTrace(); - } - }; - - - private void setBallPose() { - // adjust the position of the ballNode to match the ballBody. - if(ballNode==null || ballBody==null) return; - - DVector3C translation = ballBody.getPosition(); - DMatrix3C rotation = ballBody.getRotation(); - Matrix4d m = ODE4JHelper.assembleMatrix(translation, rotation); - ballNode.setWorld(m); - } -} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java deleted file mode 100644 index f19e10876..000000000 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/FallingCubeDemo.java +++ /dev/null @@ -1,218 +0,0 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; - -import com.marginallyclever.convenience.helpers.MatrixHelper; -import com.marginallyclever.ro3.mesh.shapes.Box; -import com.marginallyclever.ro3.mesh.shapes.Grid; -import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.Node; -import com.marginallyclever.ro3.node.nodes.pose.Pose; -import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; -import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3C; -import org.ode4j.ode.*; -import org.ode4j.ode.DGeom.DNearCallback; - -import javax.vecmath.Matrix4d; -import java.util.ArrayList; -import java.util.List; - -import static org.ode4j.ode.OdeConstants.*; -import static org.ode4j.ode.OdeHelper.*; - -/** - * * ODE4J Bouncing Cube Demo. - */ -public class FallingCubeDemo extends Node { - private static final double CUBE_SIDE_LENGTH = 5.0; - private static final double CUBE_MASS = 23.0; - private static final int ITERS = 20; - private final int N = 4; - private final DContactBuffer contacts = new DContactBuffer(N); - - private DWorld world; - private DSpace space; - private DBody cubeBody; - private DGeom cubeGeom; - private DJointGroup contactGroup; - - private Pose cubeNode; - - public FallingCubeDemo() { - super("Falling Cube"); - } - - public FallingCubeDemo(String name) { - super(name); - } - - protected void onAttach() { - super.onAttach(); - - OdeHelper.initODE2(0); - reset(); - } - - @Override - protected void onDetach() { - super.onDetach(); - stopPhysics(); - } - - // reset demo scene. - public void reset() { - resetPhysics(); - resetScene(); - } - - private void stopPhysics() { - if(world!=null) { - world.destroy(); - world=null; - } - if(space!=null) { - space.destroy(); - space=null; - } - if(contactGroup!=null) { - contactGroup.destroy(); - contactGroup=null; - } - } - - private void resetPhysics() { - stopPhysics(); - startPhysics(); - } - - private void startPhysics() { - contactGroup = OdeHelper.createJointGroup(); - - // build the world - world = createWorld(); - world.setGravity(0, 0, -9.81); - world.setCFM (1e-5); - world.setERP (0.8); - world.setQuickStepNumIterations (ITERS); - - // setup a space in the world - space = //OdeHelper.createSapSpace( null, DSapSpace.AXES.XYZ ); - OdeHelper.createSimpleSpace(); - - // add scene elements - cubeBody = OdeHelper.createBody(world); - cubeGeom = createBox(space, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); - cubeGeom.setBody(cubeBody); - DMass m = OdeHelper.createMass(); - m.setBoxTotal(CUBE_MASS, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); - cubeBody.setMass(m); - cubeBody.setPosition(0, 0, CUBE_SIDE_LENGTH *3); - - Matrix4d mat = new Matrix4d(); - mat.rotX(Math.toRadians(15)); - mat.rotY(Math.toRadians(22.5)); - DMatrix3C dMatrix3 = ODE4JHelper.convertRotationToODE(mat); - - cubeBody.setRotation(dMatrix3); - - OdeHelper.createPlane (space,0,0,1,0); - } - - private void resetScene() { - // remove all my children. - List kids = new ArrayList<>(getChildren()); - while(!kids.isEmpty()) { - removeChild(kids.remove(0)); - } - - // add a Node with a MeshInstance to represent the cube. - cubeNode = new Pose("cube"); - addChild(cubeNode); - MeshInstance cubeMesh = new MeshInstance("Cube"); - cubeNode.addChild(cubeMesh); - cubeMesh.setMesh(new Box()); - Matrix4d m = cubeMesh.getLocal(); - m.setScale(CUBE_SIDE_LENGTH); - cubeMesh.setLocal(m); - - // add a Node with a MeshInstance to represent the floor. - MeshInstance floorNode = new MeshInstance("Floor"); - addChild(floorNode); - floorNode.setMesh(new Grid()); - } - - @Override - public void update(double dt) { - super.update(dt); - - try { - OdeHelper.spaceCollide(space, null, new DNearCallback() { - @Override - public void call(Object data, DGeom o1, DGeom o2) { - nearCallback(data, o1, o2); - } - }); - } catch(Exception e) { - e.printStackTrace(); - } - try { - world.step(dt); - } catch(Exception e) { - e.printStackTrace(); - } - try { - contactGroup.empty(); - } catch(Exception e) { - e.printStackTrace(); - } - - setCubePose(); - } - - // this is called by dSpaceCollide when two objects in space are - // potentially colliding. - - private void nearCallback(Object data, DGeom o1, DGeom o2) { - int i, n; - - DBody b1 = o1.getBody(); - DBody b2 = o2.getBody(); - if (b1 != null && b2 != null && OdeHelper.areConnected(b1, b2)) - return; - - try { - n = OdeHelper.collide(o1, o2, N, contacts.getGeomBuffer());//[0].geom,sizeof(dContact)); - if (n > 0) { - for (i = 0; i < n; i++) { - DContact contact = contacts.get(i); - contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; - //if (o1 instanceof DSphere || o2 instanceof DSphere) - // contact.surface.mu = 20; - //else - contact.surface.mu = 0.5; - contact.surface.slip1 = 0.0; - contact.surface.slip2 = 0.0; - contact.surface.soft_erp = 0.8; - contact.surface.soft_cfm = 0.01; - contact.surface.bounce = 0.9; - contact.surface.bounce_vel = 0.5; - DJoint contactJoint = OdeHelper.createContactJoint(world, contactGroup, contact); - contactJoint.attach(o1.getBody(), o2.getBody()); - } - } - } catch (Exception e) { - e.printStackTrace(); - } - }; - - - private void setCubePose() { - // adjust the position of the cubeNode to match the cubeBody. - if(cubeNode==null || cubeBody==null) return; - - DVector3C translation = cubeBody.getPosition(); - DMatrix3C rotation = cubeBody.getRotation(); - - Matrix4d m = ODE4JHelper.assembleMatrix(translation, rotation); - cubeNode.setWorld(m); - } -} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index 99751a347..518e124a8 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -1,12 +1,20 @@ package com.marginallyclever.ro3.node.nodes.ode4j; +import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.math.DMatrix3; import org.ode4j.math.DMatrix3C; import org.ode4j.math.DVector3C; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; import javax.vecmath.Matrix4d; +/** + * Shared methods for working with ODE4J physics. + */ public class ODE4JHelper { + private static final Logger logger = LoggerFactory.getLogger(ODE4JHelper.class); /** * Convert an ODE4J translation/rotation pair to a Java3D matrix. @@ -49,4 +57,22 @@ public static DMatrix3C convertRotationToODE(Matrix4d mat) { ); return rotation; } + + public static void guaranteeFloor(ODEWorldSpace physics) { + MeshInstance floorNode = (MeshInstance) Registry.getScene().findChild("Floor"); + if(floorNode==null) { + logger.debug("Creating floor"); + Registry.getScene().addChild(new ODEPlane()); + } + } + + public static ODEWorldSpace guaranteePhysicsWorld() { + ODEWorldSpace physics = Registry.getScene().findFirstChild(ODEWorldSpace.class); + if (physics == null) { + logger.debug("Creating PhysicsWorld"); + physics = new ODEWorldSpace(); + Registry.getScene().addChild(physics); + } + return physics; + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java new file mode 100644 index 000000000..6626886aa --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java @@ -0,0 +1,119 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.mesh.shapes.Box; +import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3; +import org.ode4j.math.DVector3C; +import org.ode4j.ode.*; + +import javax.swing.*; +import javax.vecmath.Matrix4d; + +import java.awt.*; +import java.util.Objects; + +import static org.ode4j.ode.OdeHelper.*; + +/** + * Wrapper for a ODE4J Box. + */ +public class ODEBox extends Pose { + private static final double CUBE_SIDE_LENGTH = 5.0; + private static final double CUBE_MASS = 23.0; + + private DBody body; + private DGeom geom; + + public ODEBox() { + this("ODE Box"); + } + + public ODEBox(String name) { + super(name); + } + + @Override + protected void onAttach() { + super.onAttach(); + + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + // add scene elements + body = OdeHelper.createBody(physics.getODEWorld()); + geom = createBox(physics.getODESpace(), CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); + geom.setBody(body); + + DMass mass = OdeHelper.createMass(); + mass.setBoxTotal(CUBE_MASS, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); + body.setMass(mass); + body.setPosition(0, 0, CUBE_SIDE_LENGTH * 5); + + Matrix4d rx = new Matrix4d(); + Matrix4d ry = new Matrix4d(); + rx.rotX(Math.toRadians(Math.random()*90)); + ry.rotY(Math.toRadians(Math.random()*90)); + Matrix4d mat = new Matrix4d(); + mat.mul(ry, rx); + body.setRotation(ODE4JHelper.convertRotationToODE(mat)); + + // add a Node with a MeshInstance to represent the cube. + MeshInstance cubeMesh = new MeshInstance(); + addChild(cubeMesh); + cubeMesh.setMesh(new Box()); + mat = cubeMesh.getLocal(); + mat.setScale(CUBE_SIDE_LENGTH); + cubeMesh.setLocal(mat); + + // add a Material with random diffuse color + Material material = new Material(); + material.setDiffuseColor(new Color( + (int)(Math.random()*255.0), + (int)(Math.random()*255.0), + (int)(Math.random()*255.0))); + addChild(material); + } + + @Override + protected void onDetach() { + super.onDetach(); + if(body != null) { + body.destroy(); + body = null; + } + if(geom != null) { + geom.destroy(); + geom = null; + } + } + + @Override + public void update(double dt) { + super.update(dt); + + // adjust the position of the Node to match the body. + if(body == null) return; + + DVector3C translation = body.getPosition(); + DMatrix3C rotation = body.getRotation(); + super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); + } + + @Override + public void setWorld(Matrix4d world) { + super.setWorld(world); + if(body == null) return; + + body.setPosition(world.m03, world.m13, world.m23); + body.setRotation(ODE4JHelper.convertRotationToODE(world)); + // stop movement so object does not fight user. + body.setAngularVel(new DVector3(0, 0, 0)); + body.setLinearVel(new DVector3(0, 0, 0)); + } + + @Override + public Icon getIcon() { + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java new file mode 100644 index 000000000..a7d17f5ba --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -0,0 +1,90 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.helpers.MatrixHelper; +import com.marginallyclever.ro3.mesh.shapes.Grid; +import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.ode4j.ode.DPlane; +import org.ode4j.ode.OdeHelper; + +import javax.swing.*; +import javax.vecmath.Matrix3d; +import javax.vecmath.Matrix4d; +import javax.vecmath.Vector3d; +import java.util.Objects; + +/** + * Wrapper for a ODE4J Plane. + */ +public class ODEPlane extends Pose { + private DPlane plane; + + public ODEPlane() { + this("ODE Plane"); + } + + public ODEPlane(String name) { + super(name); + } + + @Override + protected void onAttach() { + super.onAttach(); + + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + plane = OdeHelper.createPlane(physics.getODESpace(), 0, 0, 1, 0); + + // add a Node with a MeshInstance to represent the floor. + MeshInstance mesh = new MeshInstance(); + addChild(mesh); + mesh.setMesh(new Grid()); + + addChild(new Material()); + } + + @Override + protected void onDetach() { + super.onDetach(); + if(plane!=null) { + plane.destroy(); + plane = null; + } + } + + @Override + public void update(double dt) { + super.update(dt); + + // adjust the position of the Node to match the body. + if(plane == null) return; + + var odeNormal = plane.getNormal(); + double distance = plane.getDepth(); + + Vector3d normal = new Vector3d(odeNormal.get0(), odeNormal.get1(), odeNormal.get2()); + Matrix3d m3 = MatrixHelper.getMatrixFromAxisAndRotation(normal,0); + Matrix4d m4 = new Matrix4d(); + m4.set(m3); + // set translation along normal + normal.scale(distance); + m4.setTranslation(normal); + super.setWorld(m4); + } + + @Override + public void setWorld(Matrix4d world) { + super.setWorld(world); + if(plane==null) return; + + Vector3d normal = MatrixHelper.getZAxis(world); + Vector3d position = MatrixHelper.getPosition(world); + double depth = normal.dot(position); + plane.setParams(normal.x, normal.y, normal.z, depth); + } + + @Override + public Icon getIcon() { + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java new file mode 100644 index 000000000..1ad4cfea3 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java @@ -0,0 +1,111 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; + +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3; +import org.ode4j.math.DVector3C; +import org.ode4j.ode.*; + +import javax.swing.*; +import javax.vecmath.Matrix4d; + +import java.awt.*; +import java.util.Objects; + +import static org.ode4j.ode.OdeHelper.*; + +/** + * Wrapper for a ODE4J Sphere. + */ +public class ODESphere extends Pose { + private static final double BALL_RADIUS = 3.0; + private static final double BALL_MASS = 23.0; + + private DBody body; + private DGeom geom; + + public ODESphere() { + this("ODE Sphere"); + } + + public ODESphere(String name) { + super(name); + } + + @Override + protected void onAttach() { + super.onAttach(); + + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + body = OdeHelper.createBody(physics.getODEWorld()); + geom = createSphere(physics.getODESpace(), BALL_RADIUS); + geom.setBody(body); + + DMass mass = OdeHelper.createMass(); + mass.setSphereTotal(BALL_MASS, BALL_RADIUS); + body.setMass(mass); + body.setPosition(0, 0, BALL_RADIUS * 5); + + // add a Node with a MeshInstance to represent the ball. + MeshInstance ballMesh = new MeshInstance(); + addChild(ballMesh); + ballMesh.setMesh(new Sphere()); + Matrix4d m = ballMesh.getLocal(); + m.setScale(BALL_RADIUS); + ballMesh.setLocal(m); + + // add a Material with random diffuse color + Material material = new Material(); + material.setDiffuseColor(new Color( + (int)(Math.random()*255.0), + (int)(Math.random()*255.0), + (int)(Math.random()*255.0))); + addChild(material); + } + + @Override + protected void onDetach() { + super.onDetach(); + if(body != null) { + body.destroy(); + body = null; + } + if(geom != null) { + geom.destroy(); + geom = null; + } + } + + @Override + public void update(double dt) { + super.update(dt); + + // adjust the position of the Node to match the body. + if(body == null) return; + + DVector3C translation = body.getPosition(); + DMatrix3C rotation = body.getRotation(); + super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); + } + + @Override + public void setWorld(Matrix4d world) { + super.setWorld(world); + if(body == null) return; + + body.setPosition(world.m03, world.m13, world.m23); + body.setRotation(ODE4JHelper.convertRotationToODE(world)); + // stop movement so object does not fight user. + body.setAngularVel(new DVector3(0, 0, 0)); + body.setLinearVel(new DVector3(0, 0, 0)); + } + + @Override + public Icon getIcon() { + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java new file mode 100644 index 000000000..69ba32c3d --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java @@ -0,0 +1,159 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.node.Node; +import org.ode4j.ode.*; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +import javax.swing.*; +import java.util.Objects; + +import static org.ode4j.ode.OdeConstants.*; +import static org.ode4j.ode.OdeHelper.createWorld; + +/** + * Manages the ODE4J physics world, space, and contact handling. There must be exactly one of these in the scene + * for physics to work. + */ +public class ODEWorldSpace extends Node { + private static final Logger logger = LoggerFactory.getLogger(ODEWorldSpace.class); + + public static final double WORLD_CFM = 1e-5; + public static final double WORLD_ERP = 0.8; + public static final double WORLD_GRAVITY = -9.81; + private static final int ITERS = 20; + private final int N = 4; + + private DWorld world; + private DSpace space; + private DContactBuffer contacts; + private DJointGroup contactGroup; + + public ODEWorldSpace() { + this("PhysicsWorld"); + } + + public ODEWorldSpace(String name) { + super(name); + } + + @Override + protected void onAttach() { + super.onAttach(); + + OdeHelper.initODE2(0); + + startPhysics(); + } + + @Override + protected void onDetach() { + super.onDetach(); + stopPhysics(); + } + + public void resetPhysics() { + stopPhysics(); + startPhysics(); + } + + private void startPhysics() { + logger.info("Starting Physics"); + + // build the world + world = createWorld(); + world.setGravity(0, 0, WORLD_GRAVITY); + world.setCFM (WORLD_CFM); + world.setERP (WORLD_ERP); + world.setQuickStepNumIterations (ITERS); + + // setup a space in the world + space = OdeHelper.createSapSpace( null, DSapSpace.AXES.XYZ ); + //space = OdeHelper.createSimpleSpace(); + + contacts = new DContactBuffer(N); + + if(contactGroup == null) { + contactGroup = OdeHelper.createJointGroup(); + } + } + + private void stopPhysics() { + logger.info("Stopping Physics"); + + if(world!=null) { + world.destroy(); + world=null; + } + + if(space!=null) { + space.destroy(); + space=null; + } + + if(contactGroup!=null) { + contactGroup.destroy(); + contactGroup=null; + } + } + + public DWorld getODEWorld() { + return world; + } + + public DSpace getODESpace() { + return space; + } + + @Override + public void update(double dt) { + super.update(dt); + + try { + OdeHelper.spaceCollide(getODESpace(), null, this::nearCallback); + world.step(dt); + contactGroup.empty(); + } catch(Exception e) { + logger.error("update failed.", e); + } + } + + // this is called by dSpaceCollide when two objects in space are + // potentially colliding. + private void nearCallback(Object data, DGeom o1, DGeom o2) { + DBody b1 = o1.getBody(); + DBody b2 = o2.getBody(); + if (b1 != null && b2 != null && OdeHelper.areConnected(b1, b2)) + return; + + try { + ODEWorldSpace physics = Registry.getScene().findFirstChild(ODEWorldSpace.class); + + int n = OdeHelper.collide(o1, o2, N, contacts.getGeomBuffer()); + if (n > 0) { + for (int i = 0; i < n; i++) { + DContact contact = contacts.get(i); + contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; + + contact.surface.mu = 0.5; + contact.surface.slip1 = 0.0; + contact.surface.slip2 = 0.0; + contact.surface.soft_erp = 0.8; + contact.surface.soft_cfm = 0.01; + contact.surface.bounce = 0.9; + contact.surface.bounce_vel = 0.5; + DJoint contactJoint = OdeHelper.createContactJoint(physics.getODEWorld(), contactGroup, contact); + contactJoint.attach(o1.getBody(), o2.getBody()); + } + } + } catch (Exception e) { + logger.error("collision failed.", e); + } + } + + @Override + public Icon getIcon() { + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + } +} diff --git a/src/main/resources/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png b/src/main/resources/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png new file mode 100644 index 0000000000000000000000000000000000000000..b464dcd429663a624e00abc9a0d617d66f52705a GIT binary patch literal 326 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`oCO|{#S9GG!XV7ZFl&wkQ1FMR zi(^Q|oa6+FN{7r_%ejtb&cCne_q)co?wGsxB@_RDYgSvl{akM`@7GVO&TaK&PKF7$ zo}0U5`mD(j^;}vXYt?m1J4fA!G_}ig^@wcxsZqi)2FIWqx(J#rj zoFii0vh1uR-}QER&##teH|DsCtzN%A-D}0$DEavNsSHLu>;FH>-c_Cay86n6qmQ$! zWglnn&Ods!jP;SJ!op?Myk>X1zU literal 0 HcmV?d00001 From 2a6799b4b24abfb4f98eb26b6518c23574d15c17 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Mon, 22 Apr 2024 14:35:32 -0700 Subject: [PATCH 05/52] added capsule, cylinder, icons, and floor texture. --- pom.xml | 2 +- .../com/marginallyclever/ro3/AllPanels.java | 2 +- .../ro3/apps/editorpanel/EditorPanel.java | 2 +- .../ro3/apps/ode4j/ODE4JPanel.java | 56 +++++-- .../ro3/apps/viewport/OpenGLPanel.java | 1 + .../viewport/renderpasses/DrawBackground.java | 9 +- .../ro3/mesh/shapes/Decal.java | 107 ++++++++------ .../ro3/mesh/shapes/Sphere.java | 14 +- .../ro3/node/nodes/DHParameterPanel.java | 3 - .../ro3/node/nodes/ode4j/ODE4JHelper.java | 12 +- .../ro3/node/nodes/ode4j/ODEBox.java | 13 +- .../ro3/node/nodes/ode4j/ODECapsule.java | 139 ++++++++++++++++++ .../ro3/node/nodes/ode4j/ODECylinder.java | 118 +++++++++++++++ .../ro3/node/nodes/ode4j/ODEPlane.java | 15 +- .../ro3/node/nodes/ode4j/ODESphere.java | 16 +- .../ro3/node/nodes/ode4j/ODEWorldSpace.java | 19 +++ .../node/nodes/ode4j/ODEWorldSpacePanel.java | 46 ++++++ .../ro3/texture/TextureWithMetadata.java | 11 ++ .../ro3/shared/checkerboard.png | Bin 0 -> 576 bytes .../ro3/shared/icons8-pause-16.png | Bin 0 -> 189 bytes .../editorpanel => shared}/icons8-play-16.png | Bin 21 files changed, 481 insertions(+), 104 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpacePanel.java create mode 100644 src/main/resources/com/marginallyclever/ro3/shared/checkerboard.png create mode 100644 src/main/resources/com/marginallyclever/ro3/shared/icons8-pause-16.png rename src/main/resources/com/marginallyclever/ro3/{apps/editorpanel => shared}/icons8-play-16.png (100%) diff --git a/pom.xml b/pom.xml index df04a962d..aec770524 100644 --- a/pom.xml +++ b/pom.xml @@ -481,7 +481,7 @@ org.ode4j core - 0.5.3-SNAPSHOT + 0.5.3a-SNAPSHOT diff --git a/src/main/java/com/marginallyclever/ro3/AllPanels.java b/src/main/java/com/marginallyclever/ro3/AllPanels.java index be85ff2cd..53be99375 100644 --- a/src/main/java/com/marginallyclever/ro3/AllPanels.java +++ b/src/main/java/com/marginallyclever/ro3/AllPanels.java @@ -96,13 +96,13 @@ private Collection> getHandmadeList() { com.marginallyclever.ro3.node.nodes.LinearJointPanel.class, com.marginallyclever.ro3.node.nodes.MaterialPanel.class, com.marginallyclever.ro3.node.nodes.MotorPanel.class, - com.marginallyclever.ro3.node.nodes.RigidBody3DPanel.class, com.marginallyclever.ro3.node.nodes.behavior.BehaviorTreeRunnerPanel.class, com.marginallyclever.ro3.node.nodes.behavior.actions.LimbMoveToTargetPanel.class, com.marginallyclever.ro3.node.nodes.behavior.decorators.RepeatPanel.class, com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlannerPanel.class, com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolverPanel.class, com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArmPanel.class, + com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpacePanel.class, com.marginallyclever.ro3.node.nodes.pose.PosePanel.class, com.marginallyclever.ro3.node.nodes.pose.poses.AttachmentPointPanel.class, com.marginallyclever.ro3.node.nodes.pose.poses.CameraPanel.class, diff --git a/src/main/java/com/marginallyclever/ro3/apps/editorpanel/EditorPanel.java b/src/main/java/com/marginallyclever/ro3/apps/editorpanel/EditorPanel.java index 11b76a09d..6d7a54215 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/editorpanel/EditorPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/editorpanel/EditorPanel.java @@ -59,7 +59,7 @@ public class EditorPanel extends App implements MarlinListener, PropertyChangeLi { putValue(Action.NAME, "Play"); putValue(Action.SHORT_DESCRIPTION, "Send the current line to the robot."); - putValue(Action.SMALL_ICON,new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-play-16.png")))); + putValue(Action.SMALL_ICON,new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png")))); } @Override diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index 0ace186a2..2483229c0 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -2,14 +2,12 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.App; -import com.marginallyclever.ro3.node.nodes.ode4j.ODESphere; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEBox; -import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; +import com.marginallyclever.ro3.node.nodes.ode4j.*; import javax.swing.*; import java.awt.*; import java.awt.event.ActionListener; +import java.util.Objects; /** * Actions in this window will control the contents of the {@link com.marginallyclever.ro3.Registry#scene}. @@ -21,25 +19,57 @@ public ODE4JPanel() { JToolBar toolbar = new JToolBar(); add(toolbar, BorderLayout.NORTH); - - // demo 1 - addButtonByNameAndCallback(toolbar, "Add Sphere", (e)->{ + JButton pauseButton = addButtonByNameAndCallback(toolbar, "", (e)->{ ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - ODE4JHelper.guaranteeFloor(physics); + physics.setPaused(!physics.isPaused()); + updatePauseButton((JButton)e.getSource(), physics); + }); + // I cannot call this here because the physics world has not been created yet. + // updatePauseButton(pauseButton, ODE4JHelper.guaranteePhysicsWorld()); + // The workaround is to manually set the button. Not pretty but it will have to do. + pauseButton.setToolTipText("Play"); + pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png"))) ); + + addButtonByNameAndCallback(toolbar, "+Floor", (e)->{ + ODE4JHelper.guaranteePhysicsWorld(); + Registry.getScene().addChild(new ODEPlane()); + }); + + addButtonByNameAndCallback(toolbar, "+Sphere", (e)->{ + ODE4JHelper.guaranteePhysicsWorld(); Registry.getScene().addChild(new ODESphere()); }); - // demo 2 - addButtonByNameAndCallback(toolbar, "Add Box", (e)->{ - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - ODE4JHelper.guaranteeFloor(physics); + addButtonByNameAndCallback(toolbar, "+Box", (e)->{ + ODE4JHelper.guaranteePhysicsWorld(); Registry.getScene().addChild(new ODEBox()); }); + + addButtonByNameAndCallback(toolbar, "+Cylinder", (e)->{ + ODE4JHelper.guaranteePhysicsWorld(); + Registry.getScene().addChild(new ODECylinder()); + }); + + addButtonByNameAndCallback(toolbar, "+Capsule", (e)->{ + ODE4JHelper.guaranteePhysicsWorld(); + Registry.getScene().addChild(new ODECapsule()); + }); } - private void addButtonByNameAndCallback(JToolBar toolbar, String title, ActionListener actionListener) { + private JButton addButtonByNameAndCallback(JToolBar toolbar, String title, ActionListener actionListener) { JButton button = new JButton(title); button.addActionListener(actionListener); toolbar.add(button); + return button; + } + + private void updatePauseButton(JButton pauseButton, ODEWorldSpace worldSpace) { + if (worldSpace.isPaused()) { + pauseButton.setToolTipText("Unpause"); + pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png")))); + } else { + pauseButton.setToolTipText("Pause"); + pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-pause-16.png")))); + } } } diff --git a/src/main/java/com/marginallyclever/ro3/apps/viewport/OpenGLPanel.java b/src/main/java/com/marginallyclever/ro3/apps/viewport/OpenGLPanel.java index e0afed411..77d894955 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/viewport/OpenGLPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/viewport/OpenGLPanel.java @@ -121,6 +121,7 @@ public void init(GLAutoDrawable glAutoDrawable) { gl3.glEnable(GL3.GL_LINE_SMOOTH); gl3.glEnable(GL3.GL_POLYGON_SMOOTH); gl3.glHint(GL3.GL_POLYGON_SMOOTH_HINT, GL3.GL_NICEST); + gl3.glEnable(GL3.GL_MULTISAMPLE); // depth testing and culling options gl3.glEnable(GL3.GL_DEPTH_TEST); gl3.glDepthFunc(GL3.GL_LESS); diff --git a/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawBackground.java b/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawBackground.java index 9d8ca337f..0b02a96b9 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawBackground.java +++ b/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawBackground.java @@ -168,16 +168,13 @@ private void drawSkybox(GL3 gl3, Camera camera) { shader.set1i(gl3,"useLighting",0); shader.set1i(gl3,"diffuseTexture",0); shader.set1i(gl3,"useTexture",1); - gl3.glDisable(GL3.GL_CULL_FACE); - gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_S, GL3.GL_CLAMP_TO_EDGE); - gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_T, GL3.GL_CLAMP_TO_EDGE); shader.setMatrix4d(gl3,"modelMatrix",MatrixHelper.createIdentityMatrix4()); texture.use(shader); + gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_S, GL3.GL_CLAMP_TO_EDGE); + gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_T, GL3.GL_CLAMP_TO_EDGE); + gl3.glDisable(GL3.GL_CULL_FACE); mesh.render(gl3); - - gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_S, GL3.GL_REPEAT); - gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_T, GL3.GL_REPEAT); gl3.glEnable(GL3.GL_CULL_FACE); } diff --git a/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java b/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java index 26aa0d24a..336f87c45 100644 --- a/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java +++ b/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java @@ -7,8 +7,9 @@ import javax.vecmath.Vector3d; /** - *

{@link Decal} is a {@link Mesh}. It is a 1x1 quad texture on both sides. The origin is in the center of the - * quad.

+ *

{@link Decal} is a {@link Mesh}. It is a width x height quad in the XY plane centered on the local origin. + * The one-sided version only faces +Z. + *

*/ public class Decal extends Mesh { public double height = 1; @@ -24,16 +25,38 @@ public Decal() { * Procedurally generate a list of triangles that form a box, subdivided by some * amount. */ - protected void updateModel() { - this.clear(); - this.setRenderStyle(GL3.GL_TRIANGLES); - // model.renderStyle=GL3.GL_LINES; // set to see the wireframe + public void updateModel() { + clear(); + setRenderStyle(GL3.GL_TRIANGLES); + //createTwoSidedDecal(); + createOneSidedDecal(); + } - float w = (float)width; - float h = (float)height; + /** + * Create a rectangle in the XY plane, facing +Z. + */ + private void createOneSidedDecal() { + int wParts = (int) (width ); + int hParts = (int) (height); - int wParts = (int) (w / 4f) * 2; - int hParts = (int) (h / 4f) * 2; + Vector3d n = new Vector3d(); + Vector3d p0 = new Vector3d(); + Vector3d p1 = new Vector3d(); + Vector3d p2 = new Vector3d(); + Vector3d p3 = new Vector3d(); + + // face + n.set(0, 0, 1); + p0.set( width/2.0f, height/2.0f, 0); + p1.set(-width/2.0f, height/2.0f, 0); + p2.set(-width/2.0f, -height/2.0f, 0); + p3.set( width/2.0f, -height/2.0f, 0); + addSubdividedPlane(n, p0, p1, p2, p3, wParts, hParts); + } + + private void createTwoSidedDecal() { + int wParts = (int) (width); + int hParts = (int) (height); Vector3d n = new Vector3d(); Vector3d p0 = new Vector3d(); @@ -43,18 +66,18 @@ protected void updateModel() { // bottom n.set(0, 0, -1); - p0.set(-w, h, -0.01); - p1.set(w, h, -0.01); - p2.set(w, -h, -0.01); - p3.set(-w, -h, -0.01); + p0.set(-width/2.0f, height/2.0f, -0.01); + p1.set( width/2.0f, height/2.0f, -0.01); + p2.set( width/2.0f, -height/2.0f, -0.01); + p3.set(-width/2.0f, -height/2.0f, -0.01); addSubdividedPlane(n, p0, p1, p2, p3, wParts, hParts); // top n.set(0, 0, 1); - p0.set(w, h, 0.01); - p1.set(-w, h, 0.01); - p2.set(-w, -h, 0.01); - p3.set(w, -h, 0.01); + p0.set( width/2.0f, height/2.0f, 0.01); + p1.set(-width/2.0f, height/2.0f, 0.01); + p2.set(-width/2.0f, -height/2.0f, 0.01); + p3.set( width/2.0f, -height/2.0f, 0.01); addSubdividedPlane(n, p0, p1, p2, p3, wParts, hParts); } @@ -100,39 +123,27 @@ protected void addSubdividedPlane(Vector3d n, pG.set(MathHelper.interpolate(pA, pC, (double) (y + 1) / (double) yParts)); pH.set(MathHelper.interpolate(pB, pD, (double) (y + 1) / (double) yParts)); - if (this.getRenderStyle() == GL3.GL_TRIANGLES) { - for (int j = 0; j < 6; ++j) { - this.addNormal((float) n.x, (float) n.y, (float) n.z); - this.addColor(1, 1, 1, 1); - } - - this.addVertex((float) pE.x, (float) pE.y, (float) pE.z); - this.addVertex((float) pF.x, (float) pF.y, (float) pF.z); - this.addVertex((float) pH.x, (float) pH.y, (float) pH.z); - - this.addVertex((float) pE.x, (float) pE.y, (float) pE.z); - this.addVertex((float) pH.x, (float) pH.y, (float) pH.z); - this.addVertex((float) pG.x, (float) pG.y, (float) pG.z); - } else if (this.getRenderStyle() == GL3.GL_LINES) { - for (int j = 0; j < 8; ++j) { - this.addNormal((float) n.x, (float) n.y, (float) n.z); - this.addColor(1, 1, 1, 1); - } - - this.addVertex((float) pF.x, (float) pF.y, (float) pF.z); - this.addVertex((float) pH.x, (float) pH.y, (float) pH.z); + if (getRenderStyle() == GL3.GL_TRIANGLES) { + addVertex((float) pE.x, (float) pE.y, (float) pE.z); + addVertex((float) pF.x, (float) pF.y, (float) pF.z); + addVertex((float) pH.x, (float) pH.y, (float) pH.z); - this.addVertex((float) pH.x, (float) pH.y, (float) pH.z); - this.addVertex((float) pE.x, (float) pE.y, (float) pE.z); - - this.addVertex((float) pH.x, (float) pH.y, (float) pH.z); - this.addVertex((float) pG.x, (float) pG.y, (float) pG.z); - - this.addVertex((float) pG.x, (float) pG.y, (float) pG.z); - this.addVertex((float) pE.x, (float) pE.y, (float) pE.z); + addVertex((float) pE.x, (float) pE.y, (float) pE.z); + addVertex((float) pH.x, (float) pH.y, (float) pH.z); + addVertex((float) pG.x, (float) pG.y, (float) pG.z); } } } + + for(int i=0;i dhParameter.setAlpha( ((Number)dh_alpha.getValue()).doubleValue() )); dh_theta.addPropertyChangeListener("value", e -> dhParameter.setTheta( ((Number)dh_theta.getValue()).doubleValue() )); - this.setLayout(new GridLayout(0,2)); - PanelHelper.addLabelAndComponent(this,"d",dh_d); PanelHelper.addLabelAndComponent(this,"theta",dh_theta); PanelHelper.addLabelAndComponent(this,"r",dh_r); @@ -53,6 +51,5 @@ public DHParameterPanel(DHParameter dhParameter) { this.add(fromPose); this.add(toPose); - } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index 518e124a8..ee4c444a9 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -1,6 +1,7 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.math.DMatrix3; import org.ode4j.math.DMatrix3C; @@ -50,20 +51,11 @@ static Matrix4d assembleMatrix(DVector3C translation, DMatrix3C rotation) { * @return the rotation component. */ public static DMatrix3C convertRotationToODE(Matrix4d mat) { - DMatrix3C rotation = new DMatrix3( + return new DMatrix3( mat.m00, mat.m01, mat.m02, mat.m10, mat.m11, mat.m12, mat.m20, mat.m21, mat.m22 ); - return rotation; - } - - public static void guaranteeFloor(ODEWorldSpace physics) { - MeshInstance floorNode = (MeshInstance) Registry.getScene().findChild("Floor"); - if(floorNode==null) { - logger.debug("Creating floor"); - Registry.getScene().addChild(new ODEPlane()); - } } public static ODEWorldSpace guaranteePhysicsWorld() { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java index 6626886aa..8edf106ef 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java @@ -22,7 +22,7 @@ */ public class ODEBox extends Pose { private static final double CUBE_SIDE_LENGTH = 5.0; - private static final double CUBE_MASS = 23.0; + private static final double CUBE_MASS = Math.sqrt(CUBE_SIDE_LENGTH*CUBE_SIDE_LENGTH*CUBE_SIDE_LENGTH); private DBody body; private DGeom geom; @@ -50,6 +50,7 @@ protected void onAttach() { body.setMass(mass); body.setPosition(0, 0, CUBE_SIDE_LENGTH * 5); + // set a random orientation Matrix4d rx = new Matrix4d(); Matrix4d ry = new Matrix4d(); rx.rotX(Math.toRadians(Math.random()*90)); @@ -59,12 +60,12 @@ protected void onAttach() { body.setRotation(ODE4JHelper.convertRotationToODE(mat)); // add a Node with a MeshInstance to represent the cube. - MeshInstance cubeMesh = new MeshInstance(); - addChild(cubeMesh); - cubeMesh.setMesh(new Box()); - mat = cubeMesh.getLocal(); + MeshInstance meshInstance = new MeshInstance(); + addChild(meshInstance); + meshInstance.setMesh(new Box()); + mat = meshInstance.getLocal(); mat.setScale(CUBE_SIDE_LENGTH); - cubeMesh.setLocal(mat); + meshInstance.setLocal(mat); // add a Material with random diffuse color Material material = new Material(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java new file mode 100644 index 000000000..aa487dbf8 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java @@ -0,0 +1,139 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.mesh.shapes.Cylinder; +import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3; +import org.ode4j.math.DVector3C; +import org.ode4j.ode.DBody; +import org.ode4j.ode.DGeom; +import org.ode4j.ode.DMass; +import org.ode4j.ode.OdeHelper; + +import javax.swing.*; +import javax.vecmath.Matrix4d; +import javax.vecmath.Vector3d; +import java.awt.*; +import java.util.Objects; + +/** + * Wrapper for a ODE4J capsule. + */ +public class ODECapsule extends Pose { + private static final double CAPSULE_RADIUS = 2.5; + private static final double CAPSULE_LENGTH = 5.0; + private static final double CAPSULE_MASS = Math.PI*CAPSULE_RADIUS*CAPSULE_RADIUS*CAPSULE_LENGTH; + + private DBody body; + private DGeom geom; + + public ODECapsule() { + this("ODE Capsule"); + } + + public ODECapsule(String name) { + super(name); + } + + @Override + protected void onAttach() { + super.onAttach(); + + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + body = OdeHelper.createBody(physics.getODEWorld()); + geom = OdeHelper.createCapsule(physics.getODESpace(),CAPSULE_RADIUS, CAPSULE_LENGTH); + geom.setBody(body); + + DMass mass = OdeHelper.createMass(); + mass.setCapsuleTotal(CAPSULE_MASS, 3, CAPSULE_RADIUS, CAPSULE_LENGTH); + body.setMass(mass); + body.setPosition(0, 0, CAPSULE_LENGTH * 5); + + // set a random orientation + Matrix4d rx = new Matrix4d(); + Matrix4d ry = new Matrix4d(); + rx.rotX(Math.toRadians(Math.random()*90)); + ry.rotY(Math.toRadians(Math.random()*90)); + Matrix4d mat = new Matrix4d(); + mat.mul(ry, rx); + body.setRotation(ODE4JHelper.convertRotationToODE(mat)); + + Pose cylinder = new Pose("Cylinder"); + // add a Node with a MeshInstance to represent the ball. + MeshInstance meshInstance = new MeshInstance(); + meshInstance.setMesh(new Cylinder(CAPSULE_LENGTH, CAPSULE_RADIUS, CAPSULE_RADIUS)); + cylinder.addChild(meshInstance); + addChild(cylinder); + + Pose b1 = new Pose("Ball1"); + meshInstance = new MeshInstance(); + meshInstance.setMesh(new Sphere((float)CAPSULE_RADIUS)); + b1.addChild(meshInstance); + b1.setPosition(new Vector3d(0, 0, (float)CAPSULE_LENGTH/2)); + addChild(b1); + + Pose b2 = new Pose("Ball2"); + meshInstance = new MeshInstance(); + meshInstance.setMesh(new Sphere((float)CAPSULE_RADIUS)); + b2.addChild(meshInstance); + b2.setPosition(new Vector3d(0, 0, -(float)CAPSULE_LENGTH/2)); + addChild(b2); + + // add a Material with random diffuse color + Material material = new Material(); + material.setDiffuseColor(new Color( + (int)(Math.random()*255.0), + (int)(Math.random()*255.0), + (int)(Math.random()*255.0))); + + cylinder.addChild(material); + b1.addChild(material); + b2.addChild(material); + } + + @Override + protected void onDetach() { + super.onDetach(); + if(body != null) { + body.destroy(); + body = null; + } + if(geom != null) { + geom.destroy(); + geom = null; + } + } + + @Override + public void update(double dt) { + super.update(dt); + + // adjust the position of the Node to match the body. + if(body == null) return; + + DVector3C translation = body.getPosition(); + DMatrix3C rotation = body.getRotation(); + super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); + } + + @Override + public void setWorld(Matrix4d world) { + super.setWorld(world); + if(body == null) return; + + body.setPosition(world.m03, world.m13, world.m23); + body.setRotation(ODE4JHelper.convertRotationToODE(world)); + // stop movement so object does not fight user. + body.setAngularVel(new DVector3(0, 0, 0)); + body.setLinearVel(new DVector3(0, 0, 0)); + } + + @Override + public Icon getIcon() { + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java new file mode 100644 index 000000000..27b197cea --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java @@ -0,0 +1,118 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.mesh.shapes.Cylinder; +import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3; +import org.ode4j.math.DVector3C; +import org.ode4j.ode.DBody; +import org.ode4j.ode.DGeom; +import org.ode4j.ode.DMass; +import org.ode4j.ode.OdeHelper; + +import javax.swing.*; +import javax.vecmath.Matrix4d; +import java.awt.*; +import java.util.Objects; + +/** + * Wrapper for a ODE4J cylinder. + */ +public class ODECylinder extends Pose { + private static final double CYLINDER_RADIUS = 2.5; + private static final double CYLINDER_LENGTH = 5.0; + private static final double CYLINDER_MASS = Math.PI*CYLINDER_RADIUS*CYLINDER_RADIUS*CYLINDER_LENGTH; + + private DBody body; + private DGeom geom; + + public ODECylinder() { + this("ODE Cylinder"); + } + + public ODECylinder(String name) { + super(name); + } + + @Override + protected void onAttach() { + super.onAttach(); + + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + body = OdeHelper.createBody(physics.getODEWorld()); + geom = OdeHelper.createCylinder(physics.getODESpace(),CYLINDER_RADIUS, CYLINDER_LENGTH); + geom.setBody(body); + + DMass mass = OdeHelper.createMass(); + mass.setCylinderTotal(CYLINDER_MASS, 3, CYLINDER_RADIUS, CYLINDER_LENGTH); + body.setMass(mass); + body.setPosition(0, 0, CYLINDER_LENGTH * 5); + + // set a random orientation + Matrix4d rx = new Matrix4d(); + Matrix4d ry = new Matrix4d(); + rx.rotX(Math.toRadians(Math.random()*90)); + ry.rotY(Math.toRadians(Math.random()*90)); + Matrix4d mat = new Matrix4d(); + mat.mul(ry, rx); + body.setRotation(ODE4JHelper.convertRotationToODE(mat)); + + // add a Node with a MeshInstance to represent the ball. + MeshInstance meshInstance = new MeshInstance(); + meshInstance.setMesh(new Cylinder(CYLINDER_LENGTH, CYLINDER_RADIUS, CYLINDER_RADIUS)); + addChild(meshInstance); + + // add a Material with random diffuse color + Material material = new Material(); + material.setDiffuseColor(new Color( + (int)(Math.random()*255.0), + (int)(Math.random()*255.0), + (int)(Math.random()*255.0))); + addChild(material); + } + + @Override + protected void onDetach() { + super.onDetach(); + if(body != null) { + body.destroy(); + body = null; + } + if(geom != null) { + geom.destroy(); + geom = null; + } + } + + @Override + public void update(double dt) { + super.update(dt); + + // adjust the position of the Node to match the body. + if(body == null) return; + + DVector3C translation = body.getPosition(); + DMatrix3C rotation = body.getRotation(); + super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); + } + + @Override + public void setWorld(Matrix4d world) { + super.setWorld(world); + if(body == null) return; + + body.setPosition(world.m03, world.m13, world.m23); + body.setRotation(ODE4JHelper.convertRotationToODE(world)); + // stop movement so object does not fight user. + body.setAngularVel(new DVector3(0, 0, 0)); + body.setLinearVel(new DVector3(0, 0, 0)); + } + + @Override + public Icon getIcon() { + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index a7d17f5ba..4319eaae4 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -1,10 +1,13 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.convenience.helpers.MatrixHelper; +import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.mesh.shapes.Decal; import com.marginallyclever.ro3.mesh.shapes.Grid; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import com.marginallyclever.ro3.texture.TextureFactory; import org.ode4j.ode.DPlane; import org.ode4j.ode.OdeHelper; @@ -38,9 +41,15 @@ protected void onAttach() { // add a Node with a MeshInstance to represent the floor. MeshInstance mesh = new MeshInstance(); addChild(mesh); - mesh.setMesh(new Grid()); - - addChild(new Material()); + Decal decal = new Decal(); + decal.width = 100; + decal.height = 100; + decal.updateModel(); + mesh.setMesh(decal); + + Material material = new Material(); + addChild(material); + material.setTexture(Registry.textureFactory.load("/com/marginallyclever/ro3/shared/checkerboard.png")); } @Override diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java index 1ad4cfea3..cd64c172a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java @@ -22,8 +22,8 @@ * Wrapper for a ODE4J Sphere. */ public class ODESphere extends Pose { - private static final double BALL_RADIUS = 3.0; - private static final double BALL_MASS = 23.0; + private static final double BALL_RADIUS = 2.5; + private static final double BALL_MASS = BALL_RADIUS*5; private DBody body; private DGeom geom; @@ -48,15 +48,15 @@ protected void onAttach() { DMass mass = OdeHelper.createMass(); mass.setSphereTotal(BALL_MASS, BALL_RADIUS); body.setMass(mass); - body.setPosition(0, 0, BALL_RADIUS * 5); + body.setPosition(0, 0, BALL_RADIUS * 2 * 5); // add a Node with a MeshInstance to represent the ball. - MeshInstance ballMesh = new MeshInstance(); - addChild(ballMesh); - ballMesh.setMesh(new Sphere()); - Matrix4d m = ballMesh.getLocal(); + MeshInstance meshInstance = new MeshInstance(); + addChild(meshInstance); + meshInstance.setMesh(new Sphere()); + Matrix4d m = meshInstance.getLocal(); m.setScale(BALL_RADIUS); - ballMesh.setLocal(m); + meshInstance.setLocal(m); // add a Material with random diffuse color Material material = new Material(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java index 69ba32c3d..bbb9692d5 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java @@ -2,11 +2,13 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.MaterialPanel; import org.ode4j.ode.*; import org.slf4j.Logger; import org.slf4j.LoggerFactory; import javax.swing.*; +import java.util.List; import java.util.Objects; import static org.ode4j.ode.OdeConstants.*; @@ -29,6 +31,7 @@ public class ODEWorldSpace extends Node { private DSpace space; private DContactBuffer contacts; private DJointGroup contactGroup; + private boolean isPaused = true; public ODEWorldSpace() { this("PhysicsWorld"); @@ -38,6 +41,12 @@ public ODEWorldSpace(String name) { super(name); } + @Override + public void getComponents(List list) { + list.add(new ODEWorldSpacePanel(this)); + super.getComponents(list); + } + @Override protected void onAttach() { super.onAttach(); @@ -110,6 +119,8 @@ public DSpace getODESpace() { public void update(double dt) { super.update(dt); + if(isPaused) return; + try { OdeHelper.spaceCollide(getODESpace(), null, this::nearCallback); world.step(dt); @@ -156,4 +167,12 @@ private void nearCallback(Object data, DGeom o1, DGeom o2) { public Icon getIcon() { return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); } + + public boolean isPaused() { + return isPaused; + } + + public void setPaused(boolean state) { + isPaused = state; + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpacePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpacePanel.java new file mode 100644 index 000000000..557dd7418 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpacePanel.java @@ -0,0 +1,46 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.PanelHelper; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +import javax.swing.*; +import java.awt.*; +import java.util.Objects; + +/** + * Manages the ODE4J physics world, space, and contact handling. There must be exactly one of these in the scene + * for physics to work. + */ +public class ODEWorldSpacePanel extends JPanel { + private static final Logger logger = LoggerFactory.getLogger(ODEWorldSpacePanel.class); + + public ODEWorldSpacePanel() { + this(new ODEWorldSpace()); + } + + public ODEWorldSpacePanel(ODEWorldSpace worldSpace) { + super(new GridLayout(0,2)); + this.setName(ODEWorldSpace.class.getSimpleName()); + + // toggle button to pause/unpause the simulation + JButton pauseButton = new JButton(); + pauseButton.addActionListener(e -> { + worldSpace.setPaused(!worldSpace.isPaused()); + updatePauseButton(pauseButton,worldSpace); + }); + updatePauseButton(pauseButton,worldSpace); + + PanelHelper.addLabelAndComponent(this,"Active",pauseButton); + } + + private void updatePauseButton(JButton pauseButton, ODEWorldSpace worldSpace) { + if (worldSpace.isPaused()) { + pauseButton.setToolTipText("Play"); + pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png")))); + } else { + pauseButton.setToolTipText("Pause"); + pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-pause-16.png")))); + } + } +} diff --git a/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java b/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java index e11616c47..ac90d30b9 100644 --- a/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java +++ b/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java @@ -63,6 +63,17 @@ public void use(ShaderProgram shader) { shader.set1i(gl3,"useTexture",1); shader.set1i(gl3,"diffuseTexture",0); } + + // turn on texture wrapping + gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_S, GL3.GL_REPEAT); + gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_T, GL3.GL_REPEAT); + // turn on mipmapping + //gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_MIN_FILTER, GL3.GL_LINEAR_MIPMAP_LINEAR); + //gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_MAG_FILTER, GL3.GL_LINEAR); + // turn on anisotropic filtering + float[] maxAnisotropy = new float[1]; + gl3.glGetFloatv(GL3.GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT, maxAnisotropy, 0); + gl3.glTexParameterf(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_MAX_ANISOTROPY_EXT, maxAnisotropy[0]); } /** diff --git a/src/main/resources/com/marginallyclever/ro3/shared/checkerboard.png b/src/main/resources/com/marginallyclever/ro3/shared/checkerboard.png new file mode 100644 index 0000000000000000000000000000000000000000..3fb48dc8e92d564bd9a5cca58b385b2684b88b5b GIT binary patch literal 576 zcmV-G0>AxEX>4Tx04R}tkv&MmKpe$izo!6G6K8LE>-Q4vR}Vi7EqwnD28CYOFelZGV4 z#ZhoAIQX$xb#QUk)xlK|1V2EW9h?+hq{ROvg%&X$9QWhhy~o`JF#-g4fo9#ZzK<=dc>?&Jfh)D`uQq_$Ptxmc zEpi0(ZUYzBZB5z(E_Z;zCr#8vTk_HL77D=o8GTa@=)VQJ*PPy3`#607GSt=b4RCM> zj20<--R0d~oxS~grq$mMe;{(KBCW7;00009a7bBm001r{001r{0eGc9b^rhX2XskI zMF;2v77zy!kLHMp0000PbVXQnLvL+uWo~o;Lvm$dbY)~9cWHEJAV*0}P*;Ht7XSbN zDoI2^R4C75?C9uVzy`|8%dv_xF^~vGH4p Date: Mon, 22 Apr 2024 14:37:38 -0700 Subject: [PATCH 06/52] Update pom.xml --- pom.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pom.xml b/pom.xml index aec770524..df04a962d 100644 --- a/pom.xml +++ b/pom.xml @@ -481,7 +481,7 @@ org.ode4j core - 0.5.3a-SNAPSHOT + 0.5.3-SNAPSHOT From 6d38d7753917cecd1ea6978160dcfdf1cd7f6a13 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 23 Apr 2024 08:55:49 -0700 Subject: [PATCH 07/52] fixed new scene causes exception in DBody.destroy() --- .../com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java | 4 +++- .../com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java | 4 +++- .../marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java | 4 +++- .../com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java | 4 +++- .../com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java | 4 +++- 5 files changed, 15 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java index 8edf106ef..95d4b0bc6 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java @@ -80,7 +80,9 @@ protected void onAttach() { protected void onDetach() { super.onDetach(); if(body != null) { - body.destroy(); + try { + body.destroy(); + } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. body = null; } if(geom != null) { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java index aa487dbf8..8930dce15 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java @@ -99,7 +99,9 @@ protected void onAttach() { protected void onDetach() { super.onDetach(); if(body != null) { - body.destroy(); + try { + body.destroy(); + } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. body = null; } if(geom != null) { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java index 27b197cea..07aa16049 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java @@ -78,7 +78,9 @@ protected void onAttach() { protected void onDetach() { super.onDetach(); if(body != null) { - body.destroy(); + try { + body.destroy(); + } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. body = null; } if(geom != null) { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index 4319eaae4..cca35c0d5 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -56,7 +56,9 @@ protected void onAttach() { protected void onDetach() { super.onDetach(); if(plane!=null) { - plane.destroy(); + try { + plane.destroy(); + } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. plane = null; } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java index cd64c172a..7530e5c80 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java @@ -71,7 +71,9 @@ protected void onAttach() { protected void onDetach() { super.onDetach(); if(body != null) { - body.destroy(); + try { + body.destroy(); + } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. body = null; } if(geom != null) { From 7eb4c72069ae2263bdc103a12fe607eb1a3d0630 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 23 Apr 2024 11:01:34 -0700 Subject: [PATCH 08/52] created ODEBody as common parent --- .../ro3/apps/ode4j/ODE4JPanel.java | 37 ++++++- .../ro3/node/nodes/ode4j/ODEBody.java | 81 ++++++++++++++ .../ro3/node/nodes/ode4j/ODEBox.java | 82 ++------------ .../ro3/node/nodes/ode4j/ODECapsule.java | 103 +++--------------- .../ro3/node/nodes/ode4j/ODECylinder.java | 81 ++------------ .../ro3/node/nodes/ode4j/ODESphere.java | 101 +++++------------ .../ro3/node/nodes/ode4j/ODESpherePanel.java | 26 +++++ .../ro3/node/nodes/ode4j/ODEWorldSpace.java | 31 +++--- 8 files changed, 213 insertions(+), 329 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESpherePanel.java diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index 2483229c0..425fe64ca 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -1,10 +1,15 @@ package com.marginallyclever.ro3.apps.ode4j; +import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.App; +import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.*; +import com.marginallyclever.ro3.node.nodes.pose.Pose; import javax.swing.*; +import javax.vecmath.Matrix4d; +import javax.vecmath.Vector3d; import java.awt.*; import java.awt.event.ActionListener; import java.util.Objects; @@ -37,25 +42,49 @@ public ODE4JPanel() { addButtonByNameAndCallback(toolbar, "+Sphere", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); - Registry.getScene().addChild(new ODESphere()); + add(new ODESphere()); }); addButtonByNameAndCallback(toolbar, "+Box", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); - Registry.getScene().addChild(new ODEBox()); + add(new ODEBox()); }); addButtonByNameAndCallback(toolbar, "+Cylinder", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); - Registry.getScene().addChild(new ODECylinder()); + add(new ODECylinder()); }); addButtonByNameAndCallback(toolbar, "+Capsule", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); - Registry.getScene().addChild(new ODECapsule()); + add(new ODECapsule()); }); } + private void add(ODEBody body) { + Registry.getScene().addChild(body); + placeBodyAbovePlane(body); + } + + private void placeBodyAbovePlane(Pose body) { + // set a random orientation + double x = Math.random()*90; + double y = Math.random()*90; + double z = Math.random()*90; + Matrix4d m = new Matrix4d(); + m.set(MatrixHelper.eulerToMatrix(new Vector3d(x,y,z), MatrixHelper.EulerSequence.XYZ)); + m.setTranslation(new Vector3d(0, 0, 15)); + body.setWorld(m); + + Material material = body.findFirstChild(Material.class); + if(material!=null) { + material.setDiffuseColor(new Color( + (int) (Math.random() * 255.0), + (int) (Math.random() * 255.0), + (int) (Math.random() * 255.0))); + } + } + private JButton addButtonByNameAndCallback(JToolBar toolbar, String title, ActionListener actionListener) { JButton button = new JButton(title); button.addActionListener(actionListener); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java new file mode 100644 index 000000000..fe343bd31 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java @@ -0,0 +1,81 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3; +import org.ode4j.math.DVector3C; +import org.ode4j.ode.DBody; +import org.ode4j.ode.DGeom; +import org.ode4j.ode.DMass; +import org.ode4j.ode.OdeHelper; + +import javax.swing.*; +import javax.vecmath.Matrix4d; +import java.util.Objects; + +public abstract class ODEBody extends Pose { + protected DBody body; + protected DGeom geom; + protected DMass mass; + + + public ODEBody() { + this("ODE Body"); + } + + public ODEBody(String name) { + super(name); + } + + @Override + protected void onAttach() { + super.onAttach(); + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + body = OdeHelper.createBody(physics.getODEWorld()); + mass = OdeHelper.createMass(); + } + + @Override + protected void onDetach() { + super.onDetach(); + if(body != null) { + try { + body.destroy(); + } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. + body = null; + } + if(geom != null) { + geom.destroy(); + geom = null; + } + } + + @Override + public void update(double dt) { + super.update(dt); + + // adjust the position of the Node to match the body. + if(body == null) return; + + DVector3C translation = body.getPosition(); + DMatrix3C rotation = body.getRotation(); + super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); + } + + @Override + public void setWorld(Matrix4d world) { + super.setWorld(world); + if(body == null) return; + + body.setPosition(world.m03, world.m13, world.m23); + body.setRotation(ODE4JHelper.convertRotationToODE(world)); + // stop movement so object does not fight user. + body.setAngularVel(new DVector3(0, 0, 0)); + body.setLinearVel(new DVector3(0, 0, 0)); + } + + @Override + public Icon getIcon() { + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java index 95d4b0bc6..a8ba5e6ed 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java @@ -20,12 +20,9 @@ /** * Wrapper for a ODE4J Box. */ -public class ODEBox extends Pose { - private static final double CUBE_SIDE_LENGTH = 5.0; - private static final double CUBE_MASS = Math.sqrt(CUBE_SIDE_LENGTH*CUBE_SIDE_LENGTH*CUBE_SIDE_LENGTH); - - private DBody body; - private DGeom geom; +public class ODEBox extends ODEBody { + private double sizeX=5.0, sizeY=5.0, sizeZ=5.0; + private double massQty = Math.sqrt(sizeX*sizeY*sizeZ); public ODEBox() { this("ODE Box"); @@ -41,82 +38,17 @@ protected void onAttach() { ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); // add scene elements - body = OdeHelper.createBody(physics.getODEWorld()); - geom = createBox(physics.getODESpace(), CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); + geom = createBox(physics.getODESpace(), sizeX, sizeY, sizeZ); geom.setBody(body); - DMass mass = OdeHelper.createMass(); - mass.setBoxTotal(CUBE_MASS, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH, CUBE_SIDE_LENGTH); + mass.setBoxTotal(massQty, sizeX, sizeY, sizeZ); body.setMass(mass); - body.setPosition(0, 0, CUBE_SIDE_LENGTH * 5); - - // set a random orientation - Matrix4d rx = new Matrix4d(); - Matrix4d ry = new Matrix4d(); - rx.rotX(Math.toRadians(Math.random()*90)); - ry.rotY(Math.toRadians(Math.random()*90)); - Matrix4d mat = new Matrix4d(); - mat.mul(ry, rx); - body.setRotation(ODE4JHelper.convertRotationToODE(mat)); // add a Node with a MeshInstance to represent the cube. MeshInstance meshInstance = new MeshInstance(); + meshInstance.setMesh(new Box(sizeX,sizeY,sizeZ)); addChild(meshInstance); - meshInstance.setMesh(new Box()); - mat = meshInstance.getLocal(); - mat.setScale(CUBE_SIDE_LENGTH); - meshInstance.setLocal(mat); - - // add a Material with random diffuse color - Material material = new Material(); - material.setDiffuseColor(new Color( - (int)(Math.random()*255.0), - (int)(Math.random()*255.0), - (int)(Math.random()*255.0))); - addChild(material); - } - - @Override - protected void onDetach() { - super.onDetach(); - if(body != null) { - try { - body.destroy(); - } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. - body = null; - } - if(geom != null) { - geom.destroy(); - geom = null; - } - } - - @Override - public void update(double dt) { - super.update(dt); - // adjust the position of the Node to match the body. - if(body == null) return; - - DVector3C translation = body.getPosition(); - DMatrix3C rotation = body.getRotation(); - super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); - } - - @Override - public void setWorld(Matrix4d world) { - super.setWorld(world); - if(body == null) return; - - body.setPosition(world.m03, world.m13, world.m23); - body.setRotation(ODE4JHelper.convertRotationToODE(world)); - // stop movement so object does not fight user. - body.setAngularVel(new DVector3(0, 0, 0)); - body.setLinearVel(new DVector3(0, 0, 0)); - } - - @Override - public Icon getIcon() { - return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + addChild(new Material()); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java index 8930dce15..a7e8a030e 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java @@ -2,34 +2,22 @@ import com.marginallyclever.ro3.mesh.shapes.Cylinder; import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; -import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3; -import org.ode4j.math.DVector3C; -import org.ode4j.ode.DBody; -import org.ode4j.ode.DGeom; -import org.ode4j.ode.DMass; import org.ode4j.ode.OdeHelper; -import javax.swing.*; import javax.vecmath.Matrix4d; import javax.vecmath.Vector3d; import java.awt.*; -import java.util.Objects; /** * Wrapper for a ODE4J capsule. */ -public class ODECapsule extends Pose { - private static final double CAPSULE_RADIUS = 2.5; - private static final double CAPSULE_LENGTH = 5.0; - private static final double CAPSULE_MASS = Math.PI*CAPSULE_RADIUS*CAPSULE_RADIUS*CAPSULE_LENGTH; - - private DBody body; - private DGeom geom; +public class ODECapsule extends ODEBody { + private double radius = 2.5; + private double length = 5.0; + private double massQty = Math.PI * radius * radius * length; public ODECapsule() { this("ODE Capsule"); @@ -44,98 +32,35 @@ protected void onAttach() { super.onAttach(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - body = OdeHelper.createBody(physics.getODEWorld()); - geom = OdeHelper.createCapsule(physics.getODESpace(),CAPSULE_RADIUS, CAPSULE_LENGTH); + geom = OdeHelper.createCapsule(physics.getODESpace(), radius, length); geom.setBody(body); - DMass mass = OdeHelper.createMass(); - mass.setCapsuleTotal(CAPSULE_MASS, 3, CAPSULE_RADIUS, CAPSULE_LENGTH); + mass.setCapsuleTotal(massQty, 3, radius, length); body.setMass(mass); - body.setPosition(0, 0, CAPSULE_LENGTH * 5); - - // set a random orientation - Matrix4d rx = new Matrix4d(); - Matrix4d ry = new Matrix4d(); - rx.rotX(Math.toRadians(Math.random()*90)); - ry.rotY(Math.toRadians(Math.random()*90)); - Matrix4d mat = new Matrix4d(); - mat.mul(ry, rx); - body.setRotation(ODE4JHelper.convertRotationToODE(mat)); - Pose cylinder = new Pose("Cylinder"); // add a Node with a MeshInstance to represent the ball. MeshInstance meshInstance = new MeshInstance(); - meshInstance.setMesh(new Cylinder(CAPSULE_LENGTH, CAPSULE_RADIUS, CAPSULE_RADIUS)); - cylinder.addChild(meshInstance); - addChild(cylinder); + meshInstance.setMesh(new Cylinder(length, radius, radius)); + addChild(meshInstance); Pose b1 = new Pose("Ball1"); meshInstance = new MeshInstance(); - meshInstance.setMesh(new Sphere((float)CAPSULE_RADIUS)); + meshInstance.setMesh(new Sphere((float) radius)); b1.addChild(meshInstance); - b1.setPosition(new Vector3d(0, 0, (float)CAPSULE_LENGTH/2)); + b1.setPosition(new Vector3d(0, 0, (float) length /2)); addChild(b1); Pose b2 = new Pose("Ball2"); meshInstance = new MeshInstance(); - meshInstance.setMesh(new Sphere((float)CAPSULE_RADIUS)); + meshInstance.setMesh(new Sphere((float) radius)); b2.addChild(meshInstance); - b2.setPosition(new Vector3d(0, 0, -(float)CAPSULE_LENGTH/2)); + b2.setPosition(new Vector3d(0, 0, -(float) length /2)); addChild(b2); - // add a Material with random diffuse color + // add a Material Material material = new Material(); - material.setDiffuseColor(new Color( - (int)(Math.random()*255.0), - (int)(Math.random()*255.0), - (int)(Math.random()*255.0))); - - cylinder.addChild(material); + addChild(material); b1.addChild(material); b2.addChild(material); } - - @Override - protected void onDetach() { - super.onDetach(); - if(body != null) { - try { - body.destroy(); - } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. - body = null; - } - if(geom != null) { - geom.destroy(); - geom = null; - } - } - - @Override - public void update(double dt) { - super.update(dt); - - // adjust the position of the Node to match the body. - if(body == null) return; - - DVector3C translation = body.getPosition(); - DMatrix3C rotation = body.getRotation(); - super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); - } - - @Override - public void setWorld(Matrix4d world) { - super.setWorld(world); - if(body == null) return; - - body.setPosition(world.m03, world.m13, world.m23); - body.setRotation(ODE4JHelper.convertRotationToODE(world)); - // stop movement so object does not fight user. - body.setAngularVel(new DVector3(0, 0, 0)); - body.setLinearVel(new DVector3(0, 0, 0)); - } - - @Override - public Icon getIcon() { - return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); - } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java index 07aa16049..345dc8e58 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java @@ -21,13 +21,10 @@ /** * Wrapper for a ODE4J cylinder. */ -public class ODECylinder extends Pose { - private static final double CYLINDER_RADIUS = 2.5; - private static final double CYLINDER_LENGTH = 5.0; - private static final double CYLINDER_MASS = Math.PI*CYLINDER_RADIUS*CYLINDER_RADIUS*CYLINDER_LENGTH; - - private DBody body; - private DGeom geom; +public class ODECylinder extends ODEBody { + private double radius = 2.5; + private double length = 5.0; + private double massQty = Math.PI * radius * radius * length; public ODECylinder() { this("ODE Cylinder"); @@ -42,79 +39,17 @@ protected void onAttach() { super.onAttach(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - body = OdeHelper.createBody(physics.getODEWorld()); - geom = OdeHelper.createCylinder(physics.getODESpace(),CYLINDER_RADIUS, CYLINDER_LENGTH); + geom = OdeHelper.createCylinder(physics.getODESpace(),radius, length); geom.setBody(body); - DMass mass = OdeHelper.createMass(); - mass.setCylinderTotal(CYLINDER_MASS, 3, CYLINDER_RADIUS, CYLINDER_LENGTH); + mass.setCylinderTotal(massQty, 3, radius, length); body.setMass(mass); - body.setPosition(0, 0, CYLINDER_LENGTH * 5); - - // set a random orientation - Matrix4d rx = new Matrix4d(); - Matrix4d ry = new Matrix4d(); - rx.rotX(Math.toRadians(Math.random()*90)); - ry.rotY(Math.toRadians(Math.random()*90)); - Matrix4d mat = new Matrix4d(); - mat.mul(ry, rx); - body.setRotation(ODE4JHelper.convertRotationToODE(mat)); // add a Node with a MeshInstance to represent the ball. MeshInstance meshInstance = new MeshInstance(); - meshInstance.setMesh(new Cylinder(CYLINDER_LENGTH, CYLINDER_RADIUS, CYLINDER_RADIUS)); + meshInstance.setMesh(new Cylinder(length, radius, radius)); addChild(meshInstance); - // add a Material with random diffuse color - Material material = new Material(); - material.setDiffuseColor(new Color( - (int)(Math.random()*255.0), - (int)(Math.random()*255.0), - (int)(Math.random()*255.0))); - addChild(material); - } - - @Override - protected void onDetach() { - super.onDetach(); - if(body != null) { - try { - body.destroy(); - } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. - body = null; - } - if(geom != null) { - geom.destroy(); - geom = null; - } - } - - @Override - public void update(double dt) { - super.update(dt); - - // adjust the position of the Node to match the body. - if(body == null) return; - - DVector3C translation = body.getPosition(); - DMatrix3C rotation = body.getRotation(); - super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); - } - - @Override - public void setWorld(Matrix4d world) { - super.setWorld(world); - if(body == null) return; - - body.setPosition(world.m03, world.m13, world.m23); - body.setRotation(ODE4JHelper.convertRotationToODE(world)); - // stop movement so object does not fight user. - body.setAngularVel(new DVector3(0, 0, 0)); - body.setLinearVel(new DVector3(0, 0, 0)); - } - - @Override - public Icon getIcon() { - return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + addChild(new Material()); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java index 7530e5c80..5fa35f524 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java @@ -1,32 +1,25 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.nodes.DHParameterPanel; import com.marginallyclever.ro3.node.nodes.Material; -import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; - -import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3; -import org.ode4j.math.DVector3C; -import org.ode4j.ode.*; +import org.ode4j.ode.DSphere; import javax.swing.*; import javax.vecmath.Matrix4d; import java.awt.*; -import java.util.Objects; +import java.util.List; import static org.ode4j.ode.OdeHelper.*; /** * Wrapper for a ODE4J Sphere. */ -public class ODESphere extends Pose { - private static final double BALL_RADIUS = 2.5; - private static final double BALL_MASS = BALL_RADIUS*5; - - private DBody body; - private DGeom geom; +public class ODESphere extends ODEBody { + private double radius = 2.5; + private double massQty = radius *5; public ODESphere() { this("ODE Sphere"); @@ -36,78 +29,42 @@ public ODESphere(String name) { super(name); } + @Override + public void getComponents(List list) { + list.add(new ODESpherePanel(this)); + super.getComponents(list); + } + @Override protected void onAttach() { super.onAttach(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - body = OdeHelper.createBody(physics.getODEWorld()); - geom = createSphere(physics.getODESpace(), BALL_RADIUS); + geom = createSphere(physics.getODESpace(), radius); geom.setBody(body); - DMass mass = OdeHelper.createMass(); - mass.setSphereTotal(BALL_MASS, BALL_RADIUS); - body.setMass(mass); - body.setPosition(0, 0, BALL_RADIUS * 2 * 5); - - // add a Node with a MeshInstance to represent the ball. - MeshInstance meshInstance = new MeshInstance(); - addChild(meshInstance); - meshInstance.setMesh(new Sphere()); - Matrix4d m = meshInstance.getLocal(); - m.setScale(BALL_RADIUS); - meshInstance.setLocal(m); - - // add a Material with random diffuse color - Material material = new Material(); - material.setDiffuseColor(new Color( - (int)(Math.random()*255.0), - (int)(Math.random()*255.0), - (int)(Math.random()*255.0))); - addChild(material); + addChild(new MeshInstance()); + addChild(new Material()); + setRadius(radius); } - @Override - protected void onDetach() { - super.onDetach(); - if(body != null) { - try { - body.destroy(); - } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. - body = null; - } - if(geom != null) { - geom.destroy(); - geom = null; - } + public double getRadius() { + return radius; } - @Override - public void update(double dt) { - super.update(dt); - - // adjust the position of the Node to match the body. - if(body == null) return; + public void setRadius(double radius) { + if(radius<=0) throw new IllegalArgumentException("Radius must be greater than zero."); + this.radius = radius; - DVector3C translation = body.getPosition(); - DMatrix3C rotation = body.getRotation(); - super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); - } + mass.setSphereTotal(massQty, radius); + body.setMass(mass); - @Override - public void setWorld(Matrix4d world) { - super.setWorld(world); - if(body == null) return; - - body.setPosition(world.m03, world.m13, world.m23); - body.setRotation(ODE4JHelper.convertRotationToODE(world)); - // stop movement so object does not fight user. - body.setAngularVel(new DVector3(0, 0, 0)); - body.setLinearVel(new DVector3(0, 0, 0)); - } + ((DSphere)geom).setRadius(radius); + geom.setBody(body); - @Override - public Icon getIcon() { - return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + var meshInstance = findFirstChild(MeshInstance.class); + if(meshInstance!=null) { + meshInstance.setMesh(new Sphere((float) radius)); + } } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESpherePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESpherePanel.java new file mode 100644 index 000000000..244750af6 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESpherePanel.java @@ -0,0 +1,26 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.swing.NumberFormatHelper; +import com.marginallyclever.ro3.PanelHelper; + +import javax.swing.*; +import java.awt.*; + +public class ODESpherePanel extends JPanel { + public ODESpherePanel() { + this(new ODESphere()); + } + + public ODESpherePanel(ODESphere sphere) { + super(new GridLayout(0,2)); + this.setName(ODESphere.class.getSimpleName()); + + var formatter = NumberFormatHelper.getNumberFormatter(); + formatter.setMinimum(0.001); + + JFormattedTextField radiusValue = new JFormattedTextField(formatter); + radiusValue.setValue(sphere.getRadius()); + radiusValue.addPropertyChangeListener("value", e -> sphere.setRadius( ((Number)radiusValue.getValue()).doubleValue() )); + PanelHelper.addLabelAndComponent(this,"Radius",radiusValue); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java index bbb9692d5..b15fe20cb 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java @@ -2,7 +2,6 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; -import com.marginallyclever.ro3.node.nodes.MaterialPanel; import org.ode4j.ode.*; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -21,11 +20,11 @@ public class ODEWorldSpace extends Node { private static final Logger logger = LoggerFactory.getLogger(ODEWorldSpace.class); - public static final double WORLD_CFM = 1e-5; - public static final double WORLD_ERP = 0.8; - public static final double WORLD_GRAVITY = -9.81; - private static final int ITERS = 20; - private final int N = 4; + public double WORLD_CFM = 1e-5; + public double WORLD_ERP = 0.8; + public double WORLD_GRAVITY = -9.81; + private int ITERS = 20; + private final int CONTACT_BUFFER_SIZE = 4; private DWorld world; private DSpace space; @@ -34,7 +33,7 @@ public class ODEWorldSpace extends Node { private boolean isPaused = true; public ODEWorldSpace() { - this("PhysicsWorld"); + this("ODEWorldSpace"); } public ODEWorldSpace(String name) { @@ -81,7 +80,7 @@ private void startPhysics() { space = OdeHelper.createSapSpace( null, DSapSpace.AXES.XYZ ); //space = OdeHelper.createSimpleSpace(); - contacts = new DContactBuffer(N); + contacts = new DContactBuffer(CONTACT_BUFFER_SIZE); if(contactGroup == null) { contactGroup = OdeHelper.createJointGroup(); @@ -141,19 +140,19 @@ private void nearCallback(Object data, DGeom o1, DGeom o2) { try { ODEWorldSpace physics = Registry.getScene().findFirstChild(ODEWorldSpace.class); - int n = OdeHelper.collide(o1, o2, N, contacts.getGeomBuffer()); + int n = OdeHelper.collide(o1, o2, CONTACT_BUFFER_SIZE, contacts.getGeomBuffer()); if (n > 0) { for (int i = 0; i < n; i++) { DContact contact = contacts.get(i); contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; - contact.surface.mu = 0.5; - contact.surface.slip1 = 0.0; - contact.surface.slip2 = 0.0; - contact.surface.soft_erp = 0.8; - contact.surface.soft_cfm = 0.01; - contact.surface.bounce = 0.9; - contact.surface.bounce_vel = 0.5; + contact.surface.mu = 0.5; // friction + contact.surface.slip1 = 0.0; // how much the contact surfaces can slide + contact.surface.slip2 = 0.0; // how much the contact surfaces can slide + contact.surface.soft_erp = 0.8; // how spongy the contact is + contact.surface.soft_cfm = 0.001; // how soft to make the contact + contact.surface.bounce = 0.9; // how much the contact surfaces can bounce + contact.surface.bounce_vel = 0.5; // how fast the contact surfaces can bounce DJoint contactJoint = OdeHelper.createContactJoint(physics.getODEWorld(), contactGroup, contact); contactJoint.attach(o1.getBody(), o2.getBody()); } From 3f7f2739786d719358a39e85c286838385a26088 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 23 Apr 2024 11:07:45 -0700 Subject: [PATCH 09/52] adjustable mass --- .../ro3/node/nodes/ode4j/ODEBody.java | 21 +++++++++++++++ .../ro3/node/nodes/ode4j/ODEBodyPanel.java | 26 +++++++++++++++++++ 2 files changed, 47 insertions(+) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java index fe343bd31..560ab0871 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java @@ -11,6 +11,7 @@ import javax.swing.*; import javax.vecmath.Matrix4d; +import java.util.List; import java.util.Objects; public abstract class ODEBody extends Pose { @@ -27,6 +28,12 @@ public ODEBody(String name) { super(name); } + @Override + public void getComponents(List list) { + list.add(new ODEBodyPanel(this)); + super.getComponents(list); + } + @Override protected void onAttach() { super.onAttach(); @@ -78,4 +85,18 @@ public void setWorld(Matrix4d world) { public Icon getIcon() { return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); } + + public double getMassQty() { + return mass.getMass(); + } + + /** + * + * @param massQty must be >= 0 + */ + public void setMassQty(double massQty) { + if(massQty<0) throw new IllegalArgumentException("Mass must be greater than zero."); + mass.setMass(massQty); + body.setMass(mass); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java new file mode 100644 index 000000000..9ddda3445 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java @@ -0,0 +1,26 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.swing.NumberFormatHelper; +import com.marginallyclever.ro3.PanelHelper; + +import javax.swing.*; +import java.awt.*; + +public class ODEBodyPanel extends JPanel { + public ODEBodyPanel() { + this(new ODESphere()); // I had to choose one non-abstract class to use here. + } + + public ODEBodyPanel(ODEBody body) { + super(new GridLayout(0,2)); + this.setName(ODEBody.class.getSimpleName()); + + var formatter = NumberFormatHelper.getNumberFormatter(); + formatter.setMinimum(0.000); + + JFormattedTextField massQty = new JFormattedTextField(formatter); + massQty.setValue(body.getMassQty()); + massQty.addPropertyChangeListener("value", e -> body.setMassQty( ((Number)massQty.getValue()).doubleValue() )); + PanelHelper.addLabelAndComponent(this,"Mass",massQty); + } +} From b23f1a637f43f4040902bce345aefe8caee593ed Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 23 Apr 2024 11:16:39 -0700 Subject: [PATCH 10/52] adjustable box dimensions --- .../ro3/node/nodes/ode4j/ODEBox.java | 60 +++++++++++++++++-- .../ro3/node/nodes/ode4j/ODEBoxPanel.java | 33 ++++++++++ .../ro3/node/nodes/ode4j/ODESphere.java | 6 +- 3 files changed, 90 insertions(+), 9 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBoxPanel.java diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java index a8ba5e6ed..641bb67f4 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java @@ -1,6 +1,7 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.mesh.shapes.Box; +import com.marginallyclever.ro3.mesh.shapes.Sphere; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; @@ -13,6 +14,7 @@ import javax.vecmath.Matrix4d; import java.awt.*; +import java.util.List; import java.util.Objects; import static org.ode4j.ode.OdeHelper.*; @@ -32,23 +34,69 @@ public ODEBox(String name) { super(name); } + @Override + public void getComponents(List list) { + list.add(new ODEBoxPanel(this)); + super.getComponents(list); + } + @Override protected void onAttach() { super.onAttach(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - // add scene elements geom = createBox(physics.getODESpace(), sizeX, sizeY, sizeZ); geom.setBody(body); mass.setBoxTotal(massQty, sizeX, sizeY, sizeZ); body.setMass(mass); - // add a Node with a MeshInstance to represent the cube. - MeshInstance meshInstance = new MeshInstance(); - meshInstance.setMesh(new Box(sizeX,sizeY,sizeZ)); - addChild(meshInstance); - + addChild(new MeshInstance()); addChild(new Material()); + updateSize(); + } + + public double getSizeX() { + return sizeX; + } + + public double getSizeY() { + return sizeY; + } + + public double getSizeZ() { + return sizeZ; + } + + public void setSizeX(double size) { + if(size<=0) throw new IllegalArgumentException("Size must be greater than zero."); + this.sizeX = size; + updateSize(); + } + + public void setSizeY(double size) { + if(size<=0) throw new IllegalArgumentException("Size must be greater than zero."); + this.sizeY = size; + updateSize(); + } + + public void setSizeZ(double size) { + if(size<=0) throw new IllegalArgumentException("Size must be greater than zero."); + this.sizeZ = size; + updateSize(); + } + + private void updateSize() { + ((DBox)geom).setLengths(sizeX, sizeY, sizeZ); + geom.setBody(body); + + mass.setBoxTotal(massQty, sizeX, sizeY, sizeZ); + body.setMass(mass); + + + var meshInstance = findFirstChild(MeshInstance.class); + if(meshInstance!=null) { + meshInstance.setMesh(new Box(sizeX,sizeY,sizeZ)); + } } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBoxPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBoxPanel.java new file mode 100644 index 000000000..d2c1bc435 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBoxPanel.java @@ -0,0 +1,33 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.swing.NumberFormatHelper; +import com.marginallyclever.ro3.PanelHelper; + +import javax.swing.*; +import java.awt.*; +import java.util.function.DoubleConsumer; + +public class ODEBoxPanel extends JPanel { + public ODEBoxPanel() { + this(new ODEBox()); + } + + public ODEBoxPanel(ODEBox body) { + super(new GridLayout(0,2)); + this.setName(ODEBox.class.getSimpleName()); + + addField("Size X", body.getSizeX(), body::setSizeX); + addField("Size Y", body.getSizeY(), body::setSizeY); + addField("Size Z", body.getSizeZ(), body::setSizeZ); + } + + private void addField(String label, double originalValue, DoubleConsumer setSize) { + var formatter = NumberFormatHelper.getNumberFormatter(); + formatter.setMinimum(0.001); + + JFormattedTextField field = new JFormattedTextField(formatter); + field.setValue(originalValue); + field.addPropertyChangeListener("value", e -> setSize.accept( ((Number)field.getValue()).doubleValue() )); + PanelHelper.addLabelAndComponent(this,label,field); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java index 5fa35f524..22b230c60 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java @@ -56,12 +56,12 @@ public void setRadius(double radius) { if(radius<=0) throw new IllegalArgumentException("Radius must be greater than zero."); this.radius = radius; - mass.setSphereTotal(massQty, radius); - body.setMass(mass); - ((DSphere)geom).setRadius(radius); geom.setBody(body); + mass.setSphereTotal(massQty, radius); + body.setMass(mass); + var meshInstance = findFirstChild(MeshInstance.class); if(meshInstance!=null) { meshInstance.setMesh(new Sphere((float) radius)); From e2530a9fcba26c4ddc8ebbd665b35d19a0d524b0 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 23 Apr 2024 11:27:33 -0700 Subject: [PATCH 11/52] adjustable cylinder --- .../ro3/node/nodes/ode4j/ODE4JHelper.java | 2 - .../ro3/node/nodes/ode4j/ODEBox.java | 13 +--- .../ro3/node/nodes/ode4j/ODECapsule.java | 2 - .../ro3/node/nodes/ode4j/ODECylinder.java | 61 +++++++++++++------ .../node/nodes/ode4j/ODECylinderPanel.java | 32 ++++++++++ .../ro3/node/nodes/ode4j/ODEPlane.java | 2 - .../ro3/node/nodes/ode4j/ODESphere.java | 6 +- 7 files changed, 79 insertions(+), 39 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinderPanel.java diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index ee4c444a9..2bbfd0991 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -1,8 +1,6 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.Registry; -import com.marginallyclever.ro3.node.Node; -import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.math.DMatrix3; import org.ode4j.math.DMatrix3C; import org.ode4j.math.DVector3C; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java index 641bb67f4..0b67edfa1 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java @@ -1,23 +1,14 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.mesh.shapes.Box; -import com.marginallyclever.ro3.mesh.shapes.Sphere; import com.marginallyclever.ro3.node.nodes.Material; -import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; -import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3; -import org.ode4j.math.DVector3C; -import org.ode4j.ode.*; +import org.ode4j.ode.DBox; import javax.swing.*; -import javax.vecmath.Matrix4d; - -import java.awt.*; import java.util.List; -import java.util.Objects; -import static org.ode4j.ode.OdeHelper.*; +import static org.ode4j.ode.OdeHelper.createBox; /** * Wrapper for a ODE4J Box. diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java index a7e8a030e..4ae92a41f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java @@ -7,9 +7,7 @@ import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.ode.OdeHelper; -import javax.vecmath.Matrix4d; import javax.vecmath.Vector3d; -import java.awt.*; /** * Wrapper for a ODE4J capsule. diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java index 345dc8e58..2b3895628 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java @@ -1,22 +1,13 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.mesh.shapes.Cylinder; -import com.marginallyclever.ro3.mesh.shapes.Sphere; import com.marginallyclever.ro3.node.nodes.Material; -import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; -import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3; -import org.ode4j.math.DVector3C; -import org.ode4j.ode.DBody; -import org.ode4j.ode.DGeom; -import org.ode4j.ode.DMass; +import org.ode4j.ode.DCylinder; import org.ode4j.ode.OdeHelper; import javax.swing.*; -import javax.vecmath.Matrix4d; -import java.awt.*; -import java.util.Objects; +import java.util.List; /** * Wrapper for a ODE4J cylinder. @@ -34,22 +25,58 @@ public ODECylinder(String name) { super(name); } + @Override + public void getComponents(List list) { + list.add(new ODECylinderPanel(this)); + super.getComponents(list); + } + @Override protected void onAttach() { super.onAttach(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - geom = OdeHelper.createCylinder(physics.getODESpace(),radius, length); + geom = OdeHelper.createCylinder(physics.getODESpace(), radius, length); geom.setBody(body); mass.setCylinderTotal(massQty, 3, radius, length); body.setMass(mass); - // add a Node with a MeshInstance to represent the ball. - MeshInstance meshInstance = new MeshInstance(); - meshInstance.setMesh(new Cylinder(length, radius, radius)); - addChild(meshInstance); - + addChild(new MeshInstance()); addChild(new Material()); + updateSize(); + } + + public double getRadius() { + return radius; + } + + public double getLength() { + return length; + } + + public void setRadius(double radius) { + if(radius<=0) throw new IllegalArgumentException("Radius must be greater than zero."); + this.radius = radius; + updateSize(); + } + + public void setLength(double length) { + if(length<=0) throw new IllegalArgumentException("Length must be greater than zero."); + this.length = length; + updateSize(); + } + + private void updateSize() { + ((DCylinder)geom).setParams(radius, length); + geom.setBody(body); + + mass.setCylinderTotal(massQty, 3, radius, length); + body.setMass(mass); + + MeshInstance meshInstance = findFirstChild(MeshInstance.class); + if(meshInstance!=null) { + meshInstance.setMesh(new Cylinder(length, radius, radius)); + } } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinderPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinderPanel.java new file mode 100644 index 000000000..3e8a23d77 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinderPanel.java @@ -0,0 +1,32 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.swing.NumberFormatHelper; +import com.marginallyclever.ro3.PanelHelper; + +import javax.swing.*; +import java.awt.*; +import java.util.function.DoubleConsumer; + +public class ODECylinderPanel extends JPanel { + public ODECylinderPanel() { + this(new ODECylinder()); + } + + public ODECylinderPanel(ODECylinder body) { + super(new GridLayout(0,2)); + this.setName(ODECylinder.class.getSimpleName()); + + addField("Radius", body.getRadius(), body::setRadius); + addField("Length", body.getLength(), body::setLength); + } + + private void addField(String label, double originalValue, DoubleConsumer setSize) { + var formatter = NumberFormatHelper.getNumberFormatter(); + formatter.setMinimum(0.001); + + JFormattedTextField field = new JFormattedTextField(formatter); + field.setValue(originalValue); + field.addPropertyChangeListener("value", e -> setSize.accept( ((Number)field.getValue()).doubleValue() )); + PanelHelper.addLabelAndComponent(this,label,field); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index cca35c0d5..e928d4506 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -3,11 +3,9 @@ import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Decal; -import com.marginallyclever.ro3.mesh.shapes.Grid; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; -import com.marginallyclever.ro3.texture.TextureFactory; import org.ode4j.ode.DPlane; import org.ode4j.ode.OdeHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java index 22b230c60..ab973bd95 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java @@ -1,18 +1,14 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.nodes.DHParameterPanel; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.ode.DSphere; import javax.swing.*; -import javax.vecmath.Matrix4d; - -import java.awt.*; import java.util.List; -import static org.ode4j.ode.OdeHelper.*; +import static org.ode4j.ode.OdeHelper.createSphere; /** * Wrapper for a ODE4J Sphere. From 1148764f003fc52dc5ad4d779435eb6e1cde48d2 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 23 Apr 2024 11:34:31 -0700 Subject: [PATCH 12/52] adjustable capsule --- .../ro3/node/nodes/ode4j/ODECapsule.java | 67 ++++++++++++++++--- .../ro3/node/nodes/ode4j/ODECapsulePanel.java | 31 +++++++++ .../ro3/node/nodes/ode4j/ODESphere.java | 7 +- 3 files changed, 94 insertions(+), 11 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsulePanel.java diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java index 4ae92a41f..b2cf32a19 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java @@ -5,9 +5,12 @@ import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.ode4j.ode.DCapsule; import org.ode4j.ode.OdeHelper; +import javax.swing.*; import javax.vecmath.Vector3d; +import java.util.List; /** * Wrapper for a ODE4J capsule. @@ -25,6 +28,12 @@ public ODECapsule(String name) { super(name); } + @Override + public void getComponents(List list) { + list.add(new ODECapsulePanel(this)); + super.getComponents(list); + } + @Override protected void onAttach() { super.onAttach(); @@ -42,23 +51,63 @@ protected void onAttach() { addChild(meshInstance); Pose b1 = new Pose("Ball1"); - meshInstance = new MeshInstance(); - meshInstance.setMesh(new Sphere((float) radius)); - b1.addChild(meshInstance); - b1.setPosition(new Vector3d(0, 0, (float) length /2)); addChild(b1); + b1.addChild(new MeshInstance()); Pose b2 = new Pose("Ball2"); - meshInstance = new MeshInstance(); - meshInstance.setMesh(new Sphere((float) radius)); - b2.addChild(meshInstance); - b2.setPosition(new Vector3d(0, 0, -(float) length /2)); addChild(b2); + b2.addChild(new MeshInstance()); - // add a Material Material material = new Material(); addChild(material); b1.addChild(material); b2.addChild(material); + + updateSize(); + } + + public double getRadius() { + return radius; + } + + public double getLength() { + return length; + } + + public void setRadius(double radius) { + if(radius<=0) throw new IllegalArgumentException("Radius must be greater than zero."); + this.radius = radius; + updateSize(); + } + + public void setLength(double length) { + if(length<=0) throw new IllegalArgumentException("Length must be greater than zero."); + this.length = length; + updateSize(); + } + + private void updateSize() { + ((DCapsule)geom).setParams(radius, length); + geom.setBody(body); + + mass.setCapsuleTotal(massQty, 3, radius, length); + body.setMass(mass); + + MeshInstance meshInstance = findFirstChild(MeshInstance.class); + if(null != meshInstance) { + meshInstance.setMesh(new Cylinder(length, radius, radius)); + } + + MeshInstance b1 = findNodeByPath("Ball1/MeshInstance",MeshInstance.class); + if(null != b1) { + b1.setMesh(new Sphere((float) radius)); + b1.setPosition(new Vector3d(0, 0, (float) length /2)); + } + + MeshInstance b2 = findNodeByPath("Ball2/MeshInstance",MeshInstance.class); + if(null != b2) { + b2.setMesh(new Sphere((float) radius)); + b2.setPosition(new Vector3d(0, 0, -(float) length /2)); + } } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsulePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsulePanel.java new file mode 100644 index 000000000..1915043bd --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsulePanel.java @@ -0,0 +1,31 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.swing.NumberFormatHelper; +import com.marginallyclever.ro3.PanelHelper; + +import javax.swing.*; +import java.awt.*; +import java.util.function.DoubleConsumer; + +public class ODECapsulePanel extends JPanel { + public ODECapsulePanel() { + this(new ODECapsule()); + } + public ODECapsulePanel(ODECapsule body) { + super(new GridLayout(0,2)); + this.setName(ODECapsule.class.getSimpleName()); + + addField("Radius", body.getRadius(), body::setRadius); + addField("Length", body.getLength(), body::setLength); + } + + private void addField(String label, double originalValue, DoubleConsumer setSize) { + var formatter = NumberFormatHelper.getNumberFormatter(); + formatter.setMinimum(0.001); + + JFormattedTextField field = new JFormattedTextField(formatter); + field.setValue(originalValue); + field.addPropertyChangeListener("value", e -> setSize.accept( ((Number)field.getValue()).doubleValue() )); + PanelHelper.addLabelAndComponent(this,label,field); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java index ab973bd95..99aa53cdc 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java @@ -41,7 +41,7 @@ protected void onAttach() { addChild(new MeshInstance()); addChild(new Material()); - setRadius(radius); + updateSize(); } public double getRadius() { @@ -49,9 +49,12 @@ public double getRadius() { } public void setRadius(double radius) { - if(radius<=0) throw new IllegalArgumentException("Radius must be greater than zero."); + if (radius <= 0) throw new IllegalArgumentException("Radius must be greater than zero."); this.radius = radius; + updateSize(); + } + private void updateSize() { ((DSphere)geom).setRadius(radius); geom.setBody(body); From 148567dcce4a25cbca07fba1fbe1e6fbc04e992b Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 24 Apr 2024 09:16:59 -0700 Subject: [PATCH 13/52] added ODEHinge --- pom.xml | 2 +- .../com/marginallyclever/ro3/Registry.java | 4 +- .../ro3/apps/ode4j/ODE4JPanel.java | 60 +++++-- .../ro3/mesh/shapes/Capsule.java | 154 ++++++++++++++++++ .../ro3/mesh/shapes/Decal.java | 11 +- .../com/marginallyclever/ro3/node/Node.java | 4 +- .../ro3/node/nodes/ode4j/ODE4JHelper.java | 2 +- .../ro3/node/nodes/ode4j/ODEBodyPanel.java | 2 + .../ro3/node/nodes/ode4j/ODEHinge.java | 138 ++++++++++++++++ .../ro3/node/nodes/ode4j/ODEHingePanel.java | 32 ++++ .../ro3/node/nodes/ode4j/ODEPlane.java | 7 +- .../ro3/node/nodes/ode4j/ODEWorldSpace.java | 20 +-- .../nodes/ode4j/{ => odebody}/ODEBody.java | 9 +- .../nodes/ode4j/{ => odebody}/ODEBox.java | 9 +- .../ode4j/{ => odebody}/ODEBoxPanel.java | 2 +- .../nodes/ode4j/{ => odebody}/ODECapsule.java | 35 ++-- .../ode4j/{ => odebody}/ODECapsulePanel.java | 2 +- .../ode4j/{ => odebody}/ODECylinder.java | 9 +- .../ode4j/{ => odebody}/ODECylinderPanel.java | 2 +- .../nodes/ode4j/{ => odebody}/ODESphere.java | 10 +- .../ode4j/{ => odebody}/ODESpherePanel.java | 2 +- .../ro3/node/nodes/pose/Pose.java | 7 +- .../ro3/texture/TextureWithMetadata.java | 9 +- 23 files changed, 447 insertions(+), 85 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/mesh/shapes/Capsule.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODEBody.java (89%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODEBox.java (86%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODEBoxPanel.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODECapsule.java (69%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODECapsulePanel.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODECylinder.java (86%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODECylinderPanel.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODESphere.java (82%) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODESpherePanel.java (93%) diff --git a/pom.xml b/pom.xml index df04a962d..cf12dceca 100644 --- a/pom.xml +++ b/pom.xml @@ -481,7 +481,7 @@ org.ode4j core - 0.5.3-SNAPSHOT + 0.5.4-SNAPSHOT diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index f6a86f5fd..7a8c28228 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -13,9 +13,9 @@ import com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlanner; import com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolver; import com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArm; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEBox; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; import com.marginallyclever.ro3.node.nodes.ode4j.ODEPlane; -import com.marginallyclever.ro3.node.nodes.ode4j.ODESphere; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODESphere; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.*; import com.marginallyclever.ro3.node.nodes.pose.poses.*; diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index 425fe64ca..283cbbcda 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -5,6 +5,7 @@ import com.marginallyclever.ro3.apps.App; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.*; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.*; import com.marginallyclever.ro3.node.nodes.pose.Pose; import javax.swing.*; @@ -18,64 +19,97 @@ * Actions in this window will control the contents of the {@link com.marginallyclever.ro3.Registry#scene}. */ public class ODE4JPanel extends App { + boolean randomColor = true; + boolean randomOrientation = false; + public ODE4JPanel() { super(new BorderLayout()); JToolBar toolbar = new JToolBar(); add(toolbar, BorderLayout.NORTH); + JPanel container = new JPanel(new GridLayout(0,2)); + add(container, BorderLayout.CENTER); + JButton pauseButton = addButtonByNameAndCallback(toolbar, "", (e)->{ ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); physics.setPaused(!physics.isPaused()); updatePauseButton((JButton)e.getSource(), physics); }); + + JToggleButton randomColorToggle = new JToggleButton("~Color"); + randomColorToggle.addActionListener(e->randomColor = !randomColor); + toolbar.add(randomColorToggle); + randomColorToggle.setSelected(randomColor); + + JToggleButton randomOrientationToggle = new JToggleButton("~Angle"); + randomOrientationToggle.addActionListener(e->randomOrientation = !randomOrientation); + toolbar.add(randomOrientationToggle); + randomColorToggle.setSelected(randomOrientation); + // I cannot call this here because the physics world has not been created yet. // updatePauseButton(pauseButton, ODE4JHelper.guaranteePhysicsWorld()); // The workaround is to manually set the button. Not pretty but it will have to do. pauseButton.setToolTipText("Play"); pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png"))) ); - addButtonByNameAndCallback(toolbar, "+Floor", (e)->{ + + addButtonByNameAndCallback(container, "+Floor", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); Registry.getScene().addChild(new ODEPlane()); }); - addButtonByNameAndCallback(toolbar, "+Sphere", (e)->{ + addButtonByNameAndCallback(container, "+Sphere", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); add(new ODESphere()); }); - addButtonByNameAndCallback(toolbar, "+Box", (e)->{ + addButtonByNameAndCallback(container, "+Box", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); add(new ODEBox()); }); - addButtonByNameAndCallback(toolbar, "+Cylinder", (e)->{ + addButtonByNameAndCallback(container, "+Cylinder", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); add(new ODECylinder()); }); - addButtonByNameAndCallback(toolbar, "+Capsule", (e)->{ + addButtonByNameAndCallback(container, "+Capsule", (e)->{ ODE4JHelper.guaranteePhysicsWorld(); add(new ODECapsule()); }); + + addButtonByNameAndCallback(container, "+Hinge", (e)->{ + ODE4JHelper.guaranteePhysicsWorld(); + add(new ODEHinge()); + }); } - private void add(ODEBody body) { + private void add(Pose body) { Registry.getScene().addChild(body); placeBodyAbovePlane(body); + if(randomColor) giveRandomColor(body); } private void placeBodyAbovePlane(Pose body) { - // set a random orientation - double x = Math.random()*90; - double y = Math.random()*90; - double z = Math.random()*90; Matrix4d m = new Matrix4d(); - m.set(MatrixHelper.eulerToMatrix(new Vector3d(x,y,z), MatrixHelper.EulerSequence.XYZ)); + if(randomOrientation) { + // set a random orientation + double x = Math.random() * 180; + double y = Math.random() * 180; + double z = Math.random() * 180; + m.set(MatrixHelper.eulerToMatrix(new Vector3d(x, y, z), MatrixHelper.EulerSequence.XYZ)); + } else { + m.setIdentity(); + } + + // set above world m.setTranslation(new Vector3d(0, 0, 15)); + body.setWorld(m); + } + private void giveRandomColor(Pose body) { Material material = body.findFirstChild(Material.class); if(material!=null) { material.setDiffuseColor(new Color( @@ -85,10 +119,10 @@ private void placeBodyAbovePlane(Pose body) { } } - private JButton addButtonByNameAndCallback(JToolBar toolbar, String title, ActionListener actionListener) { + private JButton addButtonByNameAndCallback(JComponent parent, String title, ActionListener actionListener) { JButton button = new JButton(title); button.addActionListener(actionListener); - toolbar.add(button); + parent.add(button); return button; } diff --git a/src/main/java/com/marginallyclever/ro3/mesh/shapes/Capsule.java b/src/main/java/com/marginallyclever/ro3/mesh/shapes/Capsule.java new file mode 100644 index 000000000..78676e1e5 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/mesh/shapes/Capsule.java @@ -0,0 +1,154 @@ +package com.marginallyclever.ro3.mesh.shapes; + +import com.jogamp.opengl.GL3; +import com.marginallyclever.ro3.mesh.Mesh; + +import javax.vecmath.Vector3d; +import java.util.ArrayList; +import java.util.List; + +/** + *

{@link Capsule} is a {@link Mesh}. It is a cylinder with rounded ends.

+ */ +public class Capsule extends Mesh { + public static final int RESOLUTION_CIRCULAR = 16; + public static final int RESOLUTION_LENGTH = 4; + public static final int RESOLUTION_DOME = 8; + + public float radius = 0.5f; + public float height = 1; + + public Capsule() { + this(2, 0.5f); + } + + public Capsule(double height, double radius) { + super(); + if(radius<=0) throw new IllegalArgumentException("radius must be greater than zero."); + if(height<=0) throw new IllegalArgumentException("height must be greater than zero."); + if(height points = new ArrayList<>(); + List normals = new ArrayList<>(); + double pi2 = Math.PI/2.0; + double doneAngleStep = pi2/RESOLUTION_DOME; + + // consider a line that runs from the North Pole, around 1/4 of the circle, + // down the cylinder, and around the second 1/4 circle to the South Pole. + for(int i=0;i<=RESOLUTION_DOME;++i) { + double angle = i * doneAngleStep; + double z = Math.cos(angle); + double x = Math.sin(angle); + points.add(new Vector3d(x*radius,0,z*radius+h2)); + normals.add(new Vector3d(x,0,z)); + } + + for(int i=0;i<=RESOLUTION_LENGTH;++i) { + points.add(new Vector3d(radius,0,h2 - i*h/RESOLUTION_LENGTH)); + normals.add(new Vector3d(1,0,0)); + } + + for(int i=0;i<=RESOLUTION_DOME;++i) { + double angle = i * doneAngleStep + pi2; + double z = Math.cos(angle); + double x = Math.sin(angle); + points.add(new Vector3d(x*radius,0,z*radius-h2)); + normals.add(new Vector3d(x,0,z)); + } + + // North Pole + addVertex(0,0,radius+h2); + addNormal(0,0,1); + // South Pole + addVertex(0,0,-radius-h2); + addNormal(0,0,-1); + + double circleAngleStep = Math.PI*2/RESOLUTION_CIRCULAR; + // now that we have one line, rotate it around the Z axis to make the rest of the cylinder. + for(int i=0;i */ public class Decal extends Mesh { - public double height = 1; - public double width = 1; + public float height = 1; + public float width = 1; + public int wParts = 1; + public int hParts = 1; + public float textureScale = 1; public Decal() { super(); @@ -36,8 +39,6 @@ public void updateModel() { * Create a rectangle in the XY plane, facing +Z. */ private void createOneSidedDecal() { - int wParts = (int) (width ); - int hParts = (int) (height); Vector3d n = new Vector3d(); Vector3d p0 = new Vector3d(); @@ -142,7 +143,7 @@ protected void addSubdividedPlane(Vector3d n, // texture coordinates are based on the distance from the top left corner float x = (float) (v.x - p2.x); float y = (float) (v.y - p2.y); - addTexCoord(x/3, y/3); + addTexCoord(x/textureScale, y/textureScale); } } /* diff --git a/src/main/java/com/marginallyclever/ro3/node/Node.java b/src/main/java/com/marginallyclever/ro3/node/Node.java index 2944c9606..9620ccb6a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/Node.java +++ b/src/main/java/com/marginallyclever/ro3/node/Node.java @@ -109,7 +109,7 @@ private void fireRenameEvent(Node child) { } /** - * Called after this node is added to its parent. + * Called after this {@link Node} is added to a new parent {@link Node}. */ protected void onAttach() {} @@ -121,7 +121,7 @@ public void removeChild(Node child) { } /** - * Called after this node is removed from its parent. + * Called after this {@link Node} is removed from its parent {@link Node}. */ protected void onDetach() {} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index 2bbfd0991..e75de2f3a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -21,7 +21,7 @@ public class ODE4JHelper { * @param rotation the rotation matrix * @return the Java3D matrix. */ - static Matrix4d assembleMatrix(DVector3C translation, DMatrix3C rotation) { + public static Matrix4d assembleMatrix(DVector3C translation, DMatrix3C rotation) { // assemble matrix from translation and rotation. Matrix4d m = new Matrix4d(); m.m00 = rotation.get00(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java index 9ddda3445..50dc37bfc 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java @@ -2,6 +2,8 @@ import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODESphere; import javax.swing.*; import java.awt.*; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java new file mode 100644 index 000000000..2b4544e15 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java @@ -0,0 +1,138 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.convenience.helpers.MatrixHelper; +import com.marginallyclever.ro3.node.NodePath; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import org.ode4j.math.DVector3; +import org.ode4j.ode.DBody; +import org.ode4j.ode.DHingeJoint; +import org.ode4j.ode.OdeHelper; + +import javax.swing.*; +import javax.vecmath.Matrix3d; +import javax.vecmath.Matrix4d; +import javax.vecmath.Vector3d; +import java.util.List; + +/** + *

Wrapper for a hinge joint in ODE4J. If one side of the hinge is null then it is attached to the world.

+ *

If the physics simulation is paused then then moving this Pose node will adjust the position and orientation + * of the hinge, as well as it's relation to the attached parts. If the simulation is NOT paused then the hinge + * will behave as normal.

+ */ +public class ODEHinge extends Pose { + private DHingeJoint hinge; + private final NodePath partA = new NodePath<>(this,ODEBody.class); + private final NodePath partB = new NodePath<>(this,ODEBody.class); + + public ODEHinge() { + this("ODE Hinge"); + } + + public ODEHinge(String name) { + super(name); + } + + @Override + public void getComponents(List list) { + list.add(new ODEHingePanel(this)); + super.getComponents(list); + } + + @Override + protected void onAttach() { + super.onAttach(); + var physics = ODE4JHelper.guaranteePhysicsWorld(); + hinge = OdeHelper.createHingeJoint (physics.getODEWorld(),null); + + DBody a = partA.getSubject() == null? null : partA.getSubject().getODEBody(); + DBody b = partB.getSubject() == null? null : partB.getSubject().getODEBody(); + hinge.attach (a,b); + + hinge.setAnchor (0,0,1); + hinge.setAxis (1,-1,1.41421356); + } + + @Override + protected void onDetach() { + super.onDetach(); + if(hinge!=null) { + try { + hinge.destroy(); + } catch(Exception ignored) {} // if physics is already destroyed, this will throw an exception. + } + } + + public NodePath getPartA() { + return partA; + } + + public NodePath getPartB() { + return partB; + } + + public DHingeJoint getHinge() { + return hinge; + } + + public void setPartA(ODEBody subject) { + partA.setUniqueIDByNode(subject); + updateHinge(); + } + + public void setPartB(ODEBody subject) { + partB.setUniqueIDByNode(subject); + updateHinge(); + } + + /** + * Tell the physics engine who is connected to this hinge. + */ + private void updateHinge() { + DBody a = partA.getSubject() == null ? null : partA.getSubject().getODEBody(); + DBody b = partB.getSubject() == null ? null : partB.getSubject().getODEBody(); + hinge.attach(a, b); + } + + @Override + public void setWorld(Matrix4d world) { + super.setWorld(world); + updateHingePose(); + } + + private void updateHingePose() { + var physics = ODE4JHelper.guaranteePhysicsWorld(); + // only let the user move the hinge if the physics simulation is paused. + if(physics.isPaused()) { + // set the hinge reference point and axis. + var mat = getWorld(); + var pos = MatrixHelper.getPosition(mat); + hinge.setAnchor(pos.x, pos.y, pos.z); + var axis = MatrixHelper.getZAxis(mat); + hinge.setAxis(axis.x, axis.y, axis.z); + } + } + + @Override + public void update(double dt) { + super.update(dt); + var physics = ODE4JHelper.guaranteePhysicsWorld(); + if(!physics.isPaused()) { + // if the physics simulation is running then the hinge will behave as normal. + DVector3 anchor = new DVector3(); + DVector3 axis = new DVector3(); + hinge.getAnchor2(anchor); + hinge.getAxis(axis); + // use axis and anchor to set the world matrix. + Matrix3d m3 = MatrixHelper.lookAt( + new Vector3d(0,0,0), + new Vector3d(axis.get0(),axis.get1(),axis.get2()) + ); + Matrix4d m4 = new Matrix4d(); + m4.set(m3); + m4.setTranslation(new Vector3d(anchor.get0(),anchor.get1(),anchor.get2())); + setWorld(m4); + } + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java new file mode 100644 index 000000000..2f22f3840 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java @@ -0,0 +1,32 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.apps.nodeselector.NodeSelector; +import com.marginallyclever.ro3.node.NodePath; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; +import com.marginallyclever.ro3.node.nodes.pose.Pose; + +import javax.swing.*; +import java.awt.*; +import java.util.function.Consumer; + +public class ODEHingePanel extends JPanel { + public ODEHingePanel() { + this(new ODEHinge()); + } + + public ODEHingePanel(ODEHinge hinge) { + super(new GridLayout(0,2)); + this.setName(ODEHinge.class.getSimpleName()); + + addSelector("part A",hinge.getPartA(),hinge::setPartA); + addSelector("part B",hinge.getPartB(),hinge::setPartB); + } + + private void addSelector(String label, NodePath originalValue, Consumer setPartA) { + NodeSelector selector = new NodeSelector<>(ODEBody.class,originalValue.getSubject()); + selector.addPropertyChangeListener("subject", (evt) ->setPartA.accept((ODEBody)evt.getNewValue())); + PanelHelper.addLabelAndComponent(this, label,selector); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index e928d4506..055905833 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -40,8 +40,11 @@ protected void onAttach() { MeshInstance mesh = new MeshInstance(); addChild(mesh); Decal decal = new Decal(); - decal.width = 100; - decal.height = 100; + decal.width = 1000; + decal.height = 1000; + decal.wParts = 20; + decal.hParts = 20; + decal.textureScale = 10; decal.updateModel(); mesh.setMesh(decal); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java index b15fe20cb..5c1f155ea 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java @@ -23,7 +23,7 @@ public class ODEWorldSpace extends Node { public double WORLD_CFM = 1e-5; public double WORLD_ERP = 0.8; public double WORLD_GRAVITY = -9.81; - private int ITERS = 20; + private final int ITERS = 20; private final int CONTACT_BUFFER_SIZE = 4; private DWorld world; @@ -61,11 +61,6 @@ protected void onDetach() { stopPhysics(); } - public void resetPhysics() { - stopPhysics(); - startPhysics(); - } - private void startPhysics() { logger.info("Starting Physics"); @@ -90,9 +85,10 @@ private void startPhysics() { private void stopPhysics() { logger.info("Stopping Physics"); - if(world!=null) { - world.destroy(); - world=null; + if(contactGroup!=null) { + contactGroup.empty(); + contactGroup.destroy(); + contactGroup=null; } if(space!=null) { @@ -100,9 +96,9 @@ private void stopPhysics() { space=null; } - if(contactGroup!=null) { - contactGroup.destroy(); - contactGroup=null; + if(world!=null) { + world.destroy(); + world=null; } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java similarity index 89% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index 560ab0871..cfadff0a2 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -1,5 +1,8 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEBodyPanel; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.Pose; import org.ode4j.math.DMatrix3C; import org.ode4j.math.DVector3; @@ -99,4 +102,8 @@ public void setMassQty(double massQty) { mass.setMass(massQty); body.setMass(mass); } + + public DBody getODEBody() { + return body; + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java similarity index 86% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java index 0b67edfa1..9b182ac79 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java @@ -1,7 +1,9 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.ro3.mesh.shapes.Box; import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.ode.DBox; @@ -15,7 +17,6 @@ */ public class ODEBox extends ODEBody { private double sizeX=5.0, sizeY=5.0, sizeZ=5.0; - private double massQty = Math.sqrt(sizeX*sizeY*sizeZ); public ODEBox() { this("ODE Box"); @@ -39,7 +40,7 @@ protected void onAttach() { geom = createBox(physics.getODESpace(), sizeX, sizeY, sizeZ); geom.setBody(body); - mass.setBoxTotal(massQty, sizeX, sizeY, sizeZ); + mass.setBoxTotal(Math.sqrt(sizeX*sizeY*sizeZ), sizeX, sizeY, sizeZ); body.setMass(mass); addChild(new MeshInstance()); @@ -81,7 +82,7 @@ private void updateSize() { ((DBox)geom).setLengths(sizeX, sizeY, sizeZ); geom.setBody(body); - mass.setBoxTotal(massQty, sizeX, sizeY, sizeZ); + mass.setBoxTotal(mass.getMass(), sizeX, sizeY, sizeZ); body.setMass(mass); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBoxPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBoxPanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java index d2c1bc435..f53dcc232 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBoxPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java similarity index 69% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java index b2cf32a19..f781ad2b1 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java @@ -1,9 +1,10 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; -import com.marginallyclever.ro3.mesh.shapes.Cylinder; +import com.marginallyclever.ro3.mesh.shapes.Capsule; import com.marginallyclever.ro3.mesh.shapes.Sphere; import com.marginallyclever.ro3.node.nodes.Material; -import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.ode.DCapsule; import org.ode4j.ode.OdeHelper; @@ -17,8 +18,7 @@ */ public class ODECapsule extends ODEBody { private double radius = 2.5; - private double length = 5.0; - private double massQty = Math.PI * radius * radius * length; + private double length = 10.0; public ODECapsule() { this("ODE Capsule"); @@ -42,26 +42,11 @@ protected void onAttach() { geom = OdeHelper.createCapsule(physics.getODESpace(), radius, length); geom.setBody(body); - mass.setCapsuleTotal(massQty, 3, radius, length); + mass.setCapsuleTotal(Math.PI * radius * radius * length, 3, radius, length); body.setMass(mass); - // add a Node with a MeshInstance to represent the ball. - MeshInstance meshInstance = new MeshInstance(); - meshInstance.setMesh(new Cylinder(length, radius, radius)); - addChild(meshInstance); - - Pose b1 = new Pose("Ball1"); - addChild(b1); - b1.addChild(new MeshInstance()); - - Pose b2 = new Pose("Ball2"); - addChild(b2); - b2.addChild(new MeshInstance()); - - Material material = new Material(); - addChild(material); - b1.addChild(material); - b2.addChild(material); + addChild(new MeshInstance()); + addChild(new Material()); updateSize(); } @@ -90,12 +75,12 @@ private void updateSize() { ((DCapsule)geom).setParams(radius, length); geom.setBody(body); - mass.setCapsuleTotal(massQty, 3, radius, length); + mass.setCapsuleTotal(mass.getMass(), 3, radius, length); body.setMass(mass); MeshInstance meshInstance = findFirstChild(MeshInstance.class); if(null != meshInstance) { - meshInstance.setMesh(new Cylinder(length, radius, radius)); + meshInstance.setMesh(new Capsule(length, radius)); } MeshInstance b1 = findNodeByPath("Ball1/MeshInstance",MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsulePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsulePanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java index 1915043bd..ee58b4467 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECapsulePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java similarity index 86% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java index 2b3895628..9b70e1ecc 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java @@ -1,7 +1,9 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.ro3.mesh.shapes.Cylinder; import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.ode.DCylinder; import org.ode4j.ode.OdeHelper; @@ -15,7 +17,6 @@ public class ODECylinder extends ODEBody { private double radius = 2.5; private double length = 5.0; - private double massQty = Math.PI * radius * radius * length; public ODECylinder() { this("ODE Cylinder"); @@ -39,7 +40,7 @@ protected void onAttach() { geom = OdeHelper.createCylinder(physics.getODESpace(), radius, length); geom.setBody(body); - mass.setCylinderTotal(massQty, 3, radius, length); + mass.setCylinderTotal(mass.getMass(), 3, radius, length); body.setMass(mass); addChild(new MeshInstance()); @@ -71,7 +72,7 @@ private void updateSize() { ((DCylinder)geom).setParams(radius, length); geom.setBody(body); - mass.setCylinderTotal(massQty, 3, radius, length); + mass.setCylinderTotal(mass.getMass(), 3, radius, length); body.setMass(mass); MeshInstance meshInstance = findFirstChild(MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinderPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinderPanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java index 3e8a23d77..014e5d741 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODECylinderPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java similarity index 82% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java index 99aa53cdc..4b4c34c00 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java @@ -1,7 +1,9 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.ro3.mesh.shapes.Sphere; import com.marginallyclever.ro3.node.nodes.Material; +import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.ode4j.ode.DSphere; @@ -15,7 +17,6 @@ */ public class ODESphere extends ODEBody { private double radius = 2.5; - private double massQty = radius *5; public ODESphere() { this("ODE Sphere"); @@ -39,6 +40,9 @@ protected void onAttach() { geom = createSphere(physics.getODESpace(), radius); geom.setBody(body); + mass.setSphereTotal(Math.PI * radius*radius*radius * 4.0/3.0, radius); + body.setMass(mass); + addChild(new MeshInstance()); addChild(new Material()); updateSize(); @@ -58,7 +62,7 @@ private void updateSize() { ((DSphere)geom).setRadius(radius); geom.setBody(body); - mass.setSphereTotal(massQty, radius); + mass.setSphereTotal(mass.getMass(), radius); body.setMass(mass); var meshInstance = findFirstChild(MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESpherePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java similarity index 93% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESpherePanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java index 244750af6..f6dabe1fe 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODESpherePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java index d1fdd0d3d..849071e67 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java @@ -68,7 +68,8 @@ public void getComponents(List list) { } /** - * @return the rotation of this pose using Euler angles in degrees. + * @param orderOfRotation the order of rotation. + * @return the local rotation of this pose using Euler angles in degrees. */ public Vector3d getRotationEuler(MatrixHelper.EulerSequence orderOfRotation) { Vector3d r = MatrixHelper.matrixToEuler(local,orderOfRotation); @@ -77,7 +78,7 @@ public Vector3d getRotationEuler(MatrixHelper.EulerSequence orderOfRotation) { } /** - * Set the rotation of this pose using Euler angles. + * Set the local rotation of this pose using Euler angles. * * @param r Euler angles in degrees. * @param orderOfRotation the order of rotation. @@ -99,7 +100,7 @@ public Vector3d getPosition() { } /** - * set the local position of this pose. + * Set the local position of this pose. * @param p the new position. */ public void setPosition(Vector3d p) { diff --git a/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java b/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java index ac90d30b9..65ebe3d0d 100644 --- a/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java +++ b/src/main/java/com/marginallyclever/ro3/texture/TextureWithMetadata.java @@ -50,7 +50,10 @@ public void use(ShaderProgram shader) { flip.setRGB(x,y,image.getRGB(x,image.getHeight()-y-1)); } } - texture = AWTTextureIO.newTexture(GLProfile.getDefault(), flip, false); + texture = AWTTextureIO.newTexture( + GLProfile.getDefault(), + flip, + true); // generate mipmaps } GL3 gl3 = GLContext.getCurrentGL().getGL3(); @@ -68,8 +71,8 @@ public void use(ShaderProgram shader) { gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_S, GL3.GL_REPEAT); gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_WRAP_T, GL3.GL_REPEAT); // turn on mipmapping - //gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_MIN_FILTER, GL3.GL_LINEAR_MIPMAP_LINEAR); - //gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_MAG_FILTER, GL3.GL_LINEAR); + gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_MIN_FILTER, GL3.GL_LINEAR_MIPMAP_LINEAR); + gl3.glTexParameteri(GL3.GL_TEXTURE_2D, GL3.GL_TEXTURE_MAG_FILTER, GL3.GL_LINEAR); // turn on anisotropic filtering float[] maxAnisotropy = new float[1]; gl3.glGetFloatv(GL3.GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT, maxAnisotropy, 0); From aa2f810d31eed05e59ae6aa2958310c35b2e623a Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 24 Apr 2024 11:18:19 -0700 Subject: [PATCH 14/52] to/from JSON --- .../com/marginallyclever/ro3/Registry.java | 6 ++ .../ro3/node/nodes/HingeJoint.java | 5 +- .../ro3/node/nodes/LinearJoint.java | 5 +- .../ro3/node/nodes/ode4j/ODE4JHelper.java | 33 +++++++ .../ro3/node/nodes/ode4j/ODEHinge.java | 6 +- .../ro3/node/nodes/ode4j/ODEPlane.java | 5 +- .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 27 +++++- .../ro3/node/nodes/ode4j/odebody/ODEBox.java | 21 ++++- .../node/nodes/ode4j/odebody/ODECapsule.java | 20 +++- .../node/nodes/ode4j/odebody/ODECylinder.java | 19 +++- .../node/nodes/ode4j/odebody/ODESphere.java | 17 +++- .../ro3/node/nodes/pose/Pose.java | 67 ++++++++----- .../ro3/node/nodes/pose/PosePanel.java | 94 +++++++++++-------- .../ro3/node/nodes/pose/poses/Camera.java | 7 +- .../ro3/node/nodes/pose/poses/LookAt.java | 2 +- 15 files changed, 251 insertions(+), 83 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index 7a8c28228..2f74b8254 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -13,8 +13,11 @@ import com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlanner; import com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolver; import com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArm; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEHinge; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; import com.marginallyclever.ro3.node.nodes.ode4j.ODEPlane; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODECapsule; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODECylinder; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODESphere; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.*; @@ -83,6 +86,9 @@ public static void start() { { physics.add("ODEWorldSpace", ODEWorldSpace::new); physics.add("ODEBox", ODEBox::new); + physics.add("ODECapsule", ODECapsule::new); + physics.add("ODECylinder", ODECylinder::new); + physics.add("ODEHinge", ODEHinge::new); physics.add("ODEPlane", ODEPlane::new); physics.add("ODESphere", ODESphere::new); } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/HingeJoint.java b/src/main/java/com/marginallyclever/ro3/node/nodes/HingeJoint.java index f1773ea83..275b97eec 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/HingeJoint.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/HingeJoint.java @@ -44,7 +44,10 @@ public void update(double dt) { if(axle.getSubject()!=null) { // set the axle's location in space. - axle.getSubject().getLocal().rotZ(Math.toRadians(angle)); + var subject = axle.getSubject(); + var m = subject.getLocal(); + m.rotZ(Math.toRadians(angle)); + subject.setLocal(m); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java b/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java index e8c0faa71..dcde2fe8a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/LinearJoint.java @@ -44,7 +44,10 @@ public void update(double dt) { if(car.getSubject()!=null) { // set the axle's location in space. - car.getSubject().getLocal().m23 = position; + var subject = car.getSubject(); + var m = subject.getLocal(); + m.m23 = position; + subject.setLocal(m); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index e75de2f3a..f8f4ed6b8 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -1,8 +1,10 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.Registry; +import org.json.JSONObject; import org.ode4j.math.DMatrix3; import org.ode4j.math.DMatrix3C; +import org.ode4j.math.DVector3; import org.ode4j.math.DVector3C; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -65,4 +67,35 @@ public static ODEWorldSpace guaranteePhysicsWorld() { } return physics; } + + public static double volumeCylinder(double radius, double length) { + return Math.PI * radius * radius * length; + } + + public static double volumeCapsule(double radius, double length) { + return volumeCylinder(radius,length) + volumeSphere(radius); + } + + public static double volumeBox(double x, double y, double z) { + return x * y * z; + } + + public static double volumeSphere(double radius) { + return 4.0 / 3.0 * Math.PI * radius * radius * radius; + } + + public static JSONObject vector3ToJSON(DVector3C vector) { + JSONObject json = new JSONObject(); + json.put("x", vector.get0()); + json.put("y", vector.get1()); + json.put("z", vector.get2()); + return json; + } + + public static DVector3C jsonToVector3(JSONObject vector) { + return new DVector3( + vector.getDouble("x"), + vector.getDouble("y"), + vector.getDouble("z")); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java index 2b4544e15..23891f2bc 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java @@ -96,8 +96,8 @@ private void updateHinge() { } @Override - public void setWorld(Matrix4d world) { - super.setWorld(world); + public void setLocal(Matrix4d m) { + super.setLocal(m); updateHingePose(); } @@ -122,7 +122,7 @@ public void update(double dt) { // if the physics simulation is running then the hinge will behave as normal. DVector3 anchor = new DVector3(); DVector3 axis = new DVector3(); - hinge.getAnchor2(anchor); + hinge.getAnchor(anchor); hinge.getAxis(axis); // use axis and anchor to set the world matrix. Matrix3d m3 = MatrixHelper.lookAt( diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index 055905833..8422c0222 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -85,10 +85,11 @@ public void update(double dt) { } @Override - public void setWorld(Matrix4d world) { - super.setWorld(world); + public void setLocal(Matrix4d m) { + super.setLocal(m); if(plane==null) return; + var world = getWorld(); Vector3d normal = MatrixHelper.getZAxis(world); Vector3d position = MatrixHelper.getPosition(world); double depth = normal.dot(position); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index cfadff0a2..52a7343d4 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -4,6 +4,7 @@ import com.marginallyclever.ro3.node.nodes.ode4j.ODEBodyPanel; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.Pose; +import org.json.JSONObject; import org.ode4j.math.DMatrix3C; import org.ode4j.math.DVector3; import org.ode4j.math.DVector3C; @@ -73,15 +74,13 @@ public void update(double dt) { } @Override - public void setWorld(Matrix4d world) { - super.setWorld(world); + public void setLocal(Matrix4d m) { + super.setLocal(m); if(body == null) return; + var world = getWorld(); body.setPosition(world.m03, world.m13, world.m23); body.setRotation(ODE4JHelper.convertRotationToODE(world)); - // stop movement so object does not fight user. - body.setAngularVel(new DVector3(0, 0, 0)); - body.setLinearVel(new DVector3(0, 0, 0)); } @Override @@ -106,4 +105,22 @@ public void setMassQty(double massQty) { public DBody getODEBody() { return body; } + + @Override + public JSONObject toJSON() { + var json = super.toJSON(); + json.put("mass", getMassQty()); + json.put("avel", ODE4JHelper.vector3ToJSON(body.getAngularVel())); + json.put("lvel", ODE4JHelper.vector3ToJSON(body.getLinearVel())); + return json; + + } + + @Override + public void fromJSON(JSONObject from) { + super.fromJSON(from); + if(from.has("mass")) setMassQty(from.getDouble("mass")); + if(from.has("avel")) body.setAngularVel(ODE4JHelper.jsonToVector3(from.getJSONObject("avel"))); + if(from.has("lvel")) body.setLinearVel(ODE4JHelper.jsonToVector3(from.getJSONObject("lvel"))); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java index 9b182ac79..25743057c 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java @@ -5,6 +5,7 @@ import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.json.JSONObject; import org.ode4j.ode.DBox; import javax.swing.*; @@ -40,7 +41,7 @@ protected void onAttach() { geom = createBox(physics.getODESpace(), sizeX, sizeY, sizeZ); geom.setBody(body); - mass.setBoxTotal(Math.sqrt(sizeX*sizeY*sizeZ), sizeX, sizeY, sizeZ); + mass.setBoxTotal(ODE4JHelper.volumeBox(sizeX,sizeY,sizeZ), sizeX, sizeY, sizeZ); body.setMass(mass); addChild(new MeshInstance()); @@ -91,4 +92,22 @@ private void updateSize() { meshInstance.setMesh(new Box(sizeX,sizeY,sizeZ)); } } + + @Override + public JSONObject toJSON() { + var json= super.toJSON(); + json.put("sizeX", sizeX); + json.put("sizeY", sizeY); + json.put("sizeZ", sizeZ); + return json; + } + + @Override + public void fromJSON(JSONObject json) { + super.fromJSON(json); + if(json.has("sizeX")) sizeX = json.getDouble("sizeX"); + if(json.has("sizeY")) sizeY = json.getDouble("sizeY"); + if(json.has("sizeZ")) sizeZ = json.getDouble("sizeZ"); + updateSize(); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java index f781ad2b1..86acf0a43 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java @@ -4,8 +4,10 @@ import com.marginallyclever.ro3.mesh.shapes.Sphere; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.node.nodes.ode4j.ODEHinge; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.json.JSONObject; import org.ode4j.ode.DCapsule; import org.ode4j.ode.OdeHelper; @@ -42,7 +44,7 @@ protected void onAttach() { geom = OdeHelper.createCapsule(physics.getODESpace(), radius, length); geom.setBody(body); - mass.setCapsuleTotal(Math.PI * radius * radius * length, 3, radius, length); + mass.setCapsuleTotal(ODE4JHelper.volumeCapsule(radius,length), 3, radius, length); body.setMass(mass); addChild(new MeshInstance()); @@ -95,4 +97,20 @@ private void updateSize() { b2.setPosition(new Vector3d(0, 0, -(float) length /2)); } } + + @Override + public JSONObject toJSON() { + var json= super.toJSON(); + json.put("radius", radius); + json.put("length", length); + return json; + } + + @Override + public void fromJSON(JSONObject json) { + super.fromJSON(json); + if(json.has("radius")) radius = json.getDouble("radius"); + if(json.has("length")) length = json.getDouble("length"); + updateSize(); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java index 9b70e1ecc..147aa9a37 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java @@ -5,6 +5,7 @@ import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.json.JSONObject; import org.ode4j.ode.DCylinder; import org.ode4j.ode.OdeHelper; @@ -40,7 +41,7 @@ protected void onAttach() { geom = OdeHelper.createCylinder(physics.getODESpace(), radius, length); geom.setBody(body); - mass.setCylinderTotal(mass.getMass(), 3, radius, length); + mass.setCylinderTotal(ODE4JHelper.volumeCylinder(radius,length), 3, radius, length); body.setMass(mass); addChild(new MeshInstance()); @@ -80,4 +81,20 @@ private void updateSize() { meshInstance.setMesh(new Cylinder(length, radius, radius)); } } + + @Override + public JSONObject toJSON() { + var json= super.toJSON(); + json.put("radius", radius); + json.put("length", length); + return json; + } + + @Override + public void fromJSON(JSONObject json) { + super.fromJSON(json); + if(json.has("radius")) radius = json.getDouble("radius"); + if(json.has("length")) length = json.getDouble("length"); + updateSize(); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java index 4b4c34c00..d25feb43d 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java @@ -5,6 +5,7 @@ import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.json.JSONObject; import org.ode4j.ode.DSphere; import javax.swing.*; @@ -40,7 +41,7 @@ protected void onAttach() { geom = createSphere(physics.getODESpace(), radius); geom.setBody(body); - mass.setSphereTotal(Math.PI * radius*radius*radius * 4.0/3.0, radius); + mass.setSphereTotal(ODE4JHelper.volumeSphere(radius), radius); body.setMass(mass); addChild(new MeshInstance()); @@ -70,4 +71,18 @@ private void updateSize() { meshInstance.setMesh(new Sphere((float) radius)); } } + + @Override + public JSONObject toJSON() { + var json= super.toJSON(); + json.put("radius", radius); + return json; + } + + @Override + public void fromJSON(JSONObject json) { + super.fromJSON(json); + if(json.has("radius")) radius = json.getDouble("radius"); + updateSize(); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java index 849071e67..dca949608 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java @@ -27,44 +27,58 @@ public Pose(String name) { super(name); } + /** + * Build a Swing Component that represents this Node. + * @param list the list to add components to. + */ + public void getComponents(List list) { + list.add(new PosePanel(this)); + super.getComponents(list); + } + public Matrix4d getLocal() { - return local; + return new Matrix4d(local); } + /** + * Set the local transform of this pose. This is the best method to override if you want to + * capture changes to the local OR world transform. + * @param m the new local transform. + */ public void setLocal(Matrix4d m) { local.set(m); } + /** + * @return the world transform of this pose. + */ public Matrix4d getWorld() { // search up the tree to find the world transform. Pose p = findParent(Pose.class); if(p==null) { - return new Matrix4d(local); + return getLocal(); } - Matrix4d parentWorld = p.getWorld(); - parentWorld.mul(local); - return parentWorld; + Matrix4d result = p.getWorld(); + result.mul(getLocal()); + return result; } - public void setWorld(Matrix4d world) { + /** + * Set the world transform of this pose. All cases call {@link #setLocal(Matrix4d)}. + * @param m the new world transform. + */ + public void setWorld(Matrix4d m) { // search up the tree to find the world transform. Pose parent = findParent(Pose.class); if(parent==null) { - local.set(world); + setLocal(m); return; } - Matrix4d inverseParentWorld = parent.getWorld(); - inverseParentWorld.invert(); - local.mul(inverseParentWorld,world); - } - - /** - * Build a Swing Component that represents this Node. - * @param list the list to add components to. - */ - public void getComponents(List list) { - list.add(new PosePanel(this)); - super.getComponents(list); + // Changing m could have unintended side effects, so use a temp variable. + Matrix4d temp = parent.getWorld(); + temp.invert(); + temp.mul(m); + setLocal(temp); } /** @@ -84,12 +98,15 @@ public Vector3d getRotationEuler(MatrixHelper.EulerSequence orderOfRotation) { * @param orderOfRotation the order of rotation. */ public void setRotationEuler(Vector3d r, MatrixHelper.EulerSequence orderOfRotation) { - System.out.println("setRotationEuler("+r+","+orderOfRotation+")"); + //System.out.println("setRotationEuler("+r+","+orderOfRotation+")"); Vector3d p = getPosition(); Vector3d rRad = new Vector3d(r); rRad.scale(Math.PI/180.0); - local.set(MatrixHelper.eulerToMatrix(rRad, orderOfRotation)); - setPosition(p); + + var m4 = new Matrix4d(); + m4.set(MatrixHelper.eulerToMatrix(rRad, orderOfRotation)); + m4.setTranslation(p); + setLocal(m4); } /** @@ -104,9 +121,9 @@ public Vector3d getPosition() { * @param p the new position. */ public void setPosition(Vector3d p) { - local.m03 = p.x; - local.m13 = p.y; - local.m23 = p.z; + var m4 = getLocal(); + MatrixHelper.setPosition(m4, p); + setLocal(m4); } @Override diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/PosePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/PosePanel.java index 0975ca60f..320f31cb1 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/PosePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/PosePanel.java @@ -8,6 +8,7 @@ import javax.swing.text.NumberFormatter; import javax.vecmath.Vector3d; import java.awt.*; +import java.beans.PropertyChangeListener; public class PosePanel extends JPanel { private final Pose pose; @@ -28,24 +29,29 @@ public PosePanel(Pose pose) { gbc.gridy=0; gbc.fill = GridBagConstraints.BOTH; - var formatter = NumberFormatHelper.getNumberFormatter(); - addTranslationComponents(formatter,gbc); + addTranslationComponents(gbc); gbc.gridy++; - addRotationComponents(formatter,gbc); + addRotationComponents(gbc); } - private void addTranslationComponents(NumberFormatter formatter,GridBagConstraints gbc) { - var local = pose.getLocal(); - JFormattedTextField tx = new JFormattedTextField(formatter); tx.setValue(local.m03); - JFormattedTextField ty = new JFormattedTextField(formatter); ty.setValue(local.m13); - JFormattedTextField tz = new JFormattedTextField(formatter); tz.setValue(local.m23); - tx.setToolTipText("translate x"); - ty.setToolTipText("translate y"); - tz.setToolTipText("translate z"); + private void addTranslationComponents(GridBagConstraints gbc) { + var local = pose.getPosition(); - tx.addPropertyChangeListener("value", e -> local.m03 = ((Number) tx.getValue()).doubleValue() ); - ty.addPropertyChangeListener("value", e -> local.m13 = ((Number) ty.getValue()).doubleValue() ); - tz.addPropertyChangeListener("value", e -> local.m23 = ((Number) tz.getValue()).doubleValue() ); + JFormattedTextField tx = addTranslateField("translate x",local.x, (e)-> { + var p = pose.getPosition(); + p.x = ((Number) e.getNewValue()).doubleValue(); + pose.setPosition(p); + }); + JFormattedTextField ty = addTranslateField("translate y",local.y, (e)-> { + var p = pose.getPosition(); + p.y = ((Number) e.getNewValue()).doubleValue(); + pose.setPosition(p); + }); + JFormattedTextField tz = addTranslateField("translate z",local.z, (e)-> { + var p = pose.getPosition(); + p.z = ((Number) e.getNewValue()).doubleValue(); + pose.setPosition(p); + }); gbc.gridx=0; this.add(new JLabel("Translation"),gbc); gbc.gridx=1; this.add(tx,gbc); @@ -53,17 +59,20 @@ private void addTranslationComponents(NumberFormatter formatter,GridBagConstrain gbc.gridx=3; this.add(tz,gbc); } - private void addRotationComponents(NumberFormatter formatter,GridBagConstraints gbc) { + private JFormattedTextField addTranslateField(String label, double value, PropertyChangeListener listener) { + var formatter = NumberFormatHelper.getNumberFormatter(); + JFormattedTextField field = new JFormattedTextField(formatter); + field.setValue(value); + field.setToolTipText(label); + field.addPropertyChangeListener("value", listener ); + + return field; + } + + private void addRotationComponents(GridBagConstraints gbc) { var rotationIndex = pose.getRotationIndex(); Vector3d r = pose.getRotationEuler(rotationIndex); - JFormattedTextField rx = new JFormattedTextField(formatter); rx.setValue(r.x); - JFormattedTextField ry = new JFormattedTextField(formatter); ry.setValue(r.y); - JFormattedTextField rz = new JFormattedTextField(formatter); rz.setValue(r.z); - rx.setToolTipText("rotate x"); - ry.setToolTipText("rotate y"); - rz.setToolTipText("rotate z"); - String [] names = new String[MatrixHelper.EulerSequence.values().length]; int i=0; for(MatrixHelper.EulerSequence s : MatrixHelper.EulerSequence.values()) { @@ -72,34 +81,41 @@ private void addRotationComponents(NumberFormatter formatter,GridBagConstraints JComboBox rotationType = new JComboBox<>(names); rotationType.setSelectedIndex(rotationIndex.ordinal()); rotationType.addActionListener( e -> { - pose.setRotationIndex( MatrixHelper.EulerSequence.values()[rotationType.getSelectedIndex()] );; + pose.setRotationIndex( MatrixHelper.EulerSequence.values()[rotationType.getSelectedIndex()] ); }); - rx.addPropertyChangeListener("value", e -> { - Vector3d r2 = pose.getRotationEuler(rotationIndex); - r2.x = ((Number) rx.getValue()).doubleValue(); - pose.setRotationEuler(r2, rotationIndex); - }); - ry.addPropertyChangeListener("value", e -> { - Vector3d r2 = pose.getRotationEuler(rotationIndex); - r2.y = ((Number) ry.getValue()).doubleValue(); - pose.setRotationEuler(r2, rotationIndex); - }); - rz.addPropertyChangeListener("value", e -> { - Vector3d r2 = pose.getRotationEuler(rotationIndex); - r2.z = ((Number) rz.getValue()).doubleValue(); - pose.setRotationEuler(r2, rotationIndex); - }); + JFormattedTextField rx = addRotation("rotate x",r.x); + JFormattedTextField ry = addRotation("rotate y",r.y); + JFormattedTextField rz = addRotation("rotate z",r.z); + + rx.addPropertyChangeListener((e)->updateRotation(rx,ry,rz)); + ry.addPropertyChangeListener((e)->updateRotation(rx,ry,rz)); + rz.addPropertyChangeListener((e)->updateRotation(rx,ry,rz)); gbc.gridx=0; this.add(new JLabel("Rotation"),gbc); gbc.gridx=1; this.add(rx,gbc); gbc.gridx=2; this.add(ry,gbc); gbc.gridx=3; this.add(rz,gbc); - gbc.gridy++; gbc.gridx=2; this.add(new JLabel("Type"),gbc); gbc.gridx=3; this.add(rotationType,gbc); gbc.gridx=0; } + + private void updateRotation(JFormattedTextField rx, JFormattedTextField ry, JFormattedTextField rz) { + Vector3d r = pose.getRotationEuler(pose.getRotationIndex()); + r.x = ((Number)rx.getValue()).doubleValue(); + r.y = ((Number)ry.getValue()).doubleValue(); + r.z = ((Number)rz.getValue()).doubleValue(); + pose.setRotationEuler(r, pose.getRotationIndex()); + } + + private JFormattedTextField addRotation(String label, double value) { + var formatter = NumberFormatHelper.getNumberFormatter(); + JFormattedTextField field = new JFormattedTextField(formatter); + field.setValue(value); + field.setToolTipText(label); + return field; + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java index 8cf97a89d..f55444f7e 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java @@ -175,7 +175,9 @@ private void rotate(Vector3d axis,double delta) { Matrix3d m = MatrixHelper.getMatrixFromAxisAndRotation(axis,delta); Matrix4d m4 = new Matrix4d(); m4.set(m); - getLocal().mul(m4); + var local = getLocal(); + local.mul(m4); + setLocal(local); } /** @@ -241,7 +243,7 @@ public Vector3d getOrbitPoint() { * @param newRadius new radius. Must be >=1. */ public void moveToNewRadius(double newRadius) { - Matrix4d local = getLocal(); + Matrix4d local = this.getLocal(); var point = getOrbitPoint(); orbitRadius = Math.max(1,newRadius); @@ -249,6 +251,7 @@ public void moveToNewRadius(double newRadius) { Vector3d orbitVector = MatrixHelper.getZAxis(local); orbitVector.scaleAdd(orbitRadius,point); local.setTranslation(orbitVector); + this.setLocal(local); } public double getOrbitRadius() { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java index 1852ff070..77a5fa3a7 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java @@ -54,7 +54,7 @@ public void update(double dt) { fromWorld.invert(); look.mul(fromWorld,look); look.setTranslation(new javax.vecmath.Vector3d()); - getLocal().set(look); + this.setLocal(look); } } From 73ed713b9a19d6d0c179dd05c8aeb35bb41cb4e6 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Fri, 26 Apr 2024 19:04:14 -0700 Subject: [PATCH 15/52] Fixed synchronization problems Defer all physics actions to onFirstUpdate() call, which only happens after the scenes have been attached. --- .../ro3/apps/actions/ImportScene.java | 1 - .../ro3/apps/ode4j/ODE4JPanel.java | 37 ++------- .../ro3/mesh/shapes/Decal.java | 2 - .../ro3/node/nodes/ode4j/ODE4JHelper.java | 9 +- .../ro3/node/nodes/ode4j/ODEHinge.java | 82 ++++++++++++++----- .../ro3/node/nodes/ode4j/ODENode.java | 49 +++++++++++ .../ro3/node/nodes/ode4j/ODEPlane.java | 52 ++++++++---- .../ro3/node/nodes/ode4j/ODEWorldSpace.java | 22 +++-- .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 70 +++++++++++----- .../ro3/node/nodes/ode4j/odebody/ODEBox.java | 11 +-- .../node/nodes/ode4j/odebody/ODECapsule.java | 11 +-- .../node/nodes/ode4j/odebody/ODECylinder.java | 10 ++- .../node/nodes/ode4j/odebody/ODESphere.java | 10 ++- .../ro3/node/nodes/ode4j/ODEHingeTest.java | 50 +++++++++++ 14 files changed, 298 insertions(+), 118 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java create mode 100644 src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java diff --git a/src/main/java/com/marginallyclever/ro3/apps/actions/ImportScene.java b/src/main/java/com/marginallyclever/ro3/apps/actions/ImportScene.java index 9380116a3..38e616d57 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/actions/ImportScene.java +++ b/src/main/java/com/marginallyclever/ro3/apps/actions/ImportScene.java @@ -15,7 +15,6 @@ * Load a Scene and insert it into the existing Scene. */ public class ImportScene extends AbstractAction { - private static final Logger logger = LoggerFactory.getLogger(ImportScene.class); private final JFileChooser chooser; public ImportScene() { diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index 283cbbcda..b93b44bcb 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -53,39 +53,16 @@ public ODE4JPanel() { pauseButton.setToolTipText("Play"); pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png"))) ); - - addButtonByNameAndCallback(container, "+Floor", (e)->{ - ODE4JHelper.guaranteePhysicsWorld(); - Registry.getScene().addChild(new ODEPlane()); - }); - - addButtonByNameAndCallback(container, "+Sphere", (e)->{ - ODE4JHelper.guaranteePhysicsWorld(); - add(new ODESphere()); - }); - - addButtonByNameAndCallback(container, "+Box", (e)->{ - ODE4JHelper.guaranteePhysicsWorld(); - add(new ODEBox()); - }); - - addButtonByNameAndCallback(container, "+Cylinder", (e)->{ - ODE4JHelper.guaranteePhysicsWorld(); - add(new ODECylinder()); - }); - - addButtonByNameAndCallback(container, "+Capsule", (e)->{ - ODE4JHelper.guaranteePhysicsWorld(); - add(new ODECapsule()); - }); - - addButtonByNameAndCallback(container, "+Hinge", (e)->{ - ODE4JHelper.guaranteePhysicsWorld(); - add(new ODEHinge()); - }); + addButtonByNameAndCallback(container, "+Floor", (e)-> Registry.getScene().addChild(new ODEPlane()) ); + addButtonByNameAndCallback(container, "+Sphere", (e)-> add(new ODESphere()) ); + addButtonByNameAndCallback(container, "+Box", (e)-> add(new ODEBox()) ); + addButtonByNameAndCallback(container, "+Cylinder", (e)-> add(new ODECylinder()) ); + addButtonByNameAndCallback(container, "+Capsule", (e)->add(new ODECapsule()) ); + addButtonByNameAndCallback(container, "+Hinge", (e)-> add(new ODEHinge()) ); } private void add(Pose body) { + ODE4JHelper.guaranteePhysicsWorld(); Registry.getScene().addChild(body); placeBodyAbovePlane(body); if(randomColor) giveRandomColor(body); diff --git a/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java b/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java index 7575e865f..1a93b2802 100644 --- a/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java +++ b/src/main/java/com/marginallyclever/ro3/mesh/shapes/Decal.java @@ -20,7 +20,6 @@ public class Decal extends Mesh { public Decal() { super(); - updateModel(); } @@ -39,7 +38,6 @@ public void updateModel() { * Create a rectangle in the XY plane, facing +Z. */ private void createOneSidedDecal() { - Vector3d n = new Vector3d(); Vector3d p0 = new Vector3d(); Vector3d p1 = new Vector3d(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index f8f4ed6b8..ed9428d23 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -10,6 +10,7 @@ import org.slf4j.LoggerFactory; import javax.vecmath.Matrix4d; +import javax.vecmath.Vector3d; /** * Shared methods for working with ODE4J physics. @@ -58,6 +59,10 @@ public static DMatrix3C convertRotationToODE(Matrix4d mat) { ); } + /** + * Gurantee there is exactly one {@link ODEWorldSpace} in the scene. + * @return the {@link ODEWorldSpace}. + */ public static ODEWorldSpace guaranteePhysicsWorld() { ODEWorldSpace physics = Registry.getScene().findFirstChild(ODEWorldSpace.class); if (physics == null) { @@ -92,8 +97,8 @@ public static JSONObject vector3ToJSON(DVector3C vector) { return json; } - public static DVector3C jsonToVector3(JSONObject vector) { - return new DVector3( + public static Vector3d jsonToVector3(JSONObject vector) { + return new Vector3d( vector.getDouble("x"), vector.getDouble("y"), vector.getDouble("z")); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java index 23891f2bc..ca49ff3e2 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java @@ -4,10 +4,13 @@ import com.marginallyclever.ro3.node.NodePath; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; import com.marginallyclever.ro3.node.nodes.pose.Pose; +import org.json.JSONObject; import org.ode4j.math.DVector3; import org.ode4j.ode.DBody; import org.ode4j.ode.DHingeJoint; import org.ode4j.ode.OdeHelper; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; import javax.swing.*; import javax.vecmath.Matrix3d; @@ -17,11 +20,12 @@ /** *

Wrapper for a hinge joint in ODE4J. If one side of the hinge is null then it is attached to the world.

- *

If the physics simulation is paused then then moving this Pose node will adjust the position and orientation + *

If the physics simulation is paused then then moving this {@link Pose} will adjust the position and orientation * of the hinge, as well as it's relation to the attached parts. If the simulation is NOT paused then the hinge * will behave as normal.

*/ -public class ODEHinge extends Pose { +public class ODEHinge extends ODENode { + private static final Logger logger = LoggerFactory.getLogger(ODEHinge.class); private DHingeJoint hinge; private final NodePath partA = new NodePath<>(this,ODEBody.class); private final NodePath partB = new NodePath<>(this,ODEBody.class); @@ -40,18 +44,20 @@ public void getComponents(List list) { super.getComponents(list); } + /** + * Called once at the start of the first {@link #update(double)} + */ @Override - protected void onAttach() { - super.onAttach(); + protected void onFirstUpdate() { + super.onFirstUpdate(); var physics = ODE4JHelper.guaranteePhysicsWorld(); - hinge = OdeHelper.createHingeJoint (physics.getODEWorld(),null); - - DBody a = partA.getSubject() == null? null : partA.getSubject().getODEBody(); - DBody b = partB.getSubject() == null? null : partB.getSubject().getODEBody(); - hinge.attach (a,b); + hinge = OdeHelper.createHingeJoint(physics.getODEWorld(), null); + connect(); + } - hinge.setAnchor (0,0,1); - hinge.setAxis (1,-1,1.41421356); + @Override + protected void onReady() { + super.onReady(); } @Override @@ -61,6 +67,7 @@ protected void onDetach() { try { hinge.destroy(); } catch(Exception ignored) {} // if physics is already destroyed, this will throw an exception. + hinge = null; } } @@ -78,21 +85,27 @@ public DHingeJoint getHinge() { public void setPartA(ODEBody subject) { partA.setUniqueIDByNode(subject); - updateHinge(); + connect(); } public void setPartB(ODEBody subject) { partB.setUniqueIDByNode(subject); - updateHinge(); + connect(); } /** * Tell the physics engine who is connected to this hinge. */ - private void updateHinge() { - DBody a = partA.getSubject() == null ? null : partA.getSubject().getODEBody(); - DBody b = partB.getSubject() == null ? null : partB.getSubject().getODEBody(); + private void connect() { + if(hinge==null) return; + + var as = partA.getSubject(); + var bs = partB.getSubject(); + DBody a = as == null ? null : as.getODEBody(); + DBody b = bs == null ? null : bs.getODEBody(); + logger.debug(this.getName()+" connect "+(as==null?"null":as.getName())+" to "+(bs==null?"null":bs.getName())); hinge.attach(a, b); + updatePhysicsFromWorld(); } @Override @@ -106,12 +119,21 @@ private void updateHingePose() { // only let the user move the hinge if the physics simulation is paused. if(physics.isPaused()) { // set the hinge reference point and axis. - var mat = getWorld(); - var pos = MatrixHelper.getPosition(mat); - hinge.setAnchor(pos.x, pos.y, pos.z); - var axis = MatrixHelper.getZAxis(mat); - hinge.setAxis(axis.x, axis.y, axis.z); + updatePhysicsFromWorld(); + } + } + + private void updatePhysicsFromWorld() { + if(hinge==null) return; + + var mat = getWorld(); + var pos = MatrixHelper.getPosition(mat); + hinge.setAnchor(pos.x, pos.y, pos.z); + var axis = MatrixHelper.getZAxis(mat); + if(axis.length()<0.001) { + logger.error("Hinge axis zero length?"); } + hinge.setAxis(axis.x, axis.y, axis.z); } @Override @@ -135,4 +157,22 @@ public void update(double dt) { setWorld(m4); } } + + @Override + public JSONObject toJSON() { + var json = super.toJSON(); + json.put("partA",partA.getUniqueID()); + json.put("partB",partB.getUniqueID()); + return json; + } + + @Override + public void fromJSON(JSONObject from) { + super.fromJSON(from); + if(from.has("partA")) partA.setUniqueID(from.getString("partA")); + if(from.has("partB")) partB.setUniqueID(from.getString("partB")); + updatePhysicsFromWorld(); + connect(); + updateHingePose(); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java new file mode 100644 index 000000000..fb27836b8 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java @@ -0,0 +1,49 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.node.nodes.pose.Pose; +import org.json.JSONObject; + +public class ODENode extends Pose { + /** + * Should not be serialized, should be reset on every deserialize (such as {@link #fromJSON(JSONObject)}) + */ + private boolean runFirstUpdate=true; + + + public ODENode() { + this("ODE Node"); + } + + public ODENode(String name) { + super(name); + } + + @Override + protected void onDetach() { + super.onDetach(); + runFirstUpdate=true; + } + + @Override + public void update(double dt) { + super.update(dt); + + if(runFirstUpdate) { + runFirstUpdate=false; + onFirstUpdate(); + } + } + + @Override + public void fromJSON(JSONObject from) { + super.fromJSON(from); + runFirstUpdate=true; + } + + /** + * Called once at the start of the first {@link #update(double)} + */ + protected void onFirstUpdate() { + // override me + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index 8422c0222..7562505c5 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -4,8 +4,8 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Decal; import com.marginallyclever.ro3.node.nodes.Material; -import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import org.json.JSONObject; import org.ode4j.ode.DPlane; import org.ode4j.ode.OdeHelper; @@ -18,8 +18,9 @@ /** * Wrapper for a ODE4J Plane. */ -public class ODEPlane extends Pose { +public class ODEPlane extends ODENode { private DPlane plane; + private final Decal decal = new Decal(); public ODEPlane() { this("ODE Plane"); @@ -27,29 +28,34 @@ public ODEPlane() { public ODEPlane(String name) { super(name); + // setup decal + decal.width = 1000; + decal.height = 1000; + decal.wParts = 20; + decal.hParts = 20; + decal.textureScale = 10; + decal.updateModel(); } @Override - protected void onAttach() { - super.onAttach(); + protected void onFirstUpdate() { + super.onFirstUpdate(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); plane = OdeHelper.createPlane(physics.getODESpace(), 0, 0, 1, 0); - // add a Node with a MeshInstance to represent the floor. - MeshInstance mesh = new MeshInstance(); - addChild(mesh); - Decal decal = new Decal(); - decal.width = 1000; - decal.height = 1000; - decal.wParts = 20; - decal.hParts = 20; - decal.textureScale = 10; - decal.updateModel(); + MeshInstance mesh = findFirstChild(MeshInstance.class); + if(mesh==null) { + mesh = new MeshInstance(); + addChild(mesh); + } mesh.setMesh(decal); - Material material = new Material(); - addChild(material); + Material material = findFirstChild(Material.class); + if(material==null) { + material = new Material(); + addChild(material); + } material.setTexture(Registry.textureFactory.load("/com/marginallyclever/ro3/shared/checkerboard.png")); } @@ -100,4 +106,18 @@ public void setLocal(Matrix4d m) { public Icon getIcon() { return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); } + + @Override + public JSONObject toJSON() { + return super.toJSON(); + } + + @Override + public void fromJSON(JSONObject from) { + super.fromJSON(from); + + if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); + MeshInstance mesh = findFirstChild(MeshInstance.class); + mesh.setMesh(decal); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java index 5c1f155ea..dc7f4f121 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java @@ -65,17 +65,23 @@ private void startPhysics() { logger.info("Starting Physics"); // build the world - world = createWorld(); - world.setGravity(0, 0, WORLD_GRAVITY); - world.setCFM (WORLD_CFM); - world.setERP (WORLD_ERP); - world.setQuickStepNumIterations (ITERS); + if(world == null) { + world = createWorld(); + world.setGravity(0, 0, WORLD_GRAVITY); + world.setCFM(WORLD_CFM); + world.setERP(WORLD_ERP); + world.setQuickStepNumIterations(ITERS); + } // setup a space in the world - space = OdeHelper.createSapSpace( null, DSapSpace.AXES.XYZ ); - //space = OdeHelper.createSimpleSpace(); + if(space == null) { + space = OdeHelper.createSapSpace(null, DSapSpace.AXES.XYZ); + //space = OdeHelper.createSimpleSpace(); + } - contacts = new DContactBuffer(CONTACT_BUFFER_SIZE); + if(contacts == null) { + contacts = new DContactBuffer(CONTACT_BUFFER_SIZE); + } if(contactGroup == null) { contactGroup = OdeHelper.createJointGroup(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index 52a7343d4..329eb8da1 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -2,11 +2,10 @@ import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.ode4j.ODEBodyPanel; +import com.marginallyclever.ro3.node.nodes.ode4j.ODENode; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; -import com.marginallyclever.ro3.node.nodes.pose.Pose; import org.json.JSONObject; import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3; import org.ode4j.math.DVector3C; import org.ode4j.ode.DBody; import org.ode4j.ode.DGeom; @@ -15,14 +14,17 @@ import javax.swing.*; import javax.vecmath.Matrix4d; +import javax.vecmath.Vector3d; import java.util.List; import java.util.Objects; -public abstract class ODEBody extends Pose { +public abstract class ODEBody extends ODENode { protected DBody body; protected DGeom geom; protected DMass mass; - + private double massQty=1; + private Vector3d angularVel = new Vector3d(); + private Vector3d linearVel = new Vector3d(); public ODEBody() { this("ODE Body"); @@ -38,14 +40,6 @@ public void getComponents(List list) { super.getComponents(list); } - @Override - protected void onAttach() { - super.onAttach(); - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - body = OdeHelper.createBody(physics.getODEWorld()); - mass = OdeHelper.createMass(); - } - @Override protected void onDetach() { super.onDetach(); @@ -61,13 +55,23 @@ protected void onDetach() { } } + /** + * Called once at the start of the first {@link #update(double)} + */ + protected void onFirstUpdate() { + ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + body = OdeHelper.createBody(physics.getODEWorld()); + mass = OdeHelper.createMass(); + updateMass(); + updatePoseFromPhysics(); + } + @Override public void update(double dt) { super.update(dt); // adjust the position of the Node to match the body. if(body == null) return; - DVector3C translation = body.getPosition(); DMatrix3C rotation = body.getRotation(); super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); @@ -76,8 +80,11 @@ public void update(double dt) { @Override public void setLocal(Matrix4d m) { super.setLocal(m); - if(body == null) return; + updatePoseFromPhysics(); + } + protected void updatePoseFromPhysics() { + if (body == null) return; var world = getWorld(); body.setPosition(world.m03, world.m13, world.m23); body.setRotation(ODE4JHelper.convertRotationToODE(world)); @@ -97,9 +104,19 @@ public double getMassQty() { * @param massQty must be >= 0 */ public void setMassQty(double massQty) { - if(massQty<0) throw new IllegalArgumentException("Mass must be greater than zero."); + if (massQty < 0) throw new IllegalArgumentException("Mass must be greater than zero."); + this.massQty = massQty; + updateMass(); + } + + private void updateMass() { + if(mass==null || body==null) return; mass.setMass(massQty); - body.setMass(mass); + if(mass.check()) { + body.setMass(mass); + body.setAngularVel(angularVel.x, angularVel.y, angularVel.z); + body.setLinearVel(linearVel.x, linearVel.y, linearVel.z); + } } public DBody getODEBody() { @@ -110,8 +127,10 @@ public DBody getODEBody() { public JSONObject toJSON() { var json = super.toJSON(); json.put("mass", getMassQty()); - json.put("avel", ODE4JHelper.vector3ToJSON(body.getAngularVel())); - json.put("lvel", ODE4JHelper.vector3ToJSON(body.getLinearVel())); + if(body!=null) { + json.put("avel", ODE4JHelper.vector3ToJSON(body.getAngularVel())); + json.put("lvel", ODE4JHelper.vector3ToJSON(body.getLinearVel())); + } return json; } @@ -120,7 +139,18 @@ public JSONObject toJSON() { public void fromJSON(JSONObject from) { super.fromJSON(from); if(from.has("mass")) setMassQty(from.getDouble("mass")); - if(from.has("avel")) body.setAngularVel(ODE4JHelper.jsonToVector3(from.getJSONObject("avel"))); - if(from.has("lvel")) body.setLinearVel(ODE4JHelper.jsonToVector3(from.getJSONObject("lvel"))); + if(from.has("avel")) setAngularVel(ODE4JHelper.jsonToVector3(from.getJSONObject("avel"))); + if(from.has("lvel")) setLinearVel(ODE4JHelper.jsonToVector3(from.getJSONObject("lvel"))); + updatePoseFromPhysics(); + } + + public void setAngularVel(Vector3d angularVel) { + this.angularVel.set(angularVel); + if(body!=null) body.setAngularVel(angularVel.x, angularVel.y, angularVel.z); + } + + public void setLinearVel(Vector3d linearVel) { + this.linearVel.set(linearVel); + if(body!=null) body.setLinearVel(linearVel.x, linearVel.y, linearVel.z); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java index 25743057c..96d4d7376 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java @@ -34,8 +34,8 @@ public void getComponents(List list) { } @Override - protected void onAttach() { - super.onAttach(); + protected void onFirstUpdate() { + super.onFirstUpdate(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); geom = createBox(physics.getODESpace(), sizeX, sizeY, sizeZ); @@ -44,8 +44,8 @@ protected void onAttach() { mass.setBoxTotal(ODE4JHelper.volumeBox(sizeX,sizeY,sizeZ), sizeX, sizeY, sizeZ); body.setMass(mass); - addChild(new MeshInstance()); - addChild(new Material()); + if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); + if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } @@ -80,13 +80,14 @@ public void setSizeZ(double size) { } private void updateSize() { + if(geom==null) return; + ((DBox)geom).setLengths(sizeX, sizeY, sizeZ); geom.setBody(body); mass.setBoxTotal(mass.getMass(), sizeX, sizeY, sizeZ); body.setMass(mass); - var meshInstance = findFirstChild(MeshInstance.class); if(meshInstance!=null) { meshInstance.setMesh(new Box(sizeX,sizeY,sizeZ)); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java index 86acf0a43..26b075788 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java @@ -37,8 +37,8 @@ public void getComponents(List list) { } @Override - protected void onAttach() { - super.onAttach(); + protected void onFirstUpdate() { + super.onFirstUpdate(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); geom = OdeHelper.createCapsule(physics.getODESpace(), radius, length); @@ -47,9 +47,8 @@ protected void onAttach() { mass.setCapsuleTotal(ODE4JHelper.volumeCapsule(radius,length), 3, radius, length); body.setMass(mass); - addChild(new MeshInstance()); - addChild(new Material()); - + if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); + if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } @@ -74,6 +73,8 @@ public void setLength(double length) { } private void updateSize() { + if(geom==null) return; + ((DCapsule)geom).setParams(radius, length); geom.setBody(body); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java index 147aa9a37..38479e0f8 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java @@ -34,8 +34,8 @@ public void getComponents(List list) { } @Override - protected void onAttach() { - super.onAttach(); + protected void onFirstUpdate() { + super.onFirstUpdate(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); geom = OdeHelper.createCylinder(physics.getODESpace(), radius, length); @@ -44,8 +44,8 @@ protected void onAttach() { mass.setCylinderTotal(ODE4JHelper.volumeCylinder(radius,length), 3, radius, length); body.setMass(mass); - addChild(new MeshInstance()); - addChild(new Material()); + if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); + if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } @@ -70,6 +70,8 @@ public void setLength(double length) { } private void updateSize() { + if(geom==null) return; + ((DCylinder)geom).setParams(radius, length); geom.setBody(body); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java index d25feb43d..b8a0c4e51 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java @@ -34,8 +34,8 @@ public void getComponents(List list) { } @Override - protected void onAttach() { - super.onAttach(); + protected void onFirstUpdate() { + super.onFirstUpdate(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); geom = createSphere(physics.getODESpace(), radius); @@ -44,8 +44,8 @@ protected void onAttach() { mass.setSphereTotal(ODE4JHelper.volumeSphere(radius), radius); body.setMass(mass); - addChild(new MeshInstance()); - addChild(new Material()); + if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); + if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } @@ -60,6 +60,8 @@ public void setRadius(double radius) { } private void updateSize() { + if(geom==null) return; + ((DSphere)geom).setRadius(radius); geom.setBody(body); diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java new file mode 100644 index 000000000..87fc0f347 --- /dev/null +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java @@ -0,0 +1,50 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; +import org.json.JSONObject; +import org.junit.jupiter.api.Assertions; +import org.junit.jupiter.api.Test; +import org.ode4j.ode.OdeHelper; + +public class ODEHingeTest { + @Test + public void test() { + Registry.start(); + Node scene = Registry.getScene(); + ODEBox box1 = new ODEBox("b1"); + scene.addChild(box1); + ODEBox box2 = new ODEBox("b2"); + scene.addChild(box2); + ODEHinge hinge1 = new ODEHinge("h1"); + scene.addChild(hinge1); + ODEHinge hinge2 = new ODEHinge("h2"); + scene.addChild(hinge2); + + hinge1.setPartB(box1); + hinge2.setPartA(box1); + hinge2.setPartB(box2); + + assertOneWorldSpaceInScene(scene); + + // make a deep copy to/from json and confirm the links are still attached. + JSONObject json = scene.toJSON(); + Node after = Registry.nodeFactory.create(json.getString("type")); + after.fromJSON(json); + + assertOneWorldSpaceInScene(scene); +// var physics = ODE4JHelper.guaranteePhysicsWorld(); + } + + private void assertOneWorldSpaceInScene(Node scene) { + // count the instances of ODEWorldSpace in scene. + int count = 0; + for(Node n : scene.getChildren()) { + if(n instanceof ODEWorldSpace) { + count++; + } + } + Assertions.assertEquals(1,count); + } +} From 4c1f3c346d650cbe8636e7674a3ec5d5a0c8ea99 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Fri, 26 Apr 2024 19:18:27 -0700 Subject: [PATCH 16/52] Documenting --- .../ro3/node/nodes/ode4j/ODEBodyPanel.java | 4 +++ .../ro3/node/nodes/ode4j/ODEHingePanel.java | 3 +++ .../ro3/node/nodes/ode4j/ODENode.java | 25 ++++++++++++++++++- .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 10 ++++++-- .../node/nodes/ode4j/odebody/ODEBoxPanel.java | 3 +++ .../nodes/ode4j/odebody/ODECapsulePanel.java | 3 +++ .../nodes/ode4j/odebody/ODECylinderPanel.java | 3 +++ .../nodes/ode4j/odebody/ODESpherePanel.java | 3 +++ 8 files changed, 51 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java index 50dc37bfc..b43fbfe7b 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java @@ -8,6 +8,10 @@ import javax.swing.*; import java.awt.*; +/** + * A panel for editing an ODEBody. + + */ public class ODEBodyPanel extends JPanel { public ODEBodyPanel() { this(new ODESphere()); // I had to choose one non-abstract class to use here. diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java index 2f22f3840..d729ab63f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java @@ -11,6 +11,9 @@ import java.awt.*; import java.util.function.Consumer; +/** + * A panel for editing an ODEHinge. + */ public class ODEHingePanel extends JPanel { public ODEHingePanel() { this(new ODEHinge()); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java index fb27836b8..5dd66a69a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java @@ -3,13 +3,25 @@ import com.marginallyclever.ro3.node.nodes.pose.Pose; import org.json.JSONObject; +/** + *

Base class for all {@link com.marginallyclever.ro3.node.Node} that implement ODE4J.

+ *

ODE Nodes like {@link ODEHinge} need to be able to find the subject nodes to which the hinge connects. These + * subjects are not guaranteed to exist during load. They *are* guaranteed at the first call to {@link #update(double)} + * after loading.

+ *

This class is responsible for calling {@link #onFirstUpdate()} once at the start of the first + * {@link #update(double)}. No physics calculations should be done in the constructor or in {@link #onAttach()}.

+ *

the flag to run #onFirstUpdate again will be reset if:

+ *
    + *
  • the node is detached
  • + *
  • the node is deserialized
  • + *
+ */ public class ODENode extends Pose { /** * Should not be serialized, should be reset on every deserialize (such as {@link #fromJSON(JSONObject)}) */ private boolean runFirstUpdate=true; - public ODENode() { this("ODE Node"); } @@ -46,4 +58,15 @@ public void fromJSON(JSONObject from) { protected void onFirstUpdate() { // override me } + + boolean getRunFirstUpdate() { + return runFirstUpdate; + } + + /** + * @param runFirstUpdate Set true to run {@link #onFirstUpdate()} again. + */ + void setRunFirstUpdate(boolean runFirstUpdate) { + this.runFirstUpdate=runFirstUpdate; + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index 329eb8da1..9118a2e9a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -18,13 +18,19 @@ import java.util.List; import java.util.Objects; +/** + *

An {@link ODENode} that represents a body with a geometry in the ODE physics engine. This node is responsible + * for the {@link DBody}, {@link DMass}, and {@link DGeom}. Classes which extend this class are responsible for the + * visual and physical representation of the shape.

+ *

TODO: They should not be responsible for the visual representation because physical and visual shape don't always match.

+ */ public abstract class ODEBody extends ODENode { protected DBody body; protected DGeom geom; protected DMass mass; private double massQty=1; - private Vector3d angularVel = new Vector3d(); - private Vector3d linearVel = new Vector3d(); + private final Vector3d angularVel = new Vector3d(); + private final Vector3d linearVel = new Vector3d(); public ODEBody() { this("ODE Body"); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java index f53dcc232..c8fb93fcc 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java @@ -7,6 +7,9 @@ import java.awt.*; import java.util.function.DoubleConsumer; +/** + * A panel for editing an ODEBox. + */ public class ODEBoxPanel extends JPanel { public ODEBoxPanel() { this(new ODEBox()); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java index ee58b4467..23126dbff 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java @@ -7,6 +7,9 @@ import java.awt.*; import java.util.function.DoubleConsumer; +/** + * A panel for editing an ODEBox. + */ public class ODECapsulePanel extends JPanel { public ODECapsulePanel() { this(new ODECapsule()); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java index 014e5d741..d0ed7cccd 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java @@ -7,6 +7,9 @@ import java.awt.*; import java.util.function.DoubleConsumer; +/** + * A panel for editing an ODEBox. + */ public class ODECylinderPanel extends JPanel { public ODECylinderPanel() { this(new ODECylinder()); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java index f6dabe1fe..ac8ca30eb 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java @@ -6,6 +6,9 @@ import javax.swing.*; import java.awt.*; +/** + * A panel for editing an ODESphere. + */ public class ODESpherePanel extends JPanel { public ODESpherePanel() { this(new ODESphere()); From 273e525603d6936a6af6883e31aff65566f2d097 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Sat, 27 Apr 2024 12:36:42 -0700 Subject: [PATCH 17/52] replace separate x y z with Vector3d --- .../ro3/node/nodes/ode4j/ODE4JHelper.java | 8 ++-- .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 6 +-- .../ro3/node/nodes/ode4j/odebody/ODEBox.java | 37 ++++++++++--------- 3 files changed, 25 insertions(+), 26 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index ed9428d23..f83569785 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -89,11 +89,11 @@ public static double volumeSphere(double radius) { return 4.0 / 3.0 * Math.PI * radius * radius * radius; } - public static JSONObject vector3ToJSON(DVector3C vector) { + public static JSONObject vector3ToJSON(Vector3d vector) { JSONObject json = new JSONObject(); - json.put("x", vector.get0()); - json.put("y", vector.get1()); - json.put("z", vector.get2()); + json.put("x", vector.x); + json.put("y", vector.y); + json.put("z", vector.z); return json; } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index 9118a2e9a..cde20117f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -133,10 +133,8 @@ public DBody getODEBody() { public JSONObject toJSON() { var json = super.toJSON(); json.put("mass", getMassQty()); - if(body!=null) { - json.put("avel", ODE4JHelper.vector3ToJSON(body.getAngularVel())); - json.put("lvel", ODE4JHelper.vector3ToJSON(body.getLinearVel())); - } + json.put("avel", ODE4JHelper.vector3ToJSON(angularVel)); + json.put("lvel", ODE4JHelper.vector3ToJSON(linearVel)); return json; } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java index 96d4d7376..5cbeb141d 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java @@ -9,6 +9,7 @@ import org.ode4j.ode.DBox; import javax.swing.*; +import javax.vecmath.Vector3d; import java.util.List; import static org.ode4j.ode.OdeHelper.createBox; @@ -17,7 +18,7 @@ * Wrapper for a ODE4J Box. */ public class ODEBox extends ODEBody { - private double sizeX=5.0, sizeY=5.0, sizeZ=5.0; + private final Vector3d size = new Vector3d(5,5,5); public ODEBox() { this("ODE Box"); @@ -38,10 +39,10 @@ protected void onFirstUpdate() { super.onFirstUpdate(); ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); - geom = createBox(physics.getODESpace(), sizeX, sizeY, sizeZ); + geom = createBox(physics.getODESpace(), size.x, size.y, size.z); geom.setBody(body); - mass.setBoxTotal(ODE4JHelper.volumeBox(sizeX,sizeY,sizeZ), sizeX, sizeY, sizeZ); + mass.setBoxTotal(ODE4JHelper.volumeBox(size.x,size.y,size.z), size.x, size.y, size.z); body.setMass(mass); if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); @@ -50,65 +51,65 @@ protected void onFirstUpdate() { } public double getSizeX() { - return sizeX; + return size.x; } public double getSizeY() { - return sizeY; + return size.y; } public double getSizeZ() { - return sizeZ; + return size.z; } public void setSizeX(double size) { if(size<=0) throw new IllegalArgumentException("Size must be greater than zero."); - this.sizeX = size; + this.size.x = size; updateSize(); } public void setSizeY(double size) { if(size<=0) throw new IllegalArgumentException("Size must be greater than zero."); - this.sizeY = size; + this.size.y = size; updateSize(); } public void setSizeZ(double size) { if(size<=0) throw new IllegalArgumentException("Size must be greater than zero."); - this.sizeZ = size; + this.size.z = size; updateSize(); } private void updateSize() { if(geom==null) return; - ((DBox)geom).setLengths(sizeX, sizeY, sizeZ); + ((DBox)geom).setLengths(size.x, size.y, size.z); geom.setBody(body); - mass.setBoxTotal(mass.getMass(), sizeX, sizeY, sizeZ); + mass.setBoxTotal(mass.getMass(), size.x, size.y, size.z); body.setMass(mass); var meshInstance = findFirstChild(MeshInstance.class); if(meshInstance!=null) { - meshInstance.setMesh(new Box(sizeX,sizeY,sizeZ)); + meshInstance.setMesh(new Box(size.x,size.y,size.z)); } } @Override public JSONObject toJSON() { var json= super.toJSON(); - json.put("sizeX", sizeX); - json.put("sizeY", sizeY); - json.put("sizeZ", sizeZ); + json.put("sizeX", size.x); + json.put("sizeY", size.y); + json.put("sizeZ", size.z); return json; } @Override public void fromJSON(JSONObject json) { super.fromJSON(json); - if(json.has("sizeX")) sizeX = json.getDouble("sizeX"); - if(json.has("sizeY")) sizeY = json.getDouble("sizeY"); - if(json.has("sizeZ")) sizeZ = json.getDouble("sizeZ"); + if(json.has("sizeX")) size.x = json.getDouble("sizeX"); + if(json.has("sizeY")) size.y = json.getDouble("sizeY"); + if(json.has("sizeZ")) size.z = json.getDouble("sizeZ"); updateSize(); } } From 2f1e79fb74fdaeab98432f14b117cd9acdf74706 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Sat, 27 Apr 2024 14:20:48 -0700 Subject: [PATCH 18/52] GUI to create procedural meshes --- .../nodes/pose/poses/MeshInstancePanel.java | 115 +++++++++++++++--- 1 file changed, 95 insertions(+), 20 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/MeshInstancePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/MeshInstancePanel.java index 66ecf8fa9..9988d5a31 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/MeshInstancePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/MeshInstancePanel.java @@ -1,15 +1,24 @@ package com.marginallyclever.ro3.node.nodes.pose.poses; import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.mesh.Mesh; import com.marginallyclever.ro3.mesh.MeshChooserDialog; import com.marginallyclever.ro3.mesh.MeshSmoother; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.mesh.shapes.*; +import com.marginallyclever.ro3.mesh.shapes.Box; import javax.swing.*; +import javax.swing.border.BevelBorder; import java.awt.*; +import java.awt.event.ActionListener; import java.io.File; +/** + * GUI for a {@link MeshInstance}. + */ public class MeshInstancePanel extends JPanel { + private final JPanel sourceContainer = new JPanel(new GridLayout(0,2)); private final MeshInstance meshInstance; public MeshInstancePanel() { @@ -17,45 +26,111 @@ public MeshInstancePanel() { } public MeshInstancePanel(MeshInstance meshInstance) { - super(new GridLayout(0,2)); + super(new GridBagLayout()); this.meshInstance = meshInstance; this.setName(MeshInstance.class.getSimpleName()); - var mesh = meshInstance.getMesh(); + GridBagConstraints gbc = new GridBagConstraints(); + gbc.weightx = 1.0; + gbc.weighty = 1.0; + gbc.gridx=0; + gbc.gridy=0; + gbc.fill = GridBagConstraints.BOTH; - JButton select = new JButton(); - setMeshButtonLabel(select); - select.addActionListener(e -> { - var meshChooserDialog = new MeshChooserDialog(); - meshChooserDialog.setSelectedItem(mesh); - int result = meshChooserDialog.run(this); - if(result == JFileChooser.APPROVE_OPTION) { - meshInstance.setMesh( meshChooserDialog.getSelectedItem() ); - setMeshButtonLabel(select); - } - }); - PanelHelper.addLabelAndComponent(this,"Mesh",select); + addMeshSource(gbc); + // mesh details + Mesh mesh = meshInstance.getMesh(); if(mesh!=null) { - PanelHelper.addLabelAndComponent(this,"Vertices",new JLabel(""+mesh.getNumVertices())); - PanelHelper.addLabelAndComponent(this,"Triangles",new JLabel(""+mesh.getNumTriangles())); + gbc.gridy++; + PanelHelper.addLabelAndComponent(this,"Vertices",new JLabel(""+mesh.getNumVertices()),gbc); + gbc.gridy++; + PanelHelper.addLabelAndComponent(this,"Triangles",new JLabel(""+mesh.getNumTriangles()),gbc); + gbc.gridy++; JButton smooth = new JButton("Smooth"); smooth.addActionListener(e -> MeshSmoother.smoothNormals(mesh,0.01f,0.25f) ); - PanelHelper.addLabelAndComponent(this,"Normals",smooth); + PanelHelper.addLabelAndComponent(this,"Normals",smooth,gbc); + gbc.gridy++; JButton adjust = new JButton("Adjust"); adjust.addActionListener(e -> meshInstance.adjustLocal()); - PanelHelper.addLabelAndComponent(this,"Local origin",adjust); + PanelHelper.addLabelAndComponent(this,"Local origin",adjust,gbc); + gbc.gridy++; JButton reload = new JButton("Reload"); reload.addActionListener(e-> Registry.meshFactory.reload(mesh) ); - PanelHelper.addLabelAndComponent(this,"Source",reload); + PanelHelper.addLabelAndComponent(this,"Source",reload,gbc); + } + } + + private void addMeshSource(GridBagConstraints gbc) { + // Create a list of available mesh sources + String[] meshSources = { "Procedural", "File" }; // replace with actual mesh sources + JComboBox meshSourceComboBox = new JComboBox<>(meshSources); + meshSourceComboBox.setSelectedItem("Procedural"); + meshSourceComboBox.addActionListener(e -> changeMeshSource(meshSourceComboBox)); + changeMeshSource(meshSourceComboBox); + + // Add the JComboBox to the panel + PanelHelper.addLabelAndComponent(this, "Mesh Source", meshSourceComboBox,gbc); + + sourceContainer.setBorder(BorderFactory.createBevelBorder(BevelBorder.LOWERED)); + gbc.gridy++; + gbc.gridwidth=2; + add(sourceContainer,gbc); + gbc.gridwidth=1; + } + + private void changeMeshSource(JComboBox meshSourceComboBox) { + sourceContainer.removeAll(); + String selectedMeshSource = (String) meshSourceComboBox.getSelectedItem(); + if(selectedMeshSource==null || selectedMeshSource.equals("File")) { + addFileMesh(); + } else if(selectedMeshSource.equals("Procedural")) { + addProceduralMesh(); + } else { + throw new RuntimeException("Unknown mesh source: "+selectedMeshSource); } + sourceContainer.revalidate(); + } + + private void addProceduralMesh() { + // Add a button to create a procedural mesh + addButton("+Box", e -> meshInstance.setMesh(new Box())); + addButton("+Sphere", e -> meshInstance.setMesh(new Sphere())); + addButton("+Cylinder", e -> meshInstance.setMesh(new Cylinder())); + addButton("+Capsule", e -> meshInstance.setMesh(new Capsule())); + } + + private void addButton(String label, ActionListener actionListener) { + JButton createBox = new JButton(label); + createBox.addActionListener(actionListener); + PanelHelper.addLabelAndComponent(sourceContainer,"Procedural",createBox); + } + + private void addFileMesh() { + JButton chooseMesh = new JButton(); + setMeshButtonLabel(chooseMesh); + chooseMesh.addActionListener(e -> { + var meshChooserDialog = new MeshChooserDialog(); + meshChooserDialog.setSelectedItem(meshInstance.getMesh()); + int result = meshChooserDialog.run(this); + if(result == JFileChooser.APPROVE_OPTION) { + meshInstance.setMesh( meshChooserDialog.getSelectedItem() ); + setMeshButtonLabel(chooseMesh); + } + }); + PanelHelper.addLabelAndComponent(sourceContainer,"File",chooseMesh); } private void setMeshButtonLabel(JButton button) { var mesh = meshInstance.getMesh(); - button.setText((mesh==null) ? "..." : mesh.getSourceName().substring(mesh.getSourceName().lastIndexOf(File.separatorChar)+1)); + if(mesh==null) { + button.setText("..."); + return; + } + var src = mesh.getSourceName().trim(); + button.setText(src.isEmpty() ? "..." : src.substring(src.lastIndexOf(File.separatorChar)+1)); } } From c10c8e4f6dba659a319db2ad108d6265a3bb130e Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Sat, 27 Apr 2024 14:21:40 -0700 Subject: [PATCH 19/52] 2.111.0 --- pom.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/pom.xml b/pom.xml index cf12dceca..17e012bd9 100644 --- a/pom.xml +++ b/pom.xml @@ -6,7 +6,7 @@ com.marginallyclever RobotOverlord - 2.110.2 + 2.111.0 Robot Overlord A friendly 3D user interface for controlling robots. https://www.marginallyclever.com/ @@ -481,7 +481,7 @@ org.ode4j core - 0.5.4-SNAPSHOT + 0.5.3-SNAPSHOT From f0352f88a9514da0b76b29cd65b76696f98d8b49 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 30 Apr 2024 13:57:06 -0700 Subject: [PATCH 20/52] remove duplicate action causing problems. --- .../com/marginallyclever/ro3/apps/actions/NewScene.java | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/apps/actions/NewScene.java b/src/main/java/com/marginallyclever/ro3/apps/actions/NewScene.java index 706e61b3f..3d1e6cc0a 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/actions/NewScene.java +++ b/src/main/java/com/marginallyclever/ro3/apps/actions/NewScene.java @@ -45,15 +45,7 @@ public void actionPerformed(ActionEvent e) { public void commitNewScene() { logger.info("New scene"); - // remove all children of the scene to make sure we're starting fresh. - Node oldScene = Registry.getScene(); - List toRemove = new ArrayList<>(oldScene.getChildren()); - for(Node child : toRemove) { - oldScene.removeChild(child); - } - Registry.reset(); - Registry.setScene(new Node("Scene")); if(saveScene!=null) saveScene.setEnabled(false); From 2a316595d150a4ac638e7ca46803feebc4a65fb6 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 30 Apr 2024 13:57:27 -0700 Subject: [PATCH 21/52] make explicit methods for some tasks --- .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 37 ++++++++++++------- 1 file changed, 24 insertions(+), 13 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index cde20117f..75ee4cbd9 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -13,7 +13,6 @@ import org.ode4j.ode.OdeHelper; import javax.swing.*; -import javax.vecmath.Matrix4d; import javax.vecmath.Vector3d; import java.util.List; import java.util.Objects; @@ -49,12 +48,18 @@ public void getComponents(List list) { @Override protected void onDetach() { super.onDetach(); + destroyBody(); + destroyGeom(); + } + + protected void destroyBody() { if(body != null) { - try { - body.destroy(); - } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. + body.destroy(); body = null; } + } + + protected void destroyGeom() { if(geom != null) { geom.destroy(); geom = null; @@ -68,15 +73,21 @@ protected void onFirstUpdate() { ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); body = OdeHelper.createBody(physics.getODEWorld()); mass = OdeHelper.createMass(); + mass.setZero(); updateMass(); - updatePoseFromPhysics(); + updatePhysicsFromPose(); } @Override public void update(double dt) { super.update(dt); - // adjust the position of the Node to match the body. + updatePoseFromPhysics(); + } + + protected void updatePoseFromPhysics() { + // adjust the position of the Node to match the body. This will + // cause the visual representation to match the physics representation. if(body == null) return; DVector3C translation = body.getPosition(); DMatrix3C rotation = body.getRotation(); @@ -84,12 +95,13 @@ public void update(double dt) { } @Override - public void setLocal(Matrix4d m) { - super.setLocal(m); - updatePoseFromPhysics(); + protected void updateChildPose() { + super.updateChildPose(); + // update the physics body to match the new pose. + updatePhysicsFromPose(); } - protected void updatePoseFromPhysics() { + protected void updatePhysicsFromPose() { if (body == null) return; var world = getWorld(); body.setPosition(world.m03, world.m13, world.m23); @@ -106,7 +118,6 @@ public double getMassQty() { } /** - * * @param massQty must be >= 0 */ public void setMassQty(double massQty) { @@ -118,7 +129,7 @@ public void setMassQty(double massQty) { private void updateMass() { if(mass==null || body==null) return; mass.setMass(massQty); - if(mass.check()) { + if(massQty>0 && mass.check()) { body.setMass(mass); body.setAngularVel(angularVel.x, angularVel.y, angularVel.z); body.setLinearVel(linearVel.x, linearVel.y, linearVel.z); @@ -145,7 +156,7 @@ public void fromJSON(JSONObject from) { if(from.has("mass")) setMassQty(from.getDouble("mass")); if(from.has("avel")) setAngularVel(ODE4JHelper.jsonToVector3(from.getJSONObject("avel"))); if(from.has("lvel")) setLinearVel(ODE4JHelper.jsonToVector3(from.getJSONObject("lvel"))); - updatePoseFromPhysics(); + updatePhysicsFromPose(); } public void setAngularVel(Vector3d angularVel) { From c8c05c6b8ffb529536aba7e064cedac6ffa7297e Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 30 Apr 2024 13:58:00 -0700 Subject: [PATCH 22/52] make explicit methods for some tasks --- .../ro3/node/nodes/ode4j/ODEHinge.java | 14 +++++++++++--- .../ro3/node/nodes/ode4j/ODENode.java | 2 +- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java index ca49ff3e2..9409cee0f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java @@ -50,9 +50,7 @@ public void getComponents(List list) { @Override protected void onFirstUpdate() { super.onFirstUpdate(); - var physics = ODE4JHelper.guaranteePhysicsWorld(); - hinge = OdeHelper.createHingeJoint(physics.getODEWorld(), null); - connect(); + createHinge(); } @Override @@ -63,6 +61,16 @@ protected void onReady() { @Override protected void onDetach() { super.onDetach(); + destroyHinge(); + } + + private void createHinge() { + var physics = ODE4JHelper.guaranteePhysicsWorld(); + hinge = OdeHelper.createHingeJoint(physics.getODEWorld(), null); + connect(); + } + + private void destroyHinge() { if(hinge!=null) { try { hinge.destroy(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java index 5dd66a69a..5ea79a7da 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java @@ -10,7 +10,7 @@ * after loading.

*

This class is responsible for calling {@link #onFirstUpdate()} once at the start of the first * {@link #update(double)}. No physics calculations should be done in the constructor or in {@link #onAttach()}.

- *

the flag to run #onFirstUpdate again will be reset if:

+ *

the flag to run {@link #onFirstUpdate()} again will be reset if:

*
    *
  • the node is detached
  • *
  • the node is deserialized
  • From a629664e6fa47a044abe5d0fca3182a681a8c3e1 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 30 Apr 2024 13:58:23 -0700 Subject: [PATCH 23/52] switch to ODE4J 0.5.3 --- pom.xml | 2 +- src/main/java/module-info.java | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/pom.xml b/pom.xml index 17e012bd9..e45191169 100644 --- a/pom.xml +++ b/pom.xml @@ -481,7 +481,7 @@ org.ode4j core - 0.5.3-SNAPSHOT + 0.5.3 diff --git a/src/main/java/module-info.java b/src/main/java/module-info.java index e617259bc..0160f02eb 100644 --- a/src/main/java/module-info.java +++ b/src/main/java/module-info.java @@ -28,9 +28,10 @@ requires batik.all; requires xml.apis.ext; requires java.datatransfer; - requires org.ode4j; + //requires org.ode4j.ode; requires flexmark.util.ast; requires webcam.capture; requires ch.qos.logback.classic; requires ch.qos.logback.core; + requires core; } \ No newline at end of file From e04e83f751472c9c9eedd46b1218f89c3f3fdee8 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 30 Apr 2024 13:58:44 -0700 Subject: [PATCH 24/52] update plane from Pose on load correctly --- .../ro3/node/nodes/ode4j/ODEPlane.java | 31 +++++++++++-------- 1 file changed, 18 insertions(+), 13 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index 7562505c5..71bb8af81 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -57,15 +57,19 @@ protected void onFirstUpdate() { addChild(material); } material.setTexture(Registry.textureFactory.load("/com/marginallyclever/ro3/shared/checkerboard.png")); + + updatePhysicsFromPose(); } @Override protected void onDetach() { super.onDetach(); + destroyPlane(); + } + + private void destroyPlane() { if(plane!=null) { - try { - plane.destroy(); - } catch(Exception ignored) {} // if the worldspace is destroyed first, this will throw an exception. + plane.destroy(); plane = null; } } @@ -93,13 +97,7 @@ public void update(double dt) { @Override public void setLocal(Matrix4d m) { super.setLocal(m); - if(plane==null) return; - - var world = getWorld(); - Vector3d normal = MatrixHelper.getZAxis(world); - Vector3d position = MatrixHelper.getPosition(world); - double depth = normal.dot(position); - plane.setParams(normal.x, normal.y, normal.z, depth); + updatePhysicsFromPose(); } @Override @@ -115,9 +113,16 @@ public JSONObject toJSON() { @Override public void fromJSON(JSONObject from) { super.fromJSON(from); + updatePhysicsFromPose(); + } - if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); - MeshInstance mesh = findFirstChild(MeshInstance.class); - mesh.setMesh(decal); + protected void updatePhysicsFromPose() { + if (plane == null) return; + + var world = getWorld(); + Vector3d normal = MatrixHelper.getZAxis(world); + Vector3d position = MatrixHelper.getPosition(world); + double depth = normal.dot(position); + plane.setParams(normal.x, normal.y, normal.z, depth); } } From c32899c8acbef391a9e67b81ca0c5b880792c031 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 30 Apr 2024 20:05:30 -0700 Subject: [PATCH 25/52] RagDog now works. --- .../ro3/node/nodes/ode4j/ODE4JHelper.java | 5 ++--- .../ro3/node/nodes/ode4j/ODEPlane.java | 6 ------ .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 20 +++++++++---------- .../ode4j/{ => odebody}/ODEBodyPanel.java | 4 +--- .../ro3/node/nodes/pose/Pose.java | 1 + 5 files changed, 13 insertions(+), 23 deletions(-) rename src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/{ => odebody}/ODEBodyPanel.java (83%) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index f83569785..6c263aed4 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -4,7 +4,6 @@ import org.json.JSONObject; import org.ode4j.math.DMatrix3; import org.ode4j.math.DMatrix3C; -import org.ode4j.math.DVector3; import org.ode4j.math.DVector3C; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -24,7 +23,7 @@ public class ODE4JHelper { * @param rotation the rotation matrix * @return the Java3D matrix. */ - public static Matrix4d assembleMatrix(DVector3C translation, DMatrix3C rotation) { + public static Matrix4d convertODEtoMatrix(DVector3C translation, DMatrix3C rotation) { // assemble matrix from translation and rotation. Matrix4d m = new Matrix4d(); m.m00 = rotation.get00(); @@ -49,7 +48,7 @@ public static Matrix4d assembleMatrix(DVector3C translation, DMatrix3C rotation) /** * receive a 4x4 matrix. extract the rotation component and store it in a DMatrix3C. * @param mat the 4x4 matrix. - * @return the rotation component. + * @return the rotation component as a 3x3 matrix. */ public static DMatrix3C convertRotationToODE(Matrix4d mat) { return new DMatrix3( diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index 71bb8af81..d857ec2fe 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -94,12 +94,6 @@ public void update(double dt) { super.setWorld(m4); } - @Override - public void setLocal(Matrix4d m) { - super.setLocal(m); - updatePhysicsFromPose(); - } - @Override public Icon getIcon() { return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index 75ee4cbd9..2f12e9f26 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -1,7 +1,6 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEBodyPanel; import com.marginallyclever.ro3.node.nodes.ode4j.ODENode; import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; import org.json.JSONObject; @@ -85,22 +84,21 @@ public void update(double dt) { updatePoseFromPhysics(); } + /** + * Adjust the position of the Node to match the body. This will cause the visual representation to match the + * physics representation. + */ protected void updatePoseFromPhysics() { - // adjust the position of the Node to match the body. This will - // cause the visual representation to match the physics representation. if(body == null) return; DVector3C translation = body.getPosition(); DMatrix3C rotation = body.getRotation(); - super.setWorld(ODE4JHelper.assembleMatrix(translation, rotation)); - } - - @Override - protected void updateChildPose() { - super.updateChildPose(); - // update the physics body to match the new pose. - updatePhysicsFromPose(); + super.setWorld(ODE4JHelper.convertODEtoMatrix(translation, rotation)); } + /** + * Update the physics body to match the Pose. This will cause the physics representation to match the visual + * representation. + */ protected void updatePhysicsFromPose() { if (body == null) return; var world = getWorld(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBodyPanel.java similarity index 83% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBodyPanel.java index b43fbfe7b..5e7c3ba46 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEBodyPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBodyPanel.java @@ -1,9 +1,7 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODESphere; import javax.swing.*; import java.awt.*; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java index dca949608..04cd20c0f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/Pose.java @@ -11,6 +11,7 @@ import javax.vecmath.Vector3d; import java.util.List; import java.util.Objects; +import java.util.Queue; /** *

    A {@link Pose} is a {@link Node} that has a position and rotation in space.

    From fdf3a930c8f3eb35cb972e71f09000d3442ec7fb Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 30 Apr 2024 21:05:20 -0700 Subject: [PATCH 26/52] addTorque() and first GUI --- .../ro3/node/nodes/ode4j/ODEHinge.java | 8 ++++++++ .../ro3/node/nodes/ode4j/ODEHingePanel.java | 16 ++++++++++++++++ 2 files changed, 24 insertions(+) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java index 9409cee0f..32336b80b 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java @@ -183,4 +183,12 @@ public void fromJSON(JSONObject from) { connect(); updateHingePose(); } + + public void addTorque(double value) { + if(hinge==null) return; + var physics = ODE4JHelper.guaranteePhysicsWorld(); + if(!physics.isPaused()) { + hinge.addTorque(value); + } + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java index d729ab63f..93c346830 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java @@ -9,6 +9,7 @@ import javax.swing.*; import java.awt.*; +import java.awt.event.ActionListener; import java.util.function.Consumer; /** @@ -25,6 +26,7 @@ public ODEHingePanel(ODEHinge hinge) { addSelector("part A",hinge.getPartA(),hinge::setPartA); addSelector("part B",hinge.getPartB(),hinge::setPartB); + addAction("Torque",hinge); } private void addSelector(String label, NodePath originalValue, Consumer setPartA) { @@ -32,4 +34,18 @@ private void addSelector(String label, NodePath originalValue, Consumer selector.addPropertyChangeListener("subject", (evt) ->setPartA.accept((ODEBody)evt.getNewValue())); PanelHelper.addLabelAndComponent(this, label,selector); } + + private void addAction(String label,ODEHinge hinge) { + JPanel panel = new JPanel(new FlowLayout()); + + JButton selector = new JButton("+"); + selector.addActionListener((e)-> hinge.addTorque(250000)); + panel.add(selector); + + JButton selector2 = new JButton("-"); + selector2.addActionListener((e)-> hinge.addTorque(-250000)); + panel.add(selector2); + + PanelHelper.addLabelAndComponent(this, label, panel); + } } From 46b59cea58d93d1473a1800e5936c65c4549f2ee Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 1 May 2024 06:44:54 -0700 Subject: [PATCH 27/52] fix hinge test --- .../marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java index 87fc0f347..29b633380 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java @@ -13,6 +13,7 @@ public class ODEHingeTest { public void test() { Registry.start(); Node scene = Registry.getScene(); + ODE4JHelper.guaranteePhysicsWorld(); ODEBox box1 = new ODEBox("b1"); scene.addChild(box1); ODEBox box2 = new ODEBox("b2"); @@ -21,11 +22,11 @@ public void test() { scene.addChild(hinge1); ODEHinge hinge2 = new ODEHinge("h2"); scene.addChild(hinge2); + scene.update(0); hinge1.setPartB(box1); hinge2.setPartA(box1); hinge2.setPartB(box2); - assertOneWorldSpaceInScene(scene); // make a deep copy to/from json and confirm the links are still attached. From b2d54a4c32565a6d2635bceb714ed2f4ab7e785d Mon Sep 17 00:00:00 2001 From: github-actions <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 1 May 2024 13:48:01 +0000 Subject: [PATCH 28/52] commit badge --- .github/badges/branches.svg | 2 +- .github/badges/jacoco.svg | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/badges/branches.svg b/.github/badges/branches.svg index 6dcfc667e..6ec7d76c2 100644 --- a/.github/badges/branches.svg +++ b/.github/badges/branches.svg @@ -1 +1 @@ -branches18.2% \ No newline at end of file +branches18.6% \ No newline at end of file diff --git a/.github/badges/jacoco.svg b/.github/badges/jacoco.svg index 59f6c5bf4..d14e4c984 100644 --- a/.github/badges/jacoco.svg +++ b/.github/badges/jacoco.svg @@ -1 +1 @@ -coverage19.7% \ No newline at end of file +coverage20.3% \ No newline at end of file From 9d8f92fb6e9b619ebe3764f7a67e861c655d1020 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Thu, 2 May 2024 10:45:10 -0700 Subject: [PATCH 29/52] Move ODEWorldSpace to ODEPhysics --- .../com/marginallyclever/ro3/AllPanels.java | 4 +- .../com/marginallyclever/ro3/Registry.java | 8 +- .../ro3/apps/ode4j/ODE4JPanel.java | 21 +++-- .../apps/viewport/ViewportSettingsPanel.java | 4 - .../com/marginallyclever/ro3/node/Node.java | 2 +- .../node/nodes/ode4j/CollisionListener.java | 19 +++++ .../node/nodes/ode4j/CreatureController.java | 80 +++++++++++++++++++ .../nodes/ode4j/CreatureControllerPanel.java | 42 ++++++++++ .../ro3/node/nodes/ode4j/ODE4JHelper.java | 11 +-- .../ro3/node/nodes/ode4j/ODENode.java | 3 +- .../ro3/node/nodes/ode4j/ODEPlane.java | 3 +- .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 17 +++- .../ro3/node/nodes/ode4j/odebody/ODEBox.java | 8 +- .../node/nodes/ode4j/odebody/ODECapsule.java | 8 +- .../node/nodes/ode4j/odebody/ODECylinder.java | 7 +- .../node/nodes/ode4j/odebody/ODESphere.java | 7 +- .../ODEPhysics.java} | 80 +++++++++++++------ .../ode4j => physics}/ODEWorldSpacePanel.java | 10 +-- .../ro3/node/nodes/ode4j/ODEHingeTest.java | 4 +- 19 files changed, 261 insertions(+), 77 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CollisionListener.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureControllerPanel.java rename src/main/java/com/marginallyclever/ro3/{node/nodes/ode4j/ODEWorldSpace.java => physics/ODEPhysics.java} (60%) rename src/main/java/com/marginallyclever/ro3/{node/nodes/ode4j => physics}/ODEWorldSpacePanel.java (83%) diff --git a/src/main/java/com/marginallyclever/ro3/AllPanels.java b/src/main/java/com/marginallyclever/ro3/AllPanels.java index 53be99375..c2b266334 100644 --- a/src/main/java/com/marginallyclever/ro3/AllPanels.java +++ b/src/main/java/com/marginallyclever/ro3/AllPanels.java @@ -1,8 +1,8 @@ package com.marginallyclever.ro3; import com.formdev.flatlaf.FlatLightLaf; +import com.marginallyclever.ro3.physics.ODEWorldSpacePanel; import org.reflections.Reflections; -import org.reflections.util.ClasspathHelper; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -102,7 +102,7 @@ private Collection> getHandmadeList() { com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlannerPanel.class, com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolverPanel.class, com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArmPanel.class, - com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpacePanel.class, + ODEWorldSpacePanel.class, com.marginallyclever.ro3.node.nodes.pose.PosePanel.class, com.marginallyclever.ro3.node.nodes.pose.poses.AttachmentPointPanel.class, com.marginallyclever.ro3.node.nodes.pose.poses.CameraPanel.class, diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index 2f74b8254..c7a98b401 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -13,13 +13,14 @@ import com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlanner; import com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolver; import com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArm; +import com.marginallyclever.ro3.node.nodes.ode4j.CreatureController; import com.marginallyclever.ro3.node.nodes.ode4j.ODEHinge; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; import com.marginallyclever.ro3.node.nodes.ode4j.ODEPlane; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODECapsule; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODECylinder; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODESphere; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; +import com.marginallyclever.ro3.physics.ODEPhysics; import com.marginallyclever.ro3.node.nodes.pose.*; import com.marginallyclever.ro3.node.nodes.pose.poses.*; import com.marginallyclever.ro3.texture.TextureFactory; @@ -41,6 +42,7 @@ public class Registry { public static final ListWithEvents cameras = new ListWithEvents<>(); private static Camera activeCamera = null; public static final ListWithEvents selection = new ListWithEvents<>(); + public static final ODEPhysics physics = new ODEPhysics(); public static void start() { nodeFactory.clear(); @@ -84,7 +86,8 @@ public static void start() { } NodeFactory.Category physics = node.add("Physics", null); { - physics.add("ODEWorldSpace", ODEWorldSpace::new); + physics.add("CreatureController", CreatureController::new); + physics.add("ODEWorldSpace", ODEPhysics::new); physics.add("ODEBox", ODEBox::new); physics.add("ODECapsule", ODECapsule::new); physics.add("ODECylinder", ODECylinder::new); @@ -117,6 +120,7 @@ public static void reset() { textureFactory.reset(); meshFactory.reset(); + physics.reset(); scene = new Node("Scene"); } diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index b93b44bcb..16c2a6d69 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -3,10 +3,12 @@ import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.App; +import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.*; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.*; import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.physics.ODEPhysics; import javax.swing.*; import javax.vecmath.Matrix4d; @@ -32,7 +34,7 @@ public ODE4JPanel() { add(container, BorderLayout.CENTER); JButton pauseButton = addButtonByNameAndCallback(toolbar, "", (e)->{ - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); physics.setPaused(!physics.isPaused()); updatePauseButton((JButton)e.getSource(), physics); }); @@ -59,13 +61,18 @@ public ODE4JPanel() { addButtonByNameAndCallback(container, "+Cylinder", (e)-> add(new ODECylinder()) ); addButtonByNameAndCallback(container, "+Capsule", (e)->add(new ODECapsule()) ); addButtonByNameAndCallback(container, "+Hinge", (e)-> add(new ODEHinge()) ); + addButtonByNameAndCallback(container, "+Creature controller", (e)-> add(new CreatureController()) ); } - private void add(Pose body) { - ODE4JHelper.guaranteePhysicsWorld(); - Registry.getScene().addChild(body); - placeBodyAbovePlane(body); - if(randomColor) giveRandomColor(body); + private void add(Node node) { + if(node instanceof Pose body) { + ODE4JHelper.guaranteePhysicsWorld(); + Registry.getScene().addChild(body); + placeBodyAbovePlane(body); + if(randomColor) giveRandomColor(body); + } else { + Registry.getScene().addChild(node); + } } private void placeBodyAbovePlane(Pose body) { @@ -103,7 +110,7 @@ private JButton addButtonByNameAndCallback(JComponent parent, String title, Acti return button; } - private void updatePauseButton(JButton pauseButton, ODEWorldSpace worldSpace) { + private void updatePauseButton(JButton pauseButton, ODEPhysics worldSpace) { if (worldSpace.isPaused()) { pauseButton.setToolTipText("Unpause"); pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png")))); diff --git a/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java b/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java index 3344ea208..5f8d39379 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java @@ -1,6 +1,5 @@ package com.marginallyclever.ro3.apps.viewport; -import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.convenience.swing.Dial; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; @@ -10,9 +9,6 @@ import javax.swing.*; import javax.swing.text.NumberFormatter; -import javax.vecmath.Matrix3d; -import javax.vecmath.Matrix4d; -import javax.vecmath.Vector3d; import java.awt.*; /** diff --git a/src/main/java/com/marginallyclever/ro3/node/Node.java b/src/main/java/com/marginallyclever/ro3/node/Node.java index 9620ccb6a..4a188ac90 100644 --- a/src/main/java/com/marginallyclever/ro3/node/Node.java +++ b/src/main/java/com/marginallyclever/ro3/node/Node.java @@ -162,7 +162,7 @@ public void setName(String name) { } /** - * @return an iterator so that calling class cannot modify the list. + * @return the original list. This is not a copy. This is dangerous! */ public List getChildren() { return children; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CollisionListener.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CollisionListener.java new file mode 100644 index 000000000..8ac68d881 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CollisionListener.java @@ -0,0 +1,19 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import org.ode4j.ode.DContact; +import org.ode4j.ode.DGeom; + +import java.util.EventListener; + +/** + * Listens for collisions between objects in the ODE physics world. + */ +public interface CollisionListener extends EventListener { + /** + * Called when two objects collide. + * @param g1 The first object + * @param g2 The second object + * @param contact The contact information + */ + void onCollision(DGeom g1, DGeom g2, DContact contact); +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java new file mode 100644 index 000000000..4ef50bf24 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java @@ -0,0 +1,80 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; +import org.ode4j.ode.DContact; +import org.ode4j.ode.DGeom; + +import javax.swing.*; +import java.util.ArrayList; +import java.util.HashSet; +import java.util.List; +import java.util.Set; + +/** + *

    A controller for a creature made of ODE4J hinges and bodies.

    + *

    This controller registers itself to receive collision events from the physics world.

    + * + */ +public class CreatureController extends Node implements CollisionListener { + public CreatureController() { + super("CreatureController"); + } + + public CreatureController(String name) { + super(name); + } + + @Override + public void getComponents(List list) { + list.add(new CreatureControllerPanel(this)); + super.getComponents(list); + } + + /** + * @return A list of all the hinges that are connected to this creature. + */ + public List findHinges() { + List hinges = new ArrayList<>(); + List toSearch = new ArrayList<>(getChildren()); + while(!toSearch.isEmpty()) { + Node node = toSearch.remove(0); + toSearch.addAll(node.getChildren()); + + if(node instanceof ODEHinge hinge) { + hinges.add(hinge); + } + } + return hinges; + } + + @Override + protected void onDetach() { + super.onDetach(); + ODE4JHelper.guaranteePhysicsWorld().removeCollisionListener(this); + } + + /** + * @return A set of all the bodies that are connected to hinges of this creature. + */ + public Set findBodies() { + Set bodies = new HashSet<>(); + List hinges = findHinges(); + for(ODEHinge hinge : hinges) { + bodies.add(hinge.getPartA().getSubject()); + bodies.add(hinge.getPartB().getSubject()); + } + return bodies; + } + + @Override + public void onCollision(DGeom g1, DGeom g2, DContact contact) { + var bodies = findBodies(); + for(ODEBody b : bodies) { + if(b.getGeom() == g1 || b.getGeom() == g2) { + // b is touching something + // TODO finish me! + } + } + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureControllerPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureControllerPanel.java new file mode 100644 index 000000000..8a28817f5 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureControllerPanel.java @@ -0,0 +1,42 @@ +package com.marginallyclever.ro3.node.nodes.ode4j; + +import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.node.Node; + +import java.util.ArrayList; +import java.util.List; +import javax.swing.*; +import java.awt.*; + +/** + * A panel for controlling an ODE4J creature. + */ +public class CreatureControllerPanel extends JPanel { + public CreatureControllerPanel() { + this(new CreatureController()); + } + + public CreatureControllerPanel(CreatureController creatureController) { + super(new GridLayout(0,2)); + setName(CreatureController.class.getSimpleName()); + + List toSearch = creatureController.findHinges(); + for(ODEHinge hinge : toSearch) { + addAction(hinge.getName(),hinge); + } + } + + private void addAction(String label,ODEHinge hinge) { + JPanel panel = new JPanel(new FlowLayout(FlowLayout.CENTER,5,0)); + + JButton selector = new JButton("+"); + selector.addActionListener((e)-> hinge.addTorque(250000)); + panel.add(selector); + + JButton selector2 = new JButton("-"); + selector2.addActionListener((e)-> hinge.addTorque(-250000)); + panel.add(selector2); + + PanelHelper.addLabelAndComponent(this, label, panel); + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java index 6c263aed4..71fe3acc7 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java @@ -1,6 +1,7 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.physics.ODEPhysics; import org.json.JSONObject; import org.ode4j.math.DMatrix3; import org.ode4j.math.DMatrix3C; @@ -59,14 +60,14 @@ public static DMatrix3C convertRotationToODE(Matrix4d mat) { } /** - * Gurantee there is exactly one {@link ODEWorldSpace} in the scene. - * @return the {@link ODEWorldSpace}. + * Gurantee there is exactly one {@link ODEPhysics} in the scene. + * @return the {@link ODEPhysics}. */ - public static ODEWorldSpace guaranteePhysicsWorld() { - ODEWorldSpace physics = Registry.getScene().findFirstChild(ODEWorldSpace.class); + public static ODEPhysics guaranteePhysicsWorld() { + ODEPhysics physics = Registry.getScene().findFirstChild(ODEPhysics.class); if (physics == null) { logger.debug("Creating PhysicsWorld"); - physics = new ODEWorldSpace(); + physics = new ODEPhysics(); Registry.getScene().addChild(physics); } return physics; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java index 5ea79a7da..49fb45507 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java @@ -53,7 +53,8 @@ public void fromJSON(JSONObject from) { } /** - * Called once at the start of the first {@link #update(double)} + * Called once at the start of the first {@link #update(double)}. + * Override this to do any setup that requires all subjects to be present. */ protected void onFirstUpdate() { // override me diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index d857ec2fe..2d6b06a45 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -5,6 +5,7 @@ import com.marginallyclever.ro3.mesh.shapes.Decal; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; +import com.marginallyclever.ro3.physics.ODEPhysics; import org.json.JSONObject; import org.ode4j.ode.DPlane; import org.ode4j.ode.OdeHelper; @@ -41,7 +42,7 @@ public ODEPlane(String name) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); plane = OdeHelper.createPlane(physics.getODESpace(), 0, 0, 1, 0); MeshInstance mesh = findFirstChild(MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index 2f12e9f26..4a15ae4a7 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -1,8 +1,10 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.ode4j.ODENode; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; +import com.marginallyclever.ro3.physics.ODEPhysics; +import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.math.DMatrix3C; import org.ode4j.math.DVector3C; @@ -44,6 +46,13 @@ public void getComponents(List list) { super.getComponents(list); } + @Override + protected void onAttach() { + super.onAttach(); + if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); + if(findFirstChild(Material.class)==null) addChild(new Material()); + } + @Override protected void onDetach() { super.onDetach(); @@ -69,7 +78,7 @@ protected void destroyGeom() { * Called once at the start of the first {@link #update(double)} */ protected void onFirstUpdate() { - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); body = OdeHelper.createBody(physics.getODEWorld()); mass = OdeHelper.createMass(); mass.setZero(); @@ -166,4 +175,8 @@ public void setLinearVel(Vector3d linearVel) { this.linearVel.set(linearVel); if(body!=null) body.setLinearVel(linearVel.x, linearVel.y, linearVel.z); } + + public DGeom getGeom() { + return geom; + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java index 5cbeb141d..f41292927 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java @@ -1,9 +1,8 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.ro3.mesh.shapes.Box; -import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; +import com.marginallyclever.ro3.physics.ODEPhysics; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DBox; @@ -38,15 +37,12 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); geom = createBox(physics.getODESpace(), size.x, size.y, size.z); geom.setBody(body); mass.setBoxTotal(ODE4JHelper.volumeBox(size.x,size.y,size.z), size.x, size.y, size.z); body.setMass(mass); - - if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); - if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java index 26b075788..0781fc63d 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java @@ -2,10 +2,8 @@ import com.marginallyclever.ro3.mesh.shapes.Capsule; import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEHinge; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; +import com.marginallyclever.ro3.physics.ODEPhysics; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DCapsule; @@ -40,15 +38,13 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); geom = OdeHelper.createCapsule(physics.getODESpace(), radius, length); geom.setBody(body); mass.setCapsuleTotal(ODE4JHelper.volumeCapsule(radius,length), 3, radius, length); body.setMass(mass); - if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); - if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java index 38479e0f8..92517d06d 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java @@ -1,9 +1,8 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.ro3.mesh.shapes.Cylinder; -import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; +import com.marginallyclever.ro3.physics.ODEPhysics; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DCylinder; @@ -37,15 +36,13 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); geom = OdeHelper.createCylinder(physics.getODESpace(), radius, length); geom.setBody(body); mass.setCylinderTotal(ODE4JHelper.volumeCylinder(radius,length), 3, radius, length); body.setMass(mass); - if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); - if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java index b8a0c4e51..d0d5d6bb4 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java @@ -1,9 +1,8 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEWorldSpace; +import com.marginallyclever.ro3.physics.ODEPhysics; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DSphere; @@ -37,15 +36,13 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEWorldSpace physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); geom = createSphere(physics.getODESpace(), radius); geom.setBody(body); mass.setSphereTotal(ODE4JHelper.volumeSphere(radius), radius); body.setMass(mass); - if(findFirstChild(MeshInstance.class)==null) addChild(new MeshInstance()); - if(findFirstChild(Material.class)==null) addChild(new Material()); updateSize(); } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java similarity index 60% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java rename to src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java index dc7f4f121..f2c7265c1 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpace.java +++ b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java @@ -1,12 +1,14 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.physics; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.ode4j.CollisionListener; import org.ode4j.ode.*; import org.slf4j.Logger; import org.slf4j.LoggerFactory; import javax.swing.*; +import javax.swing.event.EventListenerList; import java.util.List; import java.util.Objects; @@ -17,8 +19,8 @@ * Manages the ODE4J physics world, space, and contact handling. There must be exactly one of these in the scene * for physics to work. */ -public class ODEWorldSpace extends Node { - private static final Logger logger = LoggerFactory.getLogger(ODEWorldSpace.class); +public class ODEPhysics extends Node { + private static final Logger logger = LoggerFactory.getLogger(ODEPhysics.class); public double WORLD_CFM = 1e-5; public double WORLD_ERP = 0.8; @@ -32,11 +34,13 @@ public class ODEWorldSpace extends Node { private DJointGroup contactGroup; private boolean isPaused = true; - public ODEWorldSpace() { + protected final EventListenerList listeners = new EventListenerList(); + + public ODEPhysics() { this("ODEWorldSpace"); } - public ODEWorldSpace(String name) { + public ODEPhysics(String name) { super(name); } @@ -131,8 +135,12 @@ public void update(double dt) { } } - // this is called by dSpaceCollide when two objects in space are - // potentially colliding. + /** + * This is called by ODE4J's dSpaceCollide when two objects in space are potentially colliding. + * @param data user data + * @param o1 the first object + * @param o2 the second object + */ private void nearCallback(Object data, DGeom o1, DGeom o2) { DBody b1 = o1.getBody(); DBody b2 = o2.getBody(); @@ -140,30 +148,53 @@ private void nearCallback(Object data, DGeom o1, DGeom o2) { return; try { - ODEWorldSpace physics = Registry.getScene().findFirstChild(ODEWorldSpace.class); + ODEPhysics physics = Registry.getScene().findFirstChild(ODEPhysics.class); int n = OdeHelper.collide(o1, o2, CONTACT_BUFFER_SIZE, contacts.getGeomBuffer()); - if (n > 0) { - for (int i = 0; i < n; i++) { - DContact contact = contacts.get(i); - contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; - - contact.surface.mu = 0.5; // friction - contact.surface.slip1 = 0.0; // how much the contact surfaces can slide - contact.surface.slip2 = 0.0; // how much the contact surfaces can slide - contact.surface.soft_erp = 0.8; // how spongy the contact is - contact.surface.soft_cfm = 0.001; // how soft to make the contact - contact.surface.bounce = 0.9; // how much the contact surfaces can bounce - contact.surface.bounce_vel = 0.5; // how fast the contact surfaces can bounce - DJoint contactJoint = OdeHelper.createContactJoint(physics.getODEWorld(), contactGroup, contact); - contactJoint.attach(o1.getBody(), o2.getBody()); - } + for (int i = 0; i < n; ++i) { + DContact contact = contacts.get(i); + contact.surface.mode = dContactSlip1 | dContactSlip2 | dContactSoftERP | dContactSoftCFM | dContactApprox1; + + contact.surface.mu = 0.5; // friction + contact.surface.slip1 = 0.0; // how much the contact surfaces can slide + contact.surface.slip2 = 0.0; // how much the contact surfaces can slide + contact.surface.soft_erp = 0.8; // how spongy the contact is + contact.surface.soft_cfm = 0.001; // how soft to make the contact + contact.surface.bounce = 0.9; // how much the contact surfaces can bounce + contact.surface.bounce_vel = 0.5; // how fast the contact surfaces can bounce + + DJoint contactJoint = OdeHelper.createContactJoint(physics.getODEWorld(), contactGroup, contact); + contactJoint.attach(o1.getBody(), o2.getBody()); + + // inform any listeners that a collision has occurred. Use the DGeom to find the associated ODENode + // and use teh ODENode in the notification. + fireCollisionEvent(o1,o2,contact); } } catch (Exception e) { logger.error("collision failed.", e); } } + /** + * Notify all listeners that a collision has occurred. + * @param g1 the first object + * @param g2 the second object + * @param contact the contact information + */ + private void fireCollisionEvent(DGeom g1,DGeom g2,DContact contact) { + for(CollisionListener listener : listeners.getListeners(CollisionListener.class)) { + listener.onCollision(g1,g2,contact); + } + } + + public void addCollisionListener(CollisionListener listener) { + listeners.add(CollisionListener.class, listener); + } + + public void removeCollisionListener(CollisionListener listener) { + listeners.remove(CollisionListener.class, listener); + } + @Override public Icon getIcon() { return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); @@ -176,4 +207,7 @@ public boolean isPaused() { public void setPaused(boolean state) { isPaused = state; } + + public void reset() { + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpacePanel.java b/src/main/java/com/marginallyclever/ro3/physics/ODEWorldSpacePanel.java similarity index 83% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpacePanel.java rename to src/main/java/com/marginallyclever/ro3/physics/ODEWorldSpacePanel.java index 557dd7418..21b557f6c 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEWorldSpacePanel.java +++ b/src/main/java/com/marginallyclever/ro3/physics/ODEWorldSpacePanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.physics; import com.marginallyclever.ro3.PanelHelper; import org.slf4j.Logger; @@ -16,12 +16,12 @@ public class ODEWorldSpacePanel extends JPanel { private static final Logger logger = LoggerFactory.getLogger(ODEWorldSpacePanel.class); public ODEWorldSpacePanel() { - this(new ODEWorldSpace()); + this(new ODEPhysics()); } - public ODEWorldSpacePanel(ODEWorldSpace worldSpace) { + public ODEWorldSpacePanel(ODEPhysics worldSpace) { super(new GridLayout(0,2)); - this.setName(ODEWorldSpace.class.getSimpleName()); + this.setName(ODEPhysics.class.getSimpleName()); // toggle button to pause/unpause the simulation JButton pauseButton = new JButton(); @@ -34,7 +34,7 @@ public ODEWorldSpacePanel(ODEWorldSpace worldSpace) { PanelHelper.addLabelAndComponent(this,"Active",pauseButton); } - private void updatePauseButton(JButton pauseButton, ODEWorldSpace worldSpace) { + private void updatePauseButton(JButton pauseButton, ODEPhysics worldSpace) { if (worldSpace.isPaused()) { pauseButton.setToolTipText("Play"); pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png")))); diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java index 29b633380..ea845a61b 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java @@ -3,10 +3,10 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; +import com.marginallyclever.ro3.physics.ODEPhysics; import org.json.JSONObject; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; -import org.ode4j.ode.OdeHelper; public class ODEHingeTest { @Test @@ -42,7 +42,7 @@ private void assertOneWorldSpaceInScene(Node scene) { // count the instances of ODEWorldSpace in scene. int count = 0; for(Node n : scene.getChildren()) { - if(n instanceof ODEWorldSpace) { + if(n instanceof ODEPhysics) { count++; } } From 0fb8b9b3e5903145505aab3571542abc119e334a Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Thu, 2 May 2024 11:11:19 -0700 Subject: [PATCH 30/52] moved ODE4JHelper to physics package --- .../com/marginallyclever/ro3/AllPanels.java | 4 +- .../com/marginallyclever/ro3/Registry.java | 7 ++- .../ro3/apps/ode4j/ODE4JPanel.java | 3 +- .../ro3/apps/viewport/Viewport.java | 1 + .../node/nodes/ode4j/CreatureController.java | 3 +- .../ro3/node/nodes/ode4j/ODEHinge.java | 17 +++---- .../ro3/node/nodes/ode4j/ODEPlane.java | 3 +- .../ro3/node/nodes/ode4j/odebody/ODEBody.java | 7 ++- .../ro3/node/nodes/ode4j/odebody/ODEBox.java | 7 ++- .../node/nodes/ode4j/odebody/ODECapsule.java | 7 ++- .../node/nodes/ode4j/odebody/ODECylinder.java | 7 ++- .../node/nodes/ode4j/odebody/ODESphere.java | 7 ++- .../nodes/ode4j => physics}/ODE4JHelper.java | 18 +------ .../ro3/physics/ODEPhysics.java | 42 ++--------------- .../ro3/physics/ODEWorldSpacePanel.java | 46 ------------------ .../ro3/node/nodes/ode4j/ODEHingeTest.java | 47 ++++++++++--------- 16 files changed, 67 insertions(+), 159 deletions(-) rename src/main/java/com/marginallyclever/ro3/{node/nodes/ode4j => physics}/ODE4JHelper.java (81%) delete mode 100644 src/main/java/com/marginallyclever/ro3/physics/ODEWorldSpacePanel.java diff --git a/src/main/java/com/marginallyclever/ro3/AllPanels.java b/src/main/java/com/marginallyclever/ro3/AllPanels.java index c2b266334..471a91e8f 100644 --- a/src/main/java/com/marginallyclever/ro3/AllPanels.java +++ b/src/main/java/com/marginallyclever/ro3/AllPanels.java @@ -1,7 +1,7 @@ package com.marginallyclever.ro3; import com.formdev.flatlaf.FlatLightLaf; -import com.marginallyclever.ro3.physics.ODEWorldSpacePanel; +import com.marginallyclever.ro3.physics.ODEPhysicsPanel; import org.reflections.Reflections; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -102,7 +102,7 @@ private Collection> getHandmadeList() { com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlannerPanel.class, com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolverPanel.class, com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArmPanel.class, - ODEWorldSpacePanel.class, + ODEPhysicsPanel.class, com.marginallyclever.ro3.node.nodes.pose.PosePanel.class, com.marginallyclever.ro3.node.nodes.pose.poses.AttachmentPointPanel.class, com.marginallyclever.ro3.node.nodes.pose.poses.CameraPanel.class, diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index c7a98b401..86a5fce58 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -42,7 +42,7 @@ public class Registry { public static final ListWithEvents cameras = new ListWithEvents<>(); private static Camera activeCamera = null; public static final ListWithEvents selection = new ListWithEvents<>(); - public static final ODEPhysics physics = new ODEPhysics(); + private static final ODEPhysics physics = new ODEPhysics(); public static void start() { nodeFactory.clear(); @@ -87,7 +87,6 @@ public static void start() { NodeFactory.Category physics = node.add("Physics", null); { physics.add("CreatureController", CreatureController::new); - physics.add("ODEWorldSpace", ODEPhysics::new); physics.add("ODEBox", ODEBox::new); physics.add("ODECapsule", ODECapsule::new); physics.add("ODECylinder", ODECylinder::new); @@ -163,4 +162,8 @@ public static Camera getActiveCamera() { public static void setActiveCamera(Camera camera) { activeCamera = camera; } + + public static ODEPhysics getPhysics() { + return physics; + } } diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index 16c2a6d69..5c54d8b98 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -34,7 +34,7 @@ public ODE4JPanel() { add(container, BorderLayout.CENTER); JButton pauseButton = addButtonByNameAndCallback(toolbar, "", (e)->{ - ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); + ODEPhysics physics = Registry.getPhysics(); physics.setPaused(!physics.isPaused()); updatePauseButton((JButton)e.getSource(), physics); }); @@ -66,7 +66,6 @@ public ODE4JPanel() { private void add(Node node) { if(node instanceof Pose body) { - ODE4JHelper.guaranteePhysicsWorld(); Registry.getScene().addChild(body); placeBodyAbovePlane(body); if(randomColor) giveRandomColor(body); diff --git a/src/main/java/com/marginallyclever/ro3/apps/viewport/Viewport.java b/src/main/java/com/marginallyclever/ro3/apps/viewport/Viewport.java index 5e49ae997..2b58930e3 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/viewport/Viewport.java +++ b/src/main/java/com/marginallyclever/ro3/apps/viewport/Viewport.java @@ -505,6 +505,7 @@ private void renderAllPasses() { } private void updateAllNodes(double dt) { + Registry.getPhysics().update(dt); Registry.getScene().update(dt); } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java index 4ef50bf24..ab172b960 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java @@ -1,5 +1,6 @@ package com.marginallyclever.ro3.node.nodes.ode4j; +import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; import org.ode4j.ode.DContact; @@ -51,7 +52,7 @@ public List findHinges() { @Override protected void onDetach() { super.onDetach(); - ODE4JHelper.guaranteePhysicsWorld().removeCollisionListener(this); + Registry.getPhysics().removeCollisionListener(this); } /** diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java index 32336b80b..7df025f56 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java @@ -1,6 +1,7 @@ package com.marginallyclever.ro3.node.nodes.ode4j; import com.marginallyclever.convenience.helpers.MatrixHelper; +import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.NodePath; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; import com.marginallyclever.ro3.node.nodes.pose.Pose; @@ -65,8 +66,7 @@ protected void onDetach() { } private void createHinge() { - var physics = ODE4JHelper.guaranteePhysicsWorld(); - hinge = OdeHelper.createHingeJoint(physics.getODEWorld(), null); + hinge = OdeHelper.createHingeJoint(Registry.getPhysics().getODEWorld(), null); connect(); } @@ -111,6 +111,10 @@ private void connect() { var bs = partB.getSubject(); DBody a = as == null ? null : as.getODEBody(); DBody b = bs == null ? null : bs.getODEBody(); + if(a==null) { + a=b; + b=null; + } logger.debug(this.getName()+" connect "+(as==null?"null":as.getName())+" to "+(bs==null?"null":bs.getName())); hinge.attach(a, b); updatePhysicsFromWorld(); @@ -123,9 +127,8 @@ public void setLocal(Matrix4d m) { } private void updateHingePose() { - var physics = ODE4JHelper.guaranteePhysicsWorld(); // only let the user move the hinge if the physics simulation is paused. - if(physics.isPaused()) { + if(Registry.getPhysics().isPaused()) { // set the hinge reference point and axis. updatePhysicsFromWorld(); } @@ -147,8 +150,7 @@ private void updatePhysicsFromWorld() { @Override public void update(double dt) { super.update(dt); - var physics = ODE4JHelper.guaranteePhysicsWorld(); - if(!physics.isPaused()) { + if(!Registry.getPhysics().isPaused()) { // if the physics simulation is running then the hinge will behave as normal. DVector3 anchor = new DVector3(); DVector3 axis = new DVector3(); @@ -186,8 +188,7 @@ public void fromJSON(JSONObject from) { public void addTorque(double value) { if(hinge==null) return; - var physics = ODE4JHelper.guaranteePhysicsWorld(); - if(!physics.isPaused()) { + if(!Registry.getPhysics().isPaused()) { hinge.addTorque(value); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java index 2d6b06a45..154f1ec08 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java @@ -42,8 +42,7 @@ public ODEPlane(String name) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); - plane = OdeHelper.createPlane(physics.getODESpace(), 0, 0, 1, 0); + plane = OdeHelper.createPlane(Registry.getPhysics().getODESpace(), 0, 0, 1, 0); MeshInstance mesh = findFirstChild(MeshInstance.class); if(mesh==null) { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java index 4a15ae4a7..c50d4826e 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java @@ -1,9 +1,9 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.nodes.Material; -import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; +import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.ode4j.ODENode; -import com.marginallyclever.ro3.physics.ODEPhysics; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.math.DMatrix3C; @@ -78,8 +78,7 @@ protected void destroyGeom() { * Called once at the start of the first {@link #update(double)} */ protected void onFirstUpdate() { - ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); - body = OdeHelper.createBody(physics.getODEWorld()); + body = OdeHelper.createBody(Registry.getPhysics().getODEWorld()); mass = OdeHelper.createMass(); mass.setZero(); updateMass(); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java index f41292927..5b5165267 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java @@ -1,8 +1,8 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Box; -import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.physics.ODEPhysics; +import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DBox; @@ -37,8 +37,7 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); - geom = createBox(physics.getODESpace(), size.x, size.y, size.z); + geom = createBox(Registry.getPhysics().getODESpace(), size.x, size.y, size.z); geom.setBody(body); mass.setBoxTotal(ODE4JHelper.volumeBox(size.x,size.y,size.z), size.x, size.y, size.z); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java index 0781fc63d..20323c0a5 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java @@ -1,9 +1,9 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Capsule; import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.physics.ODEPhysics; +import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DCapsule; @@ -38,8 +38,7 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); - geom = OdeHelper.createCapsule(physics.getODESpace(), radius, length); + geom = OdeHelper.createCapsule(Registry.getPhysics().getODESpace(), radius, length); geom.setBody(body); mass.setCapsuleTotal(ODE4JHelper.volumeCapsule(radius,length), 3, radius, length); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java index 92517d06d..93998cf4c 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java @@ -1,8 +1,8 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Cylinder; -import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.physics.ODEPhysics; +import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DCylinder; @@ -36,8 +36,7 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); - geom = OdeHelper.createCylinder(physics.getODESpace(), radius, length); + geom = OdeHelper.createCylinder(Registry.getPhysics().getODESpace(), radius, length); geom.setBody(body); mass.setCylinderTotal(ODE4JHelper.volumeCylinder(radius,length), 3, radius, length); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java index d0d5d6bb4..595340b3a 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java @@ -1,8 +1,8 @@ package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Sphere; -import com.marginallyclever.ro3.node.nodes.ode4j.ODE4JHelper; -import com.marginallyclever.ro3.physics.ODEPhysics; +import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.ode.DSphere; @@ -36,8 +36,7 @@ public void getComponents(List list) { protected void onFirstUpdate() { super.onFirstUpdate(); - ODEPhysics physics = ODE4JHelper.guaranteePhysicsWorld(); - geom = createSphere(physics.getODESpace(), radius); + geom = createSphere(Registry.getPhysics().getODESpace(), radius); geom.setBody(body); mass.setSphereTotal(ODE4JHelper.volumeSphere(radius), radius); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java b/src/main/java/com/marginallyclever/ro3/physics/ODE4JHelper.java similarity index 81% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java rename to src/main/java/com/marginallyclever/ro3/physics/ODE4JHelper.java index 71fe3acc7..e85dd5adc 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODE4JHelper.java +++ b/src/main/java/com/marginallyclever/ro3/physics/ODE4JHelper.java @@ -1,7 +1,5 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.physics; -import com.marginallyclever.ro3.Registry; -import com.marginallyclever.ro3.physics.ODEPhysics; import org.json.JSONObject; import org.ode4j.math.DMatrix3; import org.ode4j.math.DMatrix3C; @@ -59,20 +57,6 @@ public static DMatrix3C convertRotationToODE(Matrix4d mat) { ); } - /** - * Gurantee there is exactly one {@link ODEPhysics} in the scene. - * @return the {@link ODEPhysics}. - */ - public static ODEPhysics guaranteePhysicsWorld() { - ODEPhysics physics = Registry.getScene().findFirstChild(ODEPhysics.class); - if (physics == null) { - logger.debug("Creating PhysicsWorld"); - physics = new ODEPhysics(); - Registry.getScene().addChild(physics); - } - return physics; - } - public static double volumeCylinder(double radius, double length) { return Math.PI * radius * radius * length; } diff --git a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java index f2c7265c1..44b4d214a 100644 --- a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java +++ b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java @@ -19,7 +19,7 @@ * Manages the ODE4J physics world, space, and contact handling. There must be exactly one of these in the scene * for physics to work. */ -public class ODEPhysics extends Node { +public class ODEPhysics { private static final Logger logger = LoggerFactory.getLogger(ODEPhysics.class); public double WORLD_CFM = 1e-5; @@ -37,32 +37,13 @@ public class ODEPhysics extends Node { protected final EventListenerList listeners = new EventListenerList(); public ODEPhysics() { - this("ODEWorldSpace"); - } - - public ODEPhysics(String name) { - super(name); - } - - @Override - public void getComponents(List list) { - list.add(new ODEWorldSpacePanel(this)); - super.getComponents(list); - } - - @Override - protected void onAttach() { - super.onAttach(); - + super(); OdeHelper.initODE2(0); - - startPhysics(); } - @Override - protected void onDetach() { - super.onDetach(); + public void reset() { stopPhysics(); + startPhysics(); } private void startPhysics() { @@ -120,10 +101,7 @@ public DSpace getODESpace() { return space; } - @Override public void update(double dt) { - super.update(dt); - if(isPaused) return; try { @@ -148,8 +126,6 @@ private void nearCallback(Object data, DGeom o1, DGeom o2) { return; try { - ODEPhysics physics = Registry.getScene().findFirstChild(ODEPhysics.class); - int n = OdeHelper.collide(o1, o2, CONTACT_BUFFER_SIZE, contacts.getGeomBuffer()); for (int i = 0; i < n; ++i) { DContact contact = contacts.get(i); @@ -163,7 +139,7 @@ private void nearCallback(Object data, DGeom o1, DGeom o2) { contact.surface.bounce = 0.9; // how much the contact surfaces can bounce contact.surface.bounce_vel = 0.5; // how fast the contact surfaces can bounce - DJoint contactJoint = OdeHelper.createContactJoint(physics.getODEWorld(), contactGroup, contact); + DJoint contactJoint = OdeHelper.createContactJoint(world, contactGroup, contact); contactJoint.attach(o1.getBody(), o2.getBody()); // inform any listeners that a collision has occurred. Use the DGeom to find the associated ODENode @@ -195,11 +171,6 @@ public void removeCollisionListener(CollisionListener listener) { listeners.remove(CollisionListener.class, listener); } - @Override - public Icon getIcon() { - return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); - } - public boolean isPaused() { return isPaused; } @@ -207,7 +178,4 @@ public boolean isPaused() { public void setPaused(boolean state) { isPaused = state; } - - public void reset() { - } } diff --git a/src/main/java/com/marginallyclever/ro3/physics/ODEWorldSpacePanel.java b/src/main/java/com/marginallyclever/ro3/physics/ODEWorldSpacePanel.java deleted file mode 100644 index 21b557f6c..000000000 --- a/src/main/java/com/marginallyclever/ro3/physics/ODEWorldSpacePanel.java +++ /dev/null @@ -1,46 +0,0 @@ -package com.marginallyclever.ro3.physics; - -import com.marginallyclever.ro3.PanelHelper; -import org.slf4j.Logger; -import org.slf4j.LoggerFactory; - -import javax.swing.*; -import java.awt.*; -import java.util.Objects; - -/** - * Manages the ODE4J physics world, space, and contact handling. There must be exactly one of these in the scene - * for physics to work. - */ -public class ODEWorldSpacePanel extends JPanel { - private static final Logger logger = LoggerFactory.getLogger(ODEWorldSpacePanel.class); - - public ODEWorldSpacePanel() { - this(new ODEPhysics()); - } - - public ODEWorldSpacePanel(ODEPhysics worldSpace) { - super(new GridLayout(0,2)); - this.setName(ODEPhysics.class.getSimpleName()); - - // toggle button to pause/unpause the simulation - JButton pauseButton = new JButton(); - pauseButton.addActionListener(e -> { - worldSpace.setPaused(!worldSpace.isPaused()); - updatePauseButton(pauseButton,worldSpace); - }); - updatePauseButton(pauseButton,worldSpace); - - PanelHelper.addLabelAndComponent(this,"Active",pauseButton); - } - - private void updatePauseButton(JButton pauseButton, ODEPhysics worldSpace) { - if (worldSpace.isPaused()) { - pauseButton.setToolTipText("Play"); - pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-play-16.png")))); - } else { - pauseButton.setToolTipText("Pause"); - pauseButton.setIcon( new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/shared/icons8-pause-16.png")))); - } - } -} diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java index ea845a61b..d9bf52406 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java @@ -12,40 +12,43 @@ public class ODEHingeTest { @Test public void test() { Registry.start(); - Node scene = Registry.getScene(); - ODE4JHelper.guaranteePhysicsWorld(); + Node before = Registry.getScene(); ODEBox box1 = new ODEBox("b1"); - scene.addChild(box1); + before.addChild(box1); ODEBox box2 = new ODEBox("b2"); - scene.addChild(box2); + before.addChild(box2); ODEHinge hinge1 = new ODEHinge("h1"); - scene.addChild(hinge1); + before.addChild(hinge1); ODEHinge hinge2 = new ODEHinge("h2"); - scene.addChild(hinge2); - scene.update(0); + before.addChild(hinge2); + + Registry.getPhysics().update(0); + // make sure everyone calls onFirstUpdate() + before.update(0); hinge1.setPartB(box1); hinge2.setPartA(box1); hinge2.setPartB(box2); - assertOneWorldSpaceInScene(scene); - // make a deep copy to/from json and confirm the links are still attached. - JSONObject json = scene.toJSON(); + Assertions.assertNotNull(hinge1.getHinge().getBody(0)); + Assertions.assertNotNull(hinge2.getHinge().getBody(0)); + Assertions.assertNotNull(hinge2.getHinge().getBody(1)); + + + // make a deep copy to/from json + JSONObject json = before.toJSON(); Node after = Registry.nodeFactory.create(json.getString("type")); after.fromJSON(json); - assertOneWorldSpaceInScene(scene); -// var physics = ODE4JHelper.guaranteePhysicsWorld(); - } + // confirm the hinges are still attached. + ODEHinge afterHinge1 = (ODEHinge) after.findChild("h1"); + ODEHinge afterHinge2 = (ODEHinge) after.findChild("h2"); + + // make sure everyone calls onFirstUpdate() + after.update(0); - private void assertOneWorldSpaceInScene(Node scene) { - // count the instances of ODEWorldSpace in scene. - int count = 0; - for(Node n : scene.getChildren()) { - if(n instanceof ODEPhysics) { - count++; - } - } - Assertions.assertEquals(1,count); + Assertions.assertNotNull(afterHinge1.getHinge().getBody(0)); + Assertions.assertNotNull(afterHinge2.getHinge().getBody(0)); + Assertions.assertNotNull(afterHinge2.getHinge().getBody(1)); } } From 390ea57b62b49992af16e08db7e9064290ec71fb Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Thu, 2 May 2024 11:11:42 -0700 Subject: [PATCH 31/52] moved CollisionListener to physics package --- .../ro3/node/nodes/ode4j/CreatureController.java | 1 + .../{node/nodes/ode4j => physics}/CollisionListener.java | 2 +- .../java/com/marginallyclever/ro3/physics/ODEPhysics.java | 6 ------ 3 files changed, 2 insertions(+), 7 deletions(-) rename src/main/java/com/marginallyclever/ro3/{node/nodes/ode4j => physics}/CollisionListener.java (90%) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java index ab172b960..0db7e7b28 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java @@ -3,6 +3,7 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; +import com.marginallyclever.ro3.physics.CollisionListener; import org.ode4j.ode.DContact; import org.ode4j.ode.DGeom; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CollisionListener.java b/src/main/java/com/marginallyclever/ro3/physics/CollisionListener.java similarity index 90% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CollisionListener.java rename to src/main/java/com/marginallyclever/ro3/physics/CollisionListener.java index 8ac68d881..137bb849b 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CollisionListener.java +++ b/src/main/java/com/marginallyclever/ro3/physics/CollisionListener.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.physics; import org.ode4j.ode.DContact; import org.ode4j.ode.DGeom; diff --git a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java index 44b4d214a..7dbd4ce40 100644 --- a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java +++ b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java @@ -1,16 +1,10 @@ package com.marginallyclever.ro3.physics; -import com.marginallyclever.ro3.Registry; -import com.marginallyclever.ro3.node.Node; -import com.marginallyclever.ro3.node.nodes.ode4j.CollisionListener; import org.ode4j.ode.*; import org.slf4j.Logger; import org.slf4j.LoggerFactory; -import javax.swing.*; import javax.swing.event.EventListenerList; -import java.util.List; -import java.util.Objects; import static org.ode4j.ode.OdeConstants.*; import static org.ode4j.ode.OdeHelper.createWorld; From 93edb39a7a993bd61ecde0ef33f0213761c76980 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Thu, 2 May 2024 16:12:40 -0700 Subject: [PATCH 32/52] organizing packages --- .../com/marginallyclever/ro3/AllPanels.java | 15 +++++++---- .../com/marginallyclever/ro3/Registry.java | 16 ++++++------ .../ro3/apps/RO3FrameDropTarget.java | 1 - .../ro3/apps/commands/ImportMesh.java | 5 ---- .../ro3/apps/ode4j/ODE4JPanel.java | 7 +++-- .../move/TranslateToolOneAxis.java | 2 -- .../CreatureController.java | 4 +-- .../CreatureControllerPanel.java | 4 +-- .../nodes/{ode4j => odenode}/ODEHinge.java | 4 +-- .../{ode4j => odenode}/ODEHingePanel.java | 7 ++--- .../nodes/{ode4j => odenode}/ODENode.java | 2 +- .../nodes/{ode4j => odenode}/ODEPlane.java | 5 ++-- .../{ode4j => odenode}/odebody/ODEBody.java | 6 ++--- .../odebody/ODEBodyPanel.java | 3 ++- .../odebody/odebodies}/ODEBox.java | 3 ++- .../odebody/odebodies}/ODEBoxPanel.java | 2 +- .../odebody/odebodies}/ODECapsule.java | 3 ++- .../odebody/odebodies}/ODECapsulePanel.java | 2 +- .../odebody/odebodies}/ODECylinder.java | 3 ++- .../odebody/odebodies}/ODECylinderPanel.java | 2 +- .../odebody/odebodies}/ODESphere.java | 3 ++- .../odebody/odebodies}/ODESpherePanel.java | 2 +- .../nodes/pose/poses/AttachmentPoint.java | 6 +++-- .../ro3/node/nodes/pose/poses/Camera.java | 4 +-- .../ro3/node/nodes/pose/poses/LookAt.java | 1 - .../ro3/physics/ODEPhysics.java | 4 ++- .../ro3/physics/ODEPhysicsPanel.java | 11 ++++++++ .../ro3/view/package-info.java | 24 +++++++++--------- .../icons8-mechanics-16.png | Bin .../{ode4j => odenode}/ODEHingeTest.java | 5 ++-- .../ro3/node/nodes/pose/poses/CameraTest.java | 24 +++++++++--------- .../ro3/node/nodes/pose/poses/LimbTest.java | 2 -- 32 files changed, 96 insertions(+), 86 deletions(-) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/CreatureController.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/CreatureControllerPanel.java (90%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/ODEHinge.java (97%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/ODEHingePanel.java (84%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/ODENode.java (97%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/ODEPlane.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/odebody/ODEBody.java (96%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/odebody/ODEBodyPanel.java (86%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODEBox.java (95%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODEBoxPanel.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODECapsule.java (95%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODECapsulePanel.java (93%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODECylinder.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODECylinderPanel.java (94%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODESphere.java (93%) rename src/main/java/com/marginallyclever/ro3/node/nodes/{ode4j/odebody => odenode/odebody/odebodies}/ODESpherePanel.java (92%) create mode 100644 src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java rename src/main/resources/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/icons8-mechanics-16.png (100%) rename src/test/java/com/marginallyclever/ro3/node/nodes/{ode4j => odenode}/ODEHingeTest.java (90%) diff --git a/src/main/java/com/marginallyclever/ro3/AllPanels.java b/src/main/java/com/marginallyclever/ro3/AllPanels.java index 471a91e8f..19b484be3 100644 --- a/src/main/java/com/marginallyclever/ro3/AllPanels.java +++ b/src/main/java/com/marginallyclever/ro3/AllPanels.java @@ -1,6 +1,7 @@ package com.marginallyclever.ro3; import com.formdev.flatlaf.FlatLightLaf; +import com.marginallyclever.ro3.node.nodes.pose.poses.*; import com.marginallyclever.ro3.physics.ODEPhysicsPanel; import org.reflections.Reflections; import org.slf4j.Logger; @@ -13,6 +14,10 @@ import javax.swing.*; import java.awt.*; +/** + * This class should be in tests but cannot because {@link Reflections} does not work across the + * production/test boundary. + */ public class AllPanels { private static final Logger logger = LoggerFactory.getLogger(AllPanels.class); @@ -104,11 +109,11 @@ private Collection> getHandmadeList() { com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArmPanel.class, ODEPhysicsPanel.class, com.marginallyclever.ro3.node.nodes.pose.PosePanel.class, - com.marginallyclever.ro3.node.nodes.pose.poses.AttachmentPointPanel.class, - com.marginallyclever.ro3.node.nodes.pose.poses.CameraPanel.class, - com.marginallyclever.ro3.node.nodes.pose.poses.LimbPanel.class, - com.marginallyclever.ro3.node.nodes.pose.poses.LookAtPanel.class, - com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstancePanel.class, + AttachmentPointPanel.class, + CameraPanel.class, + LimbPanel.class, + LookAtPanel.class, + MeshInstancePanel.class, com.marginallyclever.ro3.texture.TextureChooserDialog.class )); } diff --git a/src/main/java/com/marginallyclever/ro3/Registry.java b/src/main/java/com/marginallyclever/ro3/Registry.java index 86a5fce58..e55ee7e1d 100644 --- a/src/main/java/com/marginallyclever/ro3/Registry.java +++ b/src/main/java/com/marginallyclever/ro3/Registry.java @@ -13,16 +13,16 @@ import com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlanner; import com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolver; import com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArm; -import com.marginallyclever.ro3.node.nodes.ode4j.CreatureController; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEHinge; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; -import com.marginallyclever.ro3.node.nodes.ode4j.ODEPlane; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODECapsule; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODECylinder; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODESphere; +import com.marginallyclever.ro3.node.nodes.odenode.CreatureController; +import com.marginallyclever.ro3.node.nodes.odenode.ODEHinge; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODEBox; +import com.marginallyclever.ro3.node.nodes.odenode.ODEPlane; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODECapsule; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODECylinder; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODESphere; +import com.marginallyclever.ro3.node.nodes.pose.poses.*; import com.marginallyclever.ro3.physics.ODEPhysics; import com.marginallyclever.ro3.node.nodes.pose.*; -import com.marginallyclever.ro3.node.nodes.pose.poses.*; import com.marginallyclever.ro3.texture.TextureFactory; import javax.swing.event.EventListenerList; diff --git a/src/main/java/com/marginallyclever/ro3/apps/RO3FrameDropTarget.java b/src/main/java/com/marginallyclever/ro3/apps/RO3FrameDropTarget.java index e35cbbf84..48d1573e1 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/RO3FrameDropTarget.java +++ b/src/main/java/com/marginallyclever/ro3/apps/RO3FrameDropTarget.java @@ -3,7 +3,6 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.commands.ImportMesh; import com.marginallyclever.ro3.apps.commands.ImportScene; -import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.slf4j.Logger; import org.slf4j.LoggerFactory; diff --git a/src/main/java/com/marginallyclever/ro3/apps/commands/ImportMesh.java b/src/main/java/com/marginallyclever/ro3/apps/commands/ImportMesh.java index eb4ac9df3..6b49f773a 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/commands/ImportMesh.java +++ b/src/main/java/com/marginallyclever/ro3/apps/commands/ImportMesh.java @@ -1,18 +1,13 @@ package com.marginallyclever.ro3.apps.commands; import com.marginallyclever.ro3.Registry; -import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; -import org.json.JSONObject; import org.slf4j.Logger; import org.slf4j.LoggerFactory; import javax.swing.undo.AbstractUndoableEdit; import javax.swing.undo.CannotUndoException; import java.io.File; -import java.io.IOException; -import java.nio.file.Files; -import java.nio.file.Paths; import java.security.InvalidParameterException; /** diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java index 5c54d8b98..6b28a1afd 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODE4JPanel.java @@ -5,8 +5,11 @@ import com.marginallyclever.ro3.apps.App; import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.Material; -import com.marginallyclever.ro3.node.nodes.ode4j.*; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.*; +import com.marginallyclever.ro3.node.nodes.odenode.*; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODEBox; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODECapsule; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODECylinder; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODESphere; import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.physics.ODEPhysics; diff --git a/src/main/java/com/marginallyclever/ro3/apps/viewport/viewporttools/move/TranslateToolOneAxis.java b/src/main/java/com/marginallyclever/ro3/apps/viewport/viewporttools/move/TranslateToolOneAxis.java index 0cde652f8..3f6e08920 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/viewport/viewporttools/move/TranslateToolOneAxis.java +++ b/src/main/java/com/marginallyclever/ro3/apps/viewport/viewporttools/move/TranslateToolOneAxis.java @@ -15,13 +15,11 @@ import com.marginallyclever.ro3.apps.viewport.ShaderProgram; import com.marginallyclever.ro3.apps.viewport.Viewport; import com.marginallyclever.ro3.mesh.Mesh; -import com.marginallyclever.ro3.node.nodes.pose.poses.LookAt; import com.marginallyclever.ro3.texture.TextureWithMetadata; import javax.vecmath.Matrix4d; import javax.vecmath.Point3d; import javax.vecmath.Vector3d; -import java.awt.*; import java.awt.event.MouseEvent; import java.awt.geom.Rectangle2D; import java.util.List; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java index 0db7e7b28..0d5234405 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureController.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java @@ -1,8 +1,8 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.odenode; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import com.marginallyclever.ro3.physics.CollisionListener; import org.ode4j.ode.DContact; import org.ode4j.ode.DGeom; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureControllerPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureControllerPanel.java similarity index 90% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureControllerPanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureControllerPanel.java index 8a28817f5..5f52d452e 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/CreatureControllerPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureControllerPanel.java @@ -1,9 +1,7 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.odenode; import com.marginallyclever.ro3.PanelHelper; -import com.marginallyclever.ro3.node.Node; -import java.util.ArrayList; import java.util.List; import javax.swing.*; import java.awt.*; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java similarity index 97% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java index 7df025f56..7d2cf9de8 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java @@ -1,9 +1,9 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.odenode; import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.NodePath; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import com.marginallyclever.ro3.node.nodes.pose.Pose; import org.json.JSONObject; import org.ode4j.math.DVector3; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingePanel.java similarity index 84% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingePanel.java index 93c346830..cb327db01 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingePanel.java @@ -1,15 +1,12 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.odenode; import com.marginallyclever.ro3.PanelHelper; import com.marginallyclever.ro3.apps.nodeselector.NodeSelector; import com.marginallyclever.ro3.node.NodePath; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBody; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; -import com.marginallyclever.ro3.node.nodes.pose.Pose; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import javax.swing.*; import java.awt.*; -import java.awt.event.ActionListener; import java.util.function.Consumer; /** diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODENode.java similarity index 97% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODENode.java index 49fb45507..056c4b738 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODENode.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODENode.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.odenode; import com.marginallyclever.ro3.node.nodes.pose.Pose; import org.json.JSONObject; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEPlane.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEPlane.java index 154f1ec08..198726b58 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEPlane.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEPlane.java @@ -1,11 +1,10 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.odenode; import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Decal; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; -import com.marginallyclever.ro3.physics.ODEPhysics; import org.json.JSONObject; import org.ode4j.ode.DPlane; import org.ode4j.ode.OdeHelper; @@ -96,7 +95,7 @@ public void update(double dt) { @Override public Icon getIcon() { - return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/odenode/icons8-mechanics-16.png"))); } @Override diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java similarity index 96% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java index c50d4826e..c267fdc32 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java @@ -1,9 +1,9 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.nodes.Material; import com.marginallyclever.ro3.physics.ODE4JHelper; -import com.marginallyclever.ro3.node.nodes.ode4j.ODENode; +import com.marginallyclever.ro3.node.nodes.odenode.ODENode; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; import org.ode4j.math.DMatrix3C; @@ -116,7 +116,7 @@ protected void updatePhysicsFromPose() { @Override public Icon getIcon() { - return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png"))); + return new ImageIcon(Objects.requireNonNull(getClass().getResource("/com/marginallyclever/ro3/node/nodes/odenode/icons8-mechanics-16.png"))); } public double getMassQty() { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBodyPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBodyPanel.java similarity index 86% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBodyPanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBodyPanel.java index 5e7c3ba46..1ba859f51 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBodyPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBodyPanel.java @@ -1,7 +1,8 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODESphere; import javax.swing.*; import java.awt.*; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java similarity index 95% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java index 5b5165267..b9837371c 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java @@ -1,7 +1,8 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Box; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBoxPanel.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBoxPanel.java index c8fb93fcc..8ae0bdb87 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODEBoxPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBoxPanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java similarity index 95% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java index 20323c0a5..aa583b0bc 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java @@ -1,8 +1,9 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Capsule; import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsulePanel.java similarity index 93% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsulePanel.java index 23126dbff..db44057f8 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECapsulePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsulePanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java index 93998cf4c..d6db927c6 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java @@ -1,7 +1,8 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Cylinder; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinderPanel.java similarity index 94% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinderPanel.java index d0ed7cccd..f02264cd3 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODECylinderPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinderPanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java similarity index 93% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java index 595340b3a..a4639f530 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java @@ -1,7 +1,8 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.mesh.shapes.Sphere; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import com.marginallyclever.ro3.physics.ODE4JHelper; import com.marginallyclever.ro3.node.nodes.pose.poses.MeshInstance; import org.json.JSONObject; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESpherePanel.java similarity index 92% rename from src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESpherePanel.java index ac8ca30eb..f43dd4121 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/ode4j/odebody/ODESpherePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESpherePanel.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.ode4j.odebody; +package com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies; import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/AttachmentPoint.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/AttachmentPoint.java index 9f6c6a3a3..528555052 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/AttachmentPoint.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/AttachmentPoint.java @@ -18,8 +18,10 @@ import java.util.Objects; /** - *

    {@link AttachmentPoint} is a point on a {@link Pose} that can be used to attach other nodes.

    - *

    Users can click the attach button in the control panel. Developers can use the {@link #attemptAttach()} method.

    + *

    {@link AttachmentPoint} is a point on a {@link Pose} that can be used to attach other {@link Pose}s.

    + *

    Users can click the attach button in the control panel. Developers can use the {@link #attemptAttach()} method. + * If this AttachmentPoint finds another Pose within radius, it will move the other Pose to be a child of this + * AttachmentPoint.

    *

    Things in reach must be {@link Pose} items within {@link #radius} of {@link AttachmentPoint}. They must also be * immediate children of the Scene root.

    *

    The attached item will move from the Scene root and become a child of {@link AttachmentPoint}. On release all diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java index f55444f7e..a9e0403e4 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Camera.java @@ -280,7 +280,7 @@ public void orbit(double dx,double dy) { //logger.debug("after {}",getOrbitPoint()); } - public double[] getPanTiltFromMatrix(Matrix4d matrix) { + public static double[] getPanTiltFromMatrix(Matrix4d matrix) { Vector3d v = MatrixHelper.matrixToEuler(matrix, MatrixHelper.EulerSequence.YXZ); double pan = Math.toDegrees(-v.z); double tilt = Math.toDegrees(v.x); @@ -291,7 +291,7 @@ public double[] getPanTiltFromMatrix(Matrix4d matrix) { * @param panTiltAngles [0] = pan, [1] = tilt * @return a matrix that rotates the camera by the given pan and tilt angles. */ - Matrix3d buildPanTiltMatrix(double [] panTiltAngles) { + public static Matrix3d buildPanTiltMatrix(double [] panTiltAngles) { Matrix3d a = new Matrix3d(); a.rotZ(Math.toRadians(panTiltAngles[0])); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java index 77a5fa3a7..551077f0f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/LookAt.java @@ -6,7 +6,6 @@ import org.json.JSONObject; import javax.swing.*; -import javax.vecmath.Matrix3d; import javax.vecmath.Matrix4d; import java.util.List; import java.util.Objects; diff --git a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java index 7dbd4ce40..b08a0767a 100644 --- a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java +++ b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysics.java @@ -32,7 +32,7 @@ public class ODEPhysics { public ODEPhysics() { super(); - OdeHelper.initODE2(0); + startPhysics(); } public void reset() { @@ -43,6 +43,8 @@ public void reset() { private void startPhysics() { logger.info("Starting Physics"); + OdeHelper.initODE2(0); + // build the world if(world == null) { world = createWorld(); diff --git a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java new file mode 100644 index 000000000..70c94e340 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java @@ -0,0 +1,11 @@ +package com.marginallyclever.ro3.physics; + +import javax.swing.*; +import java.awt.*; + +public class ODEPhysicsPanel extends JPanel { + public ODEPhysicsPanel() { + super(); + // TODO add physics settings + } +} diff --git a/src/main/java/com/marginallyclever/ro3/view/package-info.java b/src/main/java/com/marginallyclever/ro3/view/package-info.java index 709715541..15a578546 100644 --- a/src/main/java/com/marginallyclever/ro3/view/package-info.java +++ b/src/main/java/com/marginallyclever/ro3/view/package-info.java @@ -1,14 +1,14 @@ -/* -

    Suppose there are one or more classes that provide different views of a model, in the sense of a - model-view-controller design - pattern.

    -

    When class A provides a {@link com.marginallyclever.ro3.view.View} for model class B, A should be annotated - View(of=B.class). A must also implement the {@link com.marginallyclever.ro3.view.ViewProvider} - interface. {@link com.marginallyclever.ro3.view.ViewProvider} then empowers other systems to locate and - build the Swing GUI for A.

    -

    Annotating a {@link com.marginallyclever.ro3.view.View} and failing to implement the - {@link com.marginallyclever.ro3.view.ViewProvider} interface will cause a test to fail.

    - -

    This system allows for modular and dynamic view creation for various data types in a Swing-based application.

    +/** + *

    Suppose there are one or more classes that provide different views of a model, in the sense of a + * model-view-controller design + * pattern.

    + *

    When class A provides a {@link com.marginallyclever.ro3.view.View} for model class B, A should be annotated + * View(of=B.class). A must also implement the {@link com.marginallyclever.ro3.view.ViewProvider} + * interface. {@link com.marginallyclever.ro3.view.ViewProvider} then empowers other systems to locate and + * build the Swing GUI for A.

    + *

    Annotating a {@link com.marginallyclever.ro3.view.View} and failing to implement the + * {@link com.marginallyclever.ro3.view.ViewProvider} interface will cause a test to fail.

    + * + *

    This system allows for modular and dynamic view creation for various data types in a Swing-based application.

    */ package com.marginallyclever.ro3.view; diff --git a/src/main/resources/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png b/src/main/resources/com/marginallyclever/ro3/node/nodes/odenode/icons8-mechanics-16.png similarity index 100% rename from src/main/resources/com/marginallyclever/ro3/node/nodes/ode4j/icons8-mechanics-16.png rename to src/main/resources/com/marginallyclever/ro3/node/nodes/odenode/icons8-mechanics-16.png diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingeTest.java similarity index 90% rename from src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java rename to src/test/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingeTest.java index d9bf52406..4cb1b60bd 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/ode4j/ODEHingeTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingeTest.java @@ -1,9 +1,8 @@ -package com.marginallyclever.ro3.node.nodes.ode4j; +package com.marginallyclever.ro3.node.nodes.odenode; import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; -import com.marginallyclever.ro3.node.nodes.ode4j.odebody.ODEBox; -import com.marginallyclever.ro3.physics.ODEPhysics; +import com.marginallyclever.ro3.node.nodes.odenode.odebody.odebodies.ODEBox; import org.json.JSONObject; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/CameraTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/CameraTest.java index c2c45e49c..8a4510db3 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/CameraTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/CameraTest.java @@ -24,9 +24,9 @@ public void testPanTiltInverses() { for (int pan = -180; pan <= 180; pan += 10) { for (int tilt = -90; tilt <= 90; tilt += 10) { double[] before = new double[]{pan, tilt}; - Matrix3d panTiltMatrix = camera.buildPanTiltMatrix(before); + Matrix3d panTiltMatrix = Camera.buildPanTiltMatrix(before); Matrix4d matrix = new Matrix4d(panTiltMatrix, new Vector3d(), 1.0); - double[] after = camera.getPanTiltFromMatrix(matrix); + double[] after = Camera.getPanTiltFromMatrix(matrix); //System.out.println("before="+before[0]+","+before[1]+" after="+after[0]+","+after[1]); Assertions.assertArrayEquals(before, after, 0.01); } @@ -109,9 +109,9 @@ public void dolly() { @Test public void tilt() { Camera camera = new Camera(); - var p0 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p0 = Camera.getPanTiltFromMatrix(camera.getLocal()); camera.tilt(1.0); - var p1 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p1 = Camera.getPanTiltFromMatrix(camera.getLocal()); Assertions.assertEquals(p0[0], p1[0], 0.01); Assertions.assertEquals(p0[1] + 1.0, p1[1], 0.01); } @@ -119,10 +119,10 @@ public void tilt() { @Test public void pan() { Camera camera = new Camera(); - var p0 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p0 = Camera.getPanTiltFromMatrix(camera.getLocal()); camera.tilt(-90.0); camera.pan(90.0); - var p1 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p1 = Camera.getPanTiltFromMatrix(camera.getLocal()); Assertions.assertEquals(p0[0], p1[0], 0.01); Assertions.assertEquals(p0[1] - 90, p1[1], 0.01); } @@ -131,7 +131,7 @@ public void pan() { public void panTilt() { Camera camera = new Camera(); camera.panTilt(90.0, 90.0); - var p1 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p1 = Camera.getPanTiltFromMatrix(camera.getLocal()); Assertions.assertEquals(90.0, p1[0], 0.01); Assertions.assertEquals(90.0, p1[1], 0.01); } @@ -150,10 +150,10 @@ public void roll() { @Test public void orbit() { Camera camera = new Camera(); - var p0 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p0 = Camera.getPanTiltFromMatrix(camera.getLocal()); camera.getLocal().rotX(Math.toRadians(90)); camera.orbit(90.0,-90); - var p1 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p1 = Camera.getPanTiltFromMatrix(camera.getLocal()); Assertions.assertEquals(p0[0] + 90.0, p1[0], 0.01); Assertions.assertEquals(p0[1], p1[1], 0.01); } @@ -202,9 +202,9 @@ public void getOrthographicMatrix() { public void canRotate() { Camera camera = new Camera(); camera.setCanRotate(false); - var p0 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p0 = Camera.getPanTiltFromMatrix(camera.getLocal()); camera.panTilt(90,90); - var p1 = camera.getPanTiltFromMatrix(camera.getLocal()); + var p1 = Camera.getPanTiltFromMatrix(camera.getLocal()); Assertions.assertEquals(p0[0], p1[0], 0.01); Assertions.assertEquals(p0[1], p1[1], 0.01); } @@ -244,7 +244,7 @@ public void json() { Assertions.assertEquals(a.getFarZ(),b.getFarZ(),0.01); Assertions.assertEquals(a.getFovY(),b.getFovY(),0.01); Assertions.assertEquals(a.getOrbitRadius(),b.getOrbitRadius(),0.01); - Assertions.assertArrayEquals(a.getPanTiltFromMatrix(a.getLocal()),b.getPanTiltFromMatrix(b.getLocal()),0.01); + Assertions.assertArrayEquals(Camera.getPanTiltFromMatrix(a.getLocal()),Camera.getPanTiltFromMatrix(b.getLocal()),0.01); Assertions.assertEquals(a.getPosition(),b.getPosition()); Assertions.assertEquals(a.getCanRotate(),b.getCanRotate()); Assertions.assertEquals(a.getCanTranslate(),b.getCanTranslate()); diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/LimbTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/LimbTest.java index ca9dc55da..bb9300c66 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/LimbTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/pose/poses/LimbTest.java @@ -2,9 +2,7 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.actions.LoadScene; -import com.marginallyclever.ro3.node.nodes.pose.poses.Limb; import org.junit.jupiter.api.BeforeAll; -import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import java.io.File; From a9af1290637702f129a86942aefc51410c401ad4 Mon Sep 17 00:00:00 2001 From: github-actions <41898282+github-actions[bot]@users.noreply.github.com> Date: Fri, 3 May 2024 04:02:34 +0000 Subject: [PATCH 33/52] commit badge --- .github/badges/branches.svg | 2 +- .github/badges/jacoco.svg | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/badges/branches.svg b/.github/badges/branches.svg index 6ec7d76c2..7cde8787e 100644 --- a/.github/badges/branches.svg +++ b/.github/badges/branches.svg @@ -1 +1 @@ -branches18.6% \ No newline at end of file +branches18.8% \ No newline at end of file diff --git a/.github/badges/jacoco.svg b/.github/badges/jacoco.svg index d14e4c984..3e4707e81 100644 --- a/.github/badges/jacoco.svg +++ b/.github/badges/jacoco.svg @@ -1 +1 @@ -coverage20.3% \ No newline at end of file +coverage20.4% \ No newline at end of file From a4ab6dd713e6435d49fe0a0a07e400fe9c8b9690 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Sun, 5 May 2024 09:21:38 -0700 Subject: [PATCH 34/52] oraganizing --- .../ro3/node/nodes/limbsolver/LimbSolver.java | 2 ++ .../limbsolver/{ => limbsolvers}/ApproximateJacobian.java | 2 +- .../ApproximateJacobianFiniteDifferences.java | 2 +- .../{ => limbsolvers}/ApproximateJacobianScrewTheory.java | 2 +- .../node/nodes/marlinrobotarm/ApproximateJacobianTest.java | 6 +++--- 5 files changed, 8 insertions(+), 6 deletions(-) rename src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/{ => limbsolvers}/ApproximateJacobian.java (99%) rename src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/{ => limbsolvers}/ApproximateJacobianFiniteDifferences.java (97%) rename src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/{ => limbsolvers}/ApproximateJacobianScrewTheory.java (97%) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/LimbSolver.java b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/LimbSolver.java index b33b21c31..49acd4658 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/LimbSolver.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/LimbSolver.java @@ -3,6 +3,8 @@ import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.NodePath; +import com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers.ApproximateJacobian; +import com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers.ApproximateJacobianFiniteDifferences; import com.marginallyclever.ro3.node.nodes.pose.Pose; import com.marginallyclever.ro3.node.nodes.pose.poses.Limb; import org.json.JSONObject; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobian.java b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobian.java similarity index 99% rename from src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobian.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobian.java index 23ed8e1e5..5e5ce949f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobian.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobian.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.limbsolver; +package com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers; import com.marginallyclever.convenience.helpers.BigMatrixHelper; import com.marginallyclever.convenience.helpers.StringHelper; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobianFiniteDifferences.java b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobianFiniteDifferences.java similarity index 97% rename from src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobianFiniteDifferences.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobianFiniteDifferences.java index d06a5b80c..51c6560e1 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobianFiniteDifferences.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobianFiniteDifferences.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.limbsolver; +package com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers; import com.marginallyclever.ro3.node.nodes.pose.poses.Limb; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobianScrewTheory.java b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobianScrewTheory.java similarity index 97% rename from src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobianScrewTheory.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobianScrewTheory.java index 1f8d40127..d8b7b1911 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/ApproximateJacobianScrewTheory.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/limbsolver/limbsolvers/ApproximateJacobianScrewTheory.java @@ -1,4 +1,4 @@ -package com.marginallyclever.ro3.node.nodes.limbsolver; +package com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers; import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.node.nodes.pose.Pose; diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/marlinrobotarm/ApproximateJacobianTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/marlinrobotarm/ApproximateJacobianTest.java index 4d4665d16..3d8443dc0 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/marlinrobotarm/ApproximateJacobianTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/marlinrobotarm/ApproximateJacobianTest.java @@ -2,9 +2,9 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.apps.actions.LoadScene; -import com.marginallyclever.ro3.node.nodes.limbsolver.ApproximateJacobian; -import com.marginallyclever.ro3.node.nodes.limbsolver.ApproximateJacobianFiniteDifferences; -import com.marginallyclever.ro3.node.nodes.limbsolver.ApproximateJacobianScrewTheory; +import com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers.ApproximateJacobian; +import com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers.ApproximateJacobianFiniteDifferences; +import com.marginallyclever.ro3.node.nodes.limbsolver.limbsolvers.ApproximateJacobianScrewTheory; import com.marginallyclever.ro3.node.nodes.pose.poses.Limb; import org.junit.jupiter.api.*; From 82985e8a628eab5893fcd9bec1f1ec38d28bb4fa Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 7 May 2024 20:16:49 -0700 Subject: [PATCH 35/52] documentation --- .../convenience/helpers/FileHelper.java | 2 +- .../ro3/mesh/MeshFactory.java | 19 +++++++++++++++++-- 2 files changed, 18 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/marginallyclever/convenience/helpers/FileHelper.java b/src/main/java/com/marginallyclever/convenience/helpers/FileHelper.java index 19c0c0689..ce7420a09 100644 --- a/src/main/java/com/marginallyclever/convenience/helpers/FileHelper.java +++ b/src/main/java/com/marginallyclever/convenience/helpers/FileHelper.java @@ -14,7 +14,7 @@ public class FileHelper { * - The file may be a resource inside a jar file. * - The file may be on disk. * - * @param filename The file to open + * @param filename The file to open. May be "filename.ext" or "zipfile.zip:filename.ext" * @return BufferedInputStream to the file contents * @throws IOException file open failure */ diff --git a/src/main/java/com/marginallyclever/ro3/mesh/MeshFactory.java b/src/main/java/com/marginallyclever/ro3/mesh/MeshFactory.java index d0395ade5..5128b2627 100644 --- a/src/main/java/com/marginallyclever/ro3/mesh/MeshFactory.java +++ b/src/main/java/com/marginallyclever/ro3/mesh/MeshFactory.java @@ -34,7 +34,7 @@ public class MeshFactory { /** * Makes sure to only load one instance of each source file. Loads all the data immediately. * @param filename file from which to load. May be "filename.ext" or "zipfile.zip:filename.ext" - * @return an instance of Mesh. It may contain nothing. + * @return a non-null instance of Mesh. It may contain nothing. */ public Mesh load(String filename) { if(filename == null || filename.trim().isEmpty()) return null; @@ -49,8 +49,12 @@ public Mesh load(String filename) { return mesh; } + /** + * find the existing shape in the pool + * @param filename file from which to load. May be "filename.ext" or "zipfile.zip:filename.ext" + * @return a non-null instance of Mesh. It may contain nothing. + */ private Mesh getMeshFromPool(String filename) { - // find the existing shape in the pool for( Mesh m : meshPool.getList() ) { String sourceName = m.getSourceName(); if(sourceName==null) continue; @@ -62,6 +66,11 @@ private Mesh getMeshFromPool(String filename) { return null; } + /** + * Try to load a mesh from a file using one of the available loaders. + * @param filename The file to open. May be "filename.ext" or "zipfile.zip:filename.ext" + * @param mesh the mesh to load into + */ private void attemptLoad(String filename, Mesh mesh) { for( MeshLoader loader : loaders ) { if(isValidExtension(filename,loader)) { @@ -80,6 +89,12 @@ private boolean isValidExtension(String filename, MeshLoader loader) { return false; } + /** + * Load a mesh from a file using a specific loader. + * @param filename The file to open. May be "filename.ext" or "zipfile.zip:filename.ext" + * @param mesh the mesh to load into + * @param loader the loader to use + */ private void loadMeshWithLoader(String filename, Mesh mesh, MeshLoader loader) { //logger.info("Loading "+filename+" with "+loader.getEnglishName()); From e419dbfa16071552c2389974c1fe47ad9970065f Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 7 May 2024 20:17:13 -0700 Subject: [PATCH 36/52] add brain, connect sensory input to brain. --- .../ro3/node/nodes/odenode/Brain.java | 109 +++++++++++++++++ .../nodes/odenode/CreatureController.java | 83 ++++++++++++- .../odenode/CreatureControllerPanel.java | 113 ++++++++++++++++-- .../node/nodes/odenode/odebody/ODEBody.java | 9 ++ 4 files changed, 301 insertions(+), 13 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java new file mode 100644 index 000000000..456a294ba --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java @@ -0,0 +1,109 @@ +package com.marginallyclever.ro3.node.nodes.odenode; + +import com.marginallyclever.ro3.Registry; + +import javax.vecmath.Matrix4d; +import java.awt.*; +import java.awt.image.BufferedImage; +import java.util.ArrayList; +import java.util.List; + +public class Brain { + // build a list of all body pose matrices, relative to the world + private final List matrices = new ArrayList<>(); + // build a list of contacts for each body + private final List isTouching = new ArrayList<>(); + private final static int memoryLength = 30*3; // fps * seconds + private int k=0; + + private final List neurons = new ArrayList<>(); + private BufferedImage image; + + public Brain() { + // create a list of neurons + // create a list of synapses + } + + public void setNumInputs(int size) { + // make isTouching size equal to bodies.size(); + // make matrices size equal to bodies.size(); + isTouching.clear(); + matrices.clear(); + for (int i = 0; i < size; ++i) { + isTouching.add(false); + matrices.add(new Matrix4d()); + } + + // every matrix is 4 inputs + // every is touching is 1 input. + image = new BufferedImage(size * 5, memoryLength, BufferedImage.TYPE_INT_ARGB); + eraseBrainScan(); + } + + private void eraseBrainScan() { + // Fill the image with black color + Graphics2D g = image.createGraphics(); + g.setColor(Color.BLACK); + g.fillRect(0, 0, image.getWidth(), image.getHeight()); + g.dispose(); + } + + public void setMatrix(int i, Matrix4d world) { + matrices.get(i).set(world); + } + + public void setTouching(int i, boolean touching) { + isTouching.set(i, touching); + } + + public double getOutput(int i) { + return 0; + } + + void update(double dt) { + if(Registry.getPhysics().isPaused()) return; + + // move every row of the image down one. + updateImage(); + writeInputsToTopLineOfImage(); + } + + private void writeInputsToTopLineOfImage() { + // every matrix value is copied to a pixel in the first row of the image. + // every isTouching value is copied to a pixel in the first row of the image. + k = 0; + int i=0; + for (Matrix4d m : matrices) { + addPixelToTopRow(m.m00, m.m10, m.m20, 1, -1); + addPixelToTopRow(m.m01, m.m11, m.m21, 1, -1); + addPixelToTopRow(m.m02, m.m12, m.m22, 1, -1); + addPixelToTopRow(m.m03, m.m13, m.m23, 20, -20); + } + + for (Matrix4d m : matrices) { + image.setRGB(k++, 0, isTouching.get(i++) ? 0xffff0000:0 ); + } + } + + private void addPixelToTopRow(double x,double y,double z,int max,int min) { + double f = 255.0 / (max-min); + int r = (int)( (Math.max(Math.min(x,max),min) - min) * f ); + int g = (int)( (Math.max(Math.min(y,max),min) - min) * f ); + int b = (int)( (Math.max(Math.min(z,max),min) - min) * f ); + image.setRGB(k++, 0, 0xff000000 | (g << 16) | (r << 8) | b); + } + + public BufferedImage getImage() { + return image; + } + + // move every row of the image down one. + void updateImage() { + // Copy each row from the original image to itself, one row lower. start from the bottom. + for (int y=memoryLength-1;y>0;--y) { + for (int x=0;xThis controller registers itself to receive collision events from the physics world.

    * */ -public class CreatureController extends Node implements CollisionListener { +public class CreatureController extends ODENode implements CollisionListener { + private final List hinges = new ArrayList<>(); + private final List bodies = new ArrayList<>(); + private final Brain brain = new Brain(); + public CreatureController() { super("CreatureController"); } @@ -36,7 +40,7 @@ public void getComponents(List list) { /** * @return A list of all the hinges that are connected to this creature. */ - public List findHinges() { + private List findHinges() { List hinges = new ArrayList<>(); List toSearch = new ArrayList<>(getChildren()); while(!toSearch.isEmpty()) { @@ -50,6 +54,12 @@ public List findHinges() { return hinges; } + @Override + protected void onAttach() { + super.onAttach(); + Registry.getPhysics().addCollisionListener(this); + } + @Override protected void onDetach() { super.onDetach(); @@ -59,7 +69,7 @@ protected void onDetach() { /** * @return A set of all the bodies that are connected to hinges of this creature. */ - public Set findBodies() { + private Set findBodies() { Set bodies = new HashSet<>(); List hinges = findHinges(); for(ODEHinge hinge : hinges) { @@ -75,8 +85,73 @@ public void onCollision(DGeom g1, DGeom g2, DContact contact) { for(ODEBody b : bodies) { if(b.getGeom() == g1 || b.getGeom() == g2) { // b is touching something - // TODO finish me! + // store the hinge/is-touching relationship in c + b.setTouchingSomething(true); } } } + + @Override + protected void onFirstUpdate() { + super.onFirstUpdate(); + // store a list of the hinges once and keep it until the end of time or someone forces a refresh. + hinges.clear(); + hinges.addAll(findHinges()); + bodies.clear(); + bodies.addAll(findBodies()); + brain.setNumInputs(bodies.size()+1); + } + + @Override + public void update(double dt) { + super.update(dt); + + // any bodies that are marked isTouching must be because onCollision says so. + + // get the matrix for the torso, probably always bodies[0]? Not guaranteed. + var torsoMatrix = bodies.get(0).getWorld(); + torsoMatrix.invert(); + // multiply all brain matrices by the inverse of torsoMatrix + int i=0; + for (ODEBody b : bodies) { + // I'm concerned this is not the correct matrix. + // the translation values are not normalized. + var m = b.getWorld(); + m.mul(torsoMatrix); + brain.setMatrix(i,m); + brain.setTouching(i,b.isTouchingSomething()); + System.out.print(b.isTouchingSomething()?"1":"0"); + ++i; + } + System.out.println(); + + brain.setMatrix(i,torsoMatrix); + + // I have all the input for the robot dog, normalized. + // some magic happens here + brain.update(dt); + + // I want the system to output torque values for each hinge. + i=0; + for (ODEHinge h : hinges) { + h.addTorque(brain.getOutput(i)); + ++i; + } + + // reset the isTouching flag on all bodies + for (ODEBody b : bodies) { + b.setTouchingSomething(false); + } + } + + public List getHinges() { + return hinges; + } + public List getBodies() { + return bodies; + } + + public Brain getBrain() { + return brain; + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureControllerPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureControllerPanel.java index 5f52d452e..0e99e9c14 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureControllerPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureControllerPanel.java @@ -1,40 +1,135 @@ package com.marginallyclever.ro3.node.nodes.odenode; +import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.node.nodes.MaterialPanel; import java.util.List; import javax.swing.*; +import javax.swing.text.NumberFormatter; import java.awt.*; /** * A panel for controlling an ODE4J creature. */ public class CreatureControllerPanel extends JPanel { + private double myFirstTorque = 250000; + private JLabel brainLabel = new JLabel(); + private CreatureController creatureController; + private Timer timer; + public CreatureControllerPanel() { this(new CreatureController()); } public CreatureControllerPanel(CreatureController creatureController) { - super(new GridLayout(0,2)); + super(new GridBagLayout()); setName(CreatureController.class.getSimpleName()); - List toSearch = creatureController.findHinges(); - for(ODEHinge hinge : toSearch) { - addAction(hinge.getName(),hinge); + this.creatureController = creatureController; + + GridBagConstraints gbc = new GridBagConstraints(); + gbc.weightx = 1.0; + gbc.weighty = 1.0; + gbc.gridx = 0; + gbc.gridy = 0; + gbc.fill = GridBagConstraints.BOTH; + + addHingeControls(gbc); + + gbc.weighty = 0.0; + PanelHelper.addLabelAndComponent(this, "Brain Scan", brainLabel, gbc); + gbc.weighty = 1.0; + + addSaveButton(gbc); + + beginTimer(); + } + + private void addHingeControls(GridBagConstraints gbc) { + for (ODEHinge hinge : creatureController.getHinges()) { + addAction(hinge.getName(), hinge, gbc); + gbc.gridy++; + gbc.gridx = 0; + } + } + + // a save button to export the brain to a file + private void addSaveButton(GridBagConstraints gbc) { + JButton saveButton = new JButton("Save!"); + saveButton.addActionListener((e) -> { + JFileChooser fc = new JFileChooser(); + int returnVal = fc.showSaveDialog(this); + if (returnVal == JFileChooser.APPROVE_OPTION) { + // save brain image to fc.getSelectedFile() + var brainScan = creatureController.getBrain().getImage(); + try { + javax.imageio.ImageIO.write(brainScan, "png", fc.getSelectedFile()); + } catch (Exception ex) { + ex.printStackTrace(); + } + } + }); + gbc.gridy++; + gbc.gridwidth=2; + PanelHelper.addLabelAndComponent(this, "Image", saveButton, gbc); + } + + @Override + public void addNotify() { + super.addNotify(); + beginTimer(); + } + + @Override + public void removeNotify() { + super.removeNotify(); + endTimer(); + } + + private void endTimer() { + if (timer != null) { + timer.stop(); + timer=null; + } + } + + private void beginTimer() { + // Create a timer that calls an ActionListener every 67 milliseconds + if (timer == null) { + timer = new Timer(1000 / 15, e -> updateBrainImage()); + timer.start(); } } - private void addAction(String label,ODEHinge hinge) { + private void updateBrainImage() { + // update the brain image + brainLabel.setIcon(new ImageIcon(creatureController.getBrain().getImage())); + brainLabel.repaint(); + } + + private void addAction(String label,ODEHinge hinge,GridBagConstraints gbc) { JPanel panel = new JPanel(new FlowLayout(FlowLayout.CENTER,5,0)); + // torque qty + var formatter = NumberFormatHelper.getNumberFormatter(); + formatter.setMinimum(0.0); + JFormattedTextField torqueField = new JFormattedTextField(formatter); + torqueField.setValue(myFirstTorque); + torqueField.addPropertyChangeListener("value", (evt) ->{ + myFirstTorque = ((Number) torqueField.getValue()).doubleValue(); + }); + panel.add(torqueField); + + // add torque JButton selector = new JButton("+"); - selector.addActionListener((e)-> hinge.addTorque(250000)); + selector.addActionListener((e)-> hinge.addTorque(myFirstTorque)); panel.add(selector); + // add reverse torque JButton selector2 = new JButton("-"); - selector2.addActionListener((e)-> hinge.addTorque(-250000)); + selector2.addActionListener((e)-> hinge.addTorque(-myFirstTorque)); panel.add(selector2); - - PanelHelper.addLabelAndComponent(this, label, panel); + PanelHelper.addLabelAndComponent(this, label, panel, gbc); } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java index c267fdc32..e7a0f12cf 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java @@ -31,6 +31,7 @@ public abstract class ODEBody extends ODENode { private double massQty=1; private final Vector3d angularVel = new Vector3d(); private final Vector3d linearVel = new Vector3d(); + private boolean isTouchingSomething = false; public ODEBody() { this("ODE Body"); @@ -178,4 +179,12 @@ public void setLinearVel(Vector3d linearVel) { public DGeom getGeom() { return geom; } + + public boolean isTouchingSomething() { + return isTouchingSomething; + } + + public void setTouchingSomething(boolean isTouchingSomething) { + this.isTouchingSomething = isTouchingSomething; + } } From 9b728a8c4f2d84568ef80457cac0d91df3934cd3 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 8 May 2024 12:57:30 -0700 Subject: [PATCH 37/52] cleaning --- .../ro3/node/nodes/odenode/Brain.java | 30 +++-- .../nodes/odenode/CreatureController.java | 113 ++++++++++++++---- 2 files changed, 110 insertions(+), 33 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java index 456a294ba..260260d79 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java @@ -13,7 +13,9 @@ public class Brain { private final List matrices = new ArrayList<>(); // build a list of contacts for each body private final List isTouching = new ArrayList<>(); - private final static int memoryLength = 30*3; // fps * seconds + public static int FPS = 30; + public static int MEMORY_SECONDS = 3; + private final static int MEMORY_FRAMES = FPS * MEMORY_SECONDS; // fps * seconds private int k=0; private final List neurons = new ArrayList<>(); @@ -34,9 +36,10 @@ public void setNumInputs(int size) { matrices.add(new Matrix4d()); } - // every matrix is 4 inputs - // every is touching is 1 input. - image = new BufferedImage(size * 5, memoryLength, BufferedImage.TYPE_INT_ARGB); + // every matrix is 12 inputs and can be expressed as 4 RGB pixels with 3 colors each. + // every is touching is 1 input. use a single color chanel of each pixel. + // force data from the hinges is 1 matrix each. + image = new BufferedImage(size * 5, MEMORY_FRAMES, BufferedImage.TYPE_INT_RGB); eraseBrainScan(); } @@ -65,23 +68,28 @@ void update(double dt) { // move every row of the image down one. updateImage(); + // write new data to the top row. writeInputsToTopLineOfImage(); + + // run the neural network + for(Neuron n : neurons) { + n.update(dt); + } } private void writeInputsToTopLineOfImage() { // every matrix value is copied to a pixel in the first row of the image. // every isTouching value is copied to a pixel in the first row of the image. k = 0; - int i=0; - for (Matrix4d m : matrices) { + for(Matrix4d m : matrices) { addPixelToTopRow(m.m00, m.m10, m.m20, 1, -1); addPixelToTopRow(m.m01, m.m11, m.m21, 1, -1); addPixelToTopRow(m.m02, m.m12, m.m22, 1, -1); - addPixelToTopRow(m.m03, m.m13, m.m23, 20, -20); + addPixelToTopRow(m.m03, m.m13, m.m23, 1, -1); } - for (Matrix4d m : matrices) { - image.setRGB(k++, 0, isTouching.get(i++) ? 0xffff0000:0 ); + for(int i=0; i0;--y) { + for (int y = MEMORY_FRAMES -1; y>0; --y) { for (int x=0;x hinges = new ArrayList<>(); private final List bodies = new ArrayList<>(); private final Brain brain = new Brain(); + // max experienced during simulation + private double maxForce = 0; + // max experienced during simulation + private double maxTorque = 0; public CreatureController() { super("CreatureController"); @@ -99,49 +106,111 @@ protected void onFirstUpdate() { hinges.addAll(findHinges()); bodies.clear(); bodies.addAll(findBodies()); - brain.setNumInputs(bodies.size()+1); + brain.setNumInputs(bodies.size()+hinges.size()+1); + + // add feedback to hinges + for(ODEHinge h : hinges) { + h.getHinge().setFeedback(new DJoint.DJointFeedback()); + } } @Override public void update(double dt) { super.update(dt); - // any bodies that are marked isTouching must be because onCollision says so. + sendSensoryInputToBrain(dt); + + // perform magic + brain.update(dt); + + sendBrainOutputToHinges(); + + // reset the isTouching flag on all bodies + for (ODEBody b : bodies) { + b.setTouchingSomething(false); + } + } + private void sendSensoryInputToBrain(double dt) { // get the matrix for the torso, probably always bodies[0]? Not guaranteed. var torsoMatrix = bodies.get(0).getWorld(); - torsoMatrix.invert(); + var iTorso = new Matrix4d(); + iTorso.invert(torsoMatrix); // multiply all brain matrices by the inverse of torsoMatrix + var t = new Vector3d(); int i=0; for (ODEBody b : bodies) { - // I'm concerned this is not the correct matrix. - // the translation values are not normalized. var m = b.getWorld(); - m.mul(torsoMatrix); - brain.setMatrix(i,m); - brain.setTouching(i,b.isTouchingSomething()); - System.out.print(b.isTouchingSomething()?"1":"0"); - ++i; + // normalize rotation. + m.mul(iTorso); + // normalize translation + m.get(t); + t.scale(0.1); + m.setTranslation(t); + // set to brain + brain.setMatrix(i++, m); } - System.out.println(); + // any bodies that are marked isTouching must be because onCollision says so. + // onCollision happens before update, so this is the right place to check the flag. + // add the isTouching flag to the brain sensory input + i=0; + for (ODEBody b : bodies) { + brain.setTouching(i++,b.isTouchingSomething()); + } + + // add the hinge feedback to the brain sensory input + Matrix4d hm = new Matrix4d(); + for( ODEHinge hinge : hinges) { + var internalHinge = hinge.getHinge(); + if(internalHinge==null) { + hm.setIdentity(); + } else { + convertHingeFeedbackToMatrix(internalHinge.getFeedback(),hm); + } + brain.setMatrix(i++,hm); + } + + // add the torso matrix. Good for world up, world north, height above flat ground. brain.setMatrix(i,torsoMatrix); - // I have all the input for the robot dog, normalized. - // some magic happens here - brain.update(dt); + //System.out.println("f"+fmax+" t"+tmax); + } + private void convertHingeFeedbackToMatrix(DJoint.DJointFeedback feedback, Matrix4d hm) { + hm.m00 = calcMaxF(feedback.f1.get0()); + hm.m10 = calcMaxF(feedback.f1.get1()); + hm.m20 = calcMaxF(feedback.f1.get2()); + hm.m01 = calcMaxT(feedback.t1.get0()); + hm.m11 = calcMaxT(feedback.t1.get1()); + hm.m21 = calcMaxT(feedback.t1.get2()); + hm.m02 = calcMaxF(feedback.f2.get0()); + hm.m12 = calcMaxF(feedback.f2.get1()); + hm.m22 = calcMaxF(feedback.f2.get2()); + hm.m03 = calcMaxT(feedback.t2.get0()); + hm.m13 = calcMaxT(feedback.t2.get1()); + hm.m23 = calcMaxT(feedback.t2.get2()); + } + + private double calcMaxF(double f22) { + maxForce = Math.max(maxForce,Math.abs(f22)); + return maxForce >0 ? (f22/ maxForce) : f22; + } + + private double calcMaxT(double t22) { + maxTorque = Math.max(maxTorque,Math.abs(t22)); + return maxTorque >0 ? (t22/ maxTorque) : t22; + } + + private void sendBrainOutputToHinges() { // I want the system to output torque values for each hinge. - i=0; + int i=0; for (ODEHinge h : hinges) { - h.addTorque(brain.getOutput(i)); - ++i; - } - - // reset the isTouching flag on all bodies - for (ODEBody b : bodies) { - b.setTouchingSomething(false); + var force = brain.getOutput(i++); + //System.out.print(force+"\t"); + h.addTorque(force * maxTorque); // 2.5e5 = 250k } + //System.out.println(); } public List getHinges() { From 67454473e0f35a8abc76a5ad2e56b9d50223b401 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 8 May 2024 12:58:10 -0700 Subject: [PATCH 38/52] remove reference to neuron (too soon!) --- .../com/marginallyclever/ro3/node/nodes/odenode/Brain.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java index 260260d79..8892de8b9 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java @@ -70,11 +70,11 @@ void update(double dt) { updateImage(); // write new data to the top row. writeInputsToTopLineOfImage(); - +/* // run the neural network for(Neuron n : neurons) { n.update(dt); - } + }*/ } private void writeInputsToTopLineOfImage() { From febc60aad3e647ee0138fcc43ba1b60b4bd3bbd3 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 14 May 2024 11:30:57 -0700 Subject: [PATCH 39/52] added physics settings panel --- .../com/marginallyclever/ro3/AllPanels.java | 4 +- .../com/marginallyclever/ro3/apps/App.java | 2 +- .../ro3/apps/dialogs/AppSettingsDialog.java | 5 +- .../apps/ode4j/ODEPhysicsSettingsPanel.java | 74 +++++++++++++++++++ .../apps/viewport/ViewportSettingsPanel.java | 4 +- .../ro3/physics/ODEPhysics.java | 48 ++++++++++-- .../ro3/physics/ODEPhysicsPanel.java | 11 --- 7 files changed, 126 insertions(+), 22 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/apps/ode4j/ODEPhysicsSettingsPanel.java delete mode 100644 src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java diff --git a/src/main/java/com/marginallyclever/ro3/AllPanels.java b/src/main/java/com/marginallyclever/ro3/AllPanels.java index 19b484be3..f052af7ee 100644 --- a/src/main/java/com/marginallyclever/ro3/AllPanels.java +++ b/src/main/java/com/marginallyclever/ro3/AllPanels.java @@ -2,7 +2,7 @@ import com.formdev.flatlaf.FlatLightLaf; import com.marginallyclever.ro3.node.nodes.pose.poses.*; -import com.marginallyclever.ro3.physics.ODEPhysicsPanel; +import com.marginallyclever.ro3.apps.ode4j.ODEPhysicsSettingsPanel; import org.reflections.Reflections; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -107,7 +107,7 @@ private Collection> getHandmadeList() { com.marginallyclever.ro3.node.nodes.limbplanner.LimbPlannerPanel.class, com.marginallyclever.ro3.node.nodes.limbsolver.LimbSolverPanel.class, com.marginallyclever.ro3.node.nodes.marlinrobotarm.MarlinRobotArmPanel.class, - ODEPhysicsPanel.class, + ODEPhysicsSettingsPanel.class, com.marginallyclever.ro3.node.nodes.pose.PosePanel.class, AttachmentPointPanel.class, CameraPanel.class, diff --git a/src/main/java/com/marginallyclever/ro3/apps/App.java b/src/main/java/com/marginallyclever/ro3/apps/App.java index b6d63885e..2588a105a 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/App.java +++ b/src/main/java/com/marginallyclever/ro3/apps/App.java @@ -4,7 +4,7 @@ import java.awt.*; /** - * All apps extend from App for Reflection. + * All applications in the environment extend from {@link App} for Reflection. */ public abstract class App extends JPanel { public App() { diff --git a/src/main/java/com/marginallyclever/ro3/apps/dialogs/AppSettingsDialog.java b/src/main/java/com/marginallyclever/ro3/apps/dialogs/AppSettingsDialog.java index d7f132418..26597ca15 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/dialogs/AppSettingsDialog.java +++ b/src/main/java/com/marginallyclever/ro3/apps/dialogs/AppSettingsDialog.java @@ -40,7 +40,9 @@ public AppSettingsDialog(List apps) { ViewProvider viewProvider = (ViewProvider) clazz.getConstructor().newInstance(); viewProvider.setViewSubject(appInstance); JPanel viewPanel = (JPanel)viewProvider; - tabbedPane.addTab(appClass.getSimpleName(), viewPanel); + JPanel container = new JPanel(new BorderLayout()); + container.add(viewPanel, BorderLayout.NORTH); + tabbedPane.addTab(((JPanel) viewProvider).getName(), container); } catch (NoSuchMethodException | IllegalAccessException | InstantiationException | InvocationTargetException e) { logger.error("Error creating view for app: " + appInstance.getClass().getSimpleName(), e); } @@ -49,6 +51,7 @@ public AppSettingsDialog(List apps) { } public void run(Component parent) { + // show message dialog is the reason the dialog cannot be resized. JOptionPane.showMessageDialog(parent, this, "Settings", JOptionPane.PLAIN_MESSAGE); } } \ No newline at end of file diff --git a/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODEPhysicsSettingsPanel.java b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODEPhysicsSettingsPanel.java new file mode 100644 index 000000000..44debf482 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/apps/ode4j/ODEPhysicsSettingsPanel.java @@ -0,0 +1,74 @@ +package com.marginallyclever.ro3.apps.ode4j; + +import com.marginallyclever.convenience.swing.NumberFormatHelper; +import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.physics.ODEPhysics; +import com.marginallyclever.ro3.view.View; +import com.marginallyclever.ro3.view.ViewProvider; + +import javax.swing.*; +import javax.swing.text.NumberFormatter; +import java.awt.*; + +/** + * {@link ODEPhysicsSettingsPanel} is a {@link View} for {@link ODEPhysics}. + */ +@View(of= ODE4JPanel.class) +public class ODEPhysicsSettingsPanel extends JPanel implements ViewProvider { + private ODE4JPanel subject; + private final NumberFormatter formatter = NumberFormatHelper.getNumberFormatter(); + private final JFormattedTextField cfm = new JFormattedTextField(formatter); + private final JFormattedTextField erp = new JFormattedTextField(formatter); + private final JFormattedTextField gravity = new JFormattedTextField(formatter); + + public ODEPhysicsSettingsPanel() { + super(new GridBagLayout()); + setName("Physics"); + + GridBagConstraints gbc = new GridBagConstraints(); + gbc.weightx = 1.0; + gbc.weighty = 1.0; + gbc.gridx=0; + gbc.gridy=0; + gbc.fill = GridBagConstraints.BOTH; + + var physics = Registry.getPhysics(); + // cfm + cfm.setValue(physics.getCFM()); + PanelHelper.addLabelAndComponent(this, "CFM",cfm,gbc); + cfm.addPropertyChangeListener("value", evt -> setCFM((Double) evt.getNewValue())); + + // erp + gbc.gridy++; + erp.setValue(physics.getERP()); + PanelHelper.addLabelAndComponent(this, "ERP",erp,gbc); + erp.addPropertyChangeListener("value", evt -> setERP((Double) evt.getNewValue())); + + // gravity + gbc.gridy++; + gravity.setValue(physics.getGravity()); + PanelHelper.addLabelAndComponent(this, "Gravity",gravity,gbc); + gravity.addPropertyChangeListener("value", evt ->setGravity((Double) evt.getNewValue())); + } + + public void setCFM(double cfm) { + var physics = Registry.getPhysics(); + physics.setCFM(cfm); + } + + public void setERP(double erp) { + var physics = Registry.getPhysics(); + physics.setERP(erp); + } + + public void setGravity(double gravity) { + var physics = Registry.getPhysics(); + physics.setGravity(gravity); + } + + @Override + public void setViewSubject(ODE4JPanel subject) { + this.subject = subject; + } +} diff --git a/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java b/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java index 5f8d39379..274e6dd94 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java +++ b/src/main/java/com/marginallyclever/ro3/apps/viewport/ViewportSettingsPanel.java @@ -30,7 +30,7 @@ public class ViewportSettingsPanel extends JPanel implements ViewProvider OdeHelper.createHashSpace(null); + case 2 -> OdeHelper.createSapSpace(null, DSapSpace.AXES.XYZ); + //case 3 -> OdeHelper.createQuadTreeSpace(null, new DVector3(0, 0, 0), new DVector3(100, 100, 100), 0); + default -> OdeHelper.createSimpleSpace(); + }; } if(contacts == null) { @@ -174,4 +182,32 @@ public boolean isPaused() { public void setPaused(boolean state) { isPaused = state; } + + public double getCFM() { + return WORLD_CFM; + } + + public void setCFM(double WORLD_CFM) { + this.WORLD_CFM = WORLD_CFM; + if(world!=null) world.setCFM(WORLD_CFM); + } + + public double getERP() { + return WORLD_ERP; + } + + public void setERP(double WORLD_ERP) { + this.WORLD_ERP = WORLD_ERP; + if(world!=null) world.setERP(WORLD_ERP); + } + + public double getGravity() { + return WORLD_GRAVITY; + } + + public void setGravity(double WORLD_GRAVITY) { + this.WORLD_GRAVITY = WORLD_GRAVITY; + if(world!=null) world.setGravity(0, 0, WORLD_GRAVITY); + } + } diff --git a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java b/src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java deleted file mode 100644 index 70c94e340..000000000 --- a/src/main/java/com/marginallyclever/ro3/physics/ODEPhysicsPanel.java +++ /dev/null @@ -1,11 +0,0 @@ -package com.marginallyclever.ro3.physics; - -import javax.swing.*; -import java.awt.*; - -public class ODEPhysicsPanel extends JPanel { - public ODEPhysicsPanel() { - super(); - // TODO add physics settings - } -} From f1ad08e6770637f474ce456b5a5e34425b29b048 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 14 May 2024 11:32:34 -0700 Subject: [PATCH 40/52] added brain stuff (probably all garbage) --- .../nodes/odenode/CreatureController.java | 21 +-- .../{Brain.java => brain/BrainManager.java} | 19 ++- .../ro3/node/nodes/odenode/brain/Neuron.java | 13 ++ .../node/nodes/odenode/brain/v2/Brain.java | 139 ++++++++++++++++++ .../nodes/odenode/brain/v2/Connection.java | 57 +++++++ .../odenode/brain/v2/CortisolSimulator.java | 13 ++ .../odenode/brain/v2/DopamineSimulator.java | 15 ++ .../node/nodes/odenode/brain/v2/Neuron.java | 60 ++++++++ .../nodes/odenode/brain/v2/BrainTest.java | 63 ++++++++ .../odenode/brain/v2/ConnectionTest.java | 57 +++++++ .../nodes/odenode/brain/v2/NeuronTest.java | 46 ++++++ 11 files changed, 483 insertions(+), 20 deletions(-) rename src/main/java/com/marginallyclever/ro3/node/nodes/odenode/{Brain.java => brain/BrainManager.java} (92%) create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/Neuron.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Brain.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/CortisolSimulator.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/DopamineSimulator.java create mode 100644 src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java create mode 100644 src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java create mode 100644 src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java create mode 100644 src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java index bc51d1d8e..a52bcd4a9 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java @@ -2,6 +2,7 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.Node; +import com.marginallyclever.ro3.node.nodes.odenode.brain.BrainManager; import com.marginallyclever.ro3.node.nodes.odenode.odebody.ODEBody; import com.marginallyclever.ro3.physics.CollisionListener; import org.ode4j.ode.DContact; @@ -24,7 +25,7 @@ public class CreatureController extends ODENode implements CollisionListener { private final List hinges = new ArrayList<>(); private final List bodies = new ArrayList<>(); - private final Brain brain = new Brain(); + private final BrainManager brainManager = new BrainManager(); // max experienced during simulation private double maxForce = 0; // max experienced during simulation @@ -106,7 +107,7 @@ protected void onFirstUpdate() { hinges.addAll(findHinges()); bodies.clear(); bodies.addAll(findBodies()); - brain.setNumInputs(bodies.size()+hinges.size()+1); + brainManager.setNumInputs(bodies.size()+hinges.size()+1); // add feedback to hinges for(ODEHinge h : hinges) { @@ -121,7 +122,7 @@ public void update(double dt) { sendSensoryInputToBrain(dt); // perform magic - brain.update(dt); + brainManager.update(dt); sendBrainOutputToHinges(); @@ -148,7 +149,7 @@ private void sendSensoryInputToBrain(double dt) { t.scale(0.1); m.setTranslation(t); // set to brain - brain.setMatrix(i++, m); + brainManager.setMatrix(i++, m); } // any bodies that are marked isTouching must be because onCollision says so. @@ -156,7 +157,7 @@ private void sendSensoryInputToBrain(double dt) { // add the isTouching flag to the brain sensory input i=0; for (ODEBody b : bodies) { - brain.setTouching(i++,b.isTouchingSomething()); + brainManager.setTouching(i++,b.isTouchingSomething()); } // add the hinge feedback to the brain sensory input @@ -168,11 +169,11 @@ private void sendSensoryInputToBrain(double dt) { } else { convertHingeFeedbackToMatrix(internalHinge.getFeedback(),hm); } - brain.setMatrix(i++,hm); + brainManager.setMatrix(i++,hm); } // add the torso matrix. Good for world up, world north, height above flat ground. - brain.setMatrix(i,torsoMatrix); + brainManager.setMatrix(i,torsoMatrix); //System.out.println("f"+fmax+" t"+tmax); } @@ -206,7 +207,7 @@ private void sendBrainOutputToHinges() { // I want the system to output torque values for each hinge. int i=0; for (ODEHinge h : hinges) { - var force = brain.getOutput(i++); + var force = brainManager.getOutput(i++); //System.out.print(force+"\t"); h.addTorque(force * maxTorque); // 2.5e5 = 250k } @@ -220,7 +221,7 @@ public List getBodies() { return bodies; } - public Brain getBrain() { - return brain; + public BrainManager getBrain() { + return brainManager; } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/BrainManager.java similarity index 92% rename from src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java rename to src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/BrainManager.java index 8892de8b9..61fad4456 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/Brain.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/BrainManager.java @@ -1,6 +1,7 @@ -package com.marginallyclever.ro3.node.nodes.odenode; +package com.marginallyclever.ro3.node.nodes.odenode.brain; import com.marginallyclever.ro3.Registry; +import com.marginallyclever.ro3.node.nodes.odenode.brain.v2.Brain; import javax.vecmath.Matrix4d; import java.awt.*; @@ -8,7 +9,7 @@ import java.util.ArrayList; import java.util.List; -public class Brain { +public class BrainManager { // build a list of all body pose matrices, relative to the world private final List matrices = new ArrayList<>(); // build a list of contacts for each body @@ -17,11 +18,11 @@ public class Brain { public static int MEMORY_SECONDS = 3; private final static int MEMORY_FRAMES = FPS * MEMORY_SECONDS; // fps * seconds private int k=0; + private Brain brain; - private final List neurons = new ArrayList<>(); private BufferedImage image; - public Brain() { + public BrainManager() { // create a list of neurons // create a list of synapses } @@ -63,18 +64,16 @@ public double getOutput(int i) { return 0; } - void update(double dt) { + public void update(double dt) { if(Registry.getPhysics().isPaused()) return; // move every row of the image down one. updateImage(); // write new data to the top row. writeInputsToTopLineOfImage(); -/* - // run the neural network - for(Neuron n : neurons) { - n.update(dt); - }*/ + + // update brain + } private void writeInputsToTopLineOfImage() { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/Neuron.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/Neuron.java new file mode 100644 index 000000000..909ebddbf --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/Neuron.java @@ -0,0 +1,13 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain; + +/** + * A neuron in a brain. + * The neuron does not know how many inputs it has. + * The neuron knows how many outputs it has. + * An output might go to nothing. + * An output might go to a synapse. + * The synapse have bindings to "good" and "bad" feelings. + */ +public class Neuron { + +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Brain.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Brain.java new file mode 100644 index 000000000..54e396a62 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Brain.java @@ -0,0 +1,139 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +import java.util.ArrayList; +import java.util.List; + +public class Brain { + private List inputNeurons = new ArrayList<>(); + private List outputNeurons = new ArrayList<>(); + private List hiddenNeurons = new ArrayList<>(); + private List connections = new ArrayList<>(); + private final DopamineSimulator dopamineSimulator; + private final CortisolSimulator cortisolSimulator; + + public Brain(int numInputs, int numOutputs, DopamineSimulator dopamineSimulator, CortisolSimulator cortisolSimulator) { + super(); + this.dopamineSimulator = dopamineSimulator; + this.cortisolSimulator = cortisolSimulator; + + // Initialize input neurons on the x=0 plane + for (int i = 0; i < numInputs; i++) { + inputNeurons.add(new Neuron(0, i, 0)); + } + + // Initialize output neurons on the y=0 plane + for (int i = 0; i < numOutputs; i++) { + outputNeurons.add(new Neuron(i, 0, 0)); + } + + // Create initial connections between input and output neurons + for (Neuron inputNeuron : inputNeurons) { + for (Neuron outputNeuron : outputNeurons) { + Connection connection = new Connection(inputNeuron, outputNeuron, Math.random() * 0.2 - 0.1); + addConnection(connection); + } + } + } + + public void setInputs(List inputs) { + if(inputs.size() != inputNeurons.size()) { + throw new IllegalArgumentException("Number of inputs must match the number of input neurons"); + } + // Feed the input through the network + for (int i = 0; i < inputs.size(); i++) { + inputNeurons.get(i).setInputValue(inputs.get(i)); + } + } + + /** + * Train the network with a set of inputs and expected outputs + * @param inputs List of input values + * @param expectedOutputs List of expected output values + */ + public void train(List inputs, List expectedOutputs) { + setInputs(inputs); + + propagate(); + + if(expectedOutputs.size() != outputNeurons.size()) { + throw new IllegalArgumentException("Number of expected outputs must match the number of output neurons"); + } + double[] output = getOutputs(); + for (int i = 0; i < expectedOutputs.size(); i++) { + double d = outputNeurons.get(i).getOutputValue(); + double error = expectedOutputs.get(i) - d; + + // what happens here? + } + } + + private void propagate() { + // Activate input neurons + for (Neuron neuron : inputNeurons) { + neuron.activate(); + } + // Activate hidden and output neurons + for (Neuron neuron : hiddenNeurons) { + neuron.activate(); + } + for (Neuron neuron : outputNeurons) { + neuron.activate(); + } + } + + public double[] getOutputs() { + // Evaluate the network's output based on the input + double[] output = new double[outputNeurons.size()]; + for (int i = 0; i < outputNeurons.size(); i++) { + output[i] = outputNeurons.get(i).getOutputValue(); + } + return output; + } + + public List findActiveConnections() { + List activeConnections = new ArrayList<>(); + for (Connection connection : connections) { + if (connection.isActive()) { + activeConnections.add(connection); + } + } + return activeConnections; + } + + public void resetNetwork() { + for (Neuron neuron : inputNeurons) { + neuron.reset(); + } + for (Neuron neuron : hiddenNeurons) { + neuron.reset(); + } + for (Neuron neuron : outputNeurons) { + neuron.reset(); + } + for (Connection connection : connections) { + connection.reset(); + } + } + + public void addNeuron(Neuron neuron) { + hiddenNeurons.add(neuron); + } + + public void addConnection(Connection connection) { + connections.add(connection); + connection.getFromNeuron().addOutgoingConnection(connection); + } + + public List getInputNeurons() { + return inputNeurons; + } + + public List getOutputNeurons() { + return outputNeurons; + } + + public List getConnections() { + return connections; + } +} + diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java new file mode 100644 index 000000000..b8680416d --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java @@ -0,0 +1,57 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +/** + * Positive weights will act as excitatory connections. + * Negative weights will act as inhibitory connections. + */ +public class Connection { + private Neuron fromNeuron; + private Neuron toNeuron; + private double weight; + private boolean active; + + public Connection(Neuron fromNeuron, Neuron toNeuron, double weight) { + this.fromNeuron = fromNeuron; + this.toNeuron = toNeuron; + this.weight = weight; + this.active = false; + } + + public void propagate() { + double propagatedValue = fromNeuron.getOutputValue() * weight; + toNeuron.addInputValue(propagatedValue); + active = true; + } + + public void reset() { + active = false; + } + + public boolean isActive() { + return active; + } + + public Neuron getFromNeuron() { + return fromNeuron; + } + + public Neuron getToNeuron() { + return toNeuron; + } + + public void addWeight(double amount) { + // Example: Increase the weight by a small factor + weight += amount; + //weight = Math.max(-1.0, Math.min(1.0, weight)); + } + + public void scaleWeight(double scale) { + // Example: Decrease the weight by a small factor + weight *= scale; + //weight = Math.max(-1.0, Math.min(1.0, weight)); + } + + public double getWeight() { + return weight; + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/CortisolSimulator.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/CortisolSimulator.java new file mode 100644 index 000000000..a6aff496b --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/CortisolSimulator.java @@ -0,0 +1,13 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +import java.util.List; + +public class CortisolSimulator { + double changeAmount = 1.0 - .01; + public void releaseCortisol(List activeConnections) { + for (Connection connection : activeConnections) { + // Weaken or prune the connection + connection.scaleWeight(changeAmount); + } + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/DopamineSimulator.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/DopamineSimulator.java new file mode 100644 index 000000000..725cc70fb --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/DopamineSimulator.java @@ -0,0 +1,15 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +import java.util.List; + +public class DopamineSimulator { + double changeAmount = 1.0 + .01; + + public void releaseDopamine(List activeConnections) { + for (Connection connection : activeConnections) { + // Strengthen the connection or add neurons along the pathway + connection.scaleWeight(changeAmount); + } + // Optionally, add new neurons to reinforce successful pathways + } +} diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java new file mode 100644 index 000000000..0b7ae5600 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java @@ -0,0 +1,60 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +import javax.vecmath.Vector3d; +import java.util.ArrayList; +import java.util.List; + +public class Neuron { + private final Vector3d position = new Vector3d(); + private double inputValue; + private double outputValue; + private final List outgoingConnections = new ArrayList<>(); + + public Neuron(double x, double y, double z) { + this.inputValue = 0.0; + this.outputValue = 0.0; + position.set(x, y, z); + } + + public Vector3d getPosition() { + return position; + } + + public double getInputValue() { + return inputValue; + } + + public void setInputValue(double inputValue) { + this.inputValue = inputValue; + } + + public double getOutputValue() { + return outputValue; + } + + public void addInputValue(double inputValue) { + this.inputValue += inputValue; + } + + public void activate() { + // Using tanh as the activation function to normalize between -1 and 1 + this.outputValue = Math.tanh(this.inputValue); + // Propagate the output value to outgoing connections + for (Connection connection : outgoingConnections) { + connection.propagate(); + } + } + + public void reset() { + this.inputValue = 0.0; + this.outputValue = 0.0; + } + + public void addOutgoingConnection(Connection connection) { + outgoingConnections.add(connection); + } + + public List getOutgoingConnections() { + return outgoingConnections; + } +} diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java new file mode 100644 index 000000000..5198aa4fc --- /dev/null +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java @@ -0,0 +1,63 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +import org.junit.jupiter.api.Test; +import static org.junit.jupiter.api.Assertions.*; + +import java.util.ArrayList; +import java.util.List; + +public class BrainTest { + @Test + public void testBrainInitialization() { + DopamineSimulator dopamineSimulator = new DopamineSimulator(); + CortisolSimulator cortisolSimulator = new CortisolSimulator(); + Brain brain = new Brain(3, 2, dopamineSimulator, cortisolSimulator); + + assertEquals(3, brain.getInputNeurons().size()); + assertEquals(2, brain.getOutputNeurons().size()); + assertEquals(3 * 2, brain.getConnections().size()); + } + + @Test + public void testTrain() { + DopamineSimulator dopamineSimulator = new DopamineSimulator(); + CortisolSimulator cortisolSimulator = new CortisolSimulator(); + Brain brain = new Brain(3, 2, dopamineSimulator, cortisolSimulator); + + List inputs = new ArrayList<>(List.of(new Double[]{0.5, -0.5, 0.1})); + List expectedOutputs = new ArrayList<>(List.of(new Double[]{0.3, -0.1})); + + brain.train(inputs, expectedOutputs); + + // Check if the connections were adjusted properly + List activeConnections = brain.findActiveConnections(); + for (Connection connection : activeConnections) { + // This is just a simple check to ensure the connections were indeed active + assertTrue(connection.isActive()); + } + } + + @Test + public void testResetNetwork() { + DopamineSimulator dopamineSimulator = new DopamineSimulator(); + CortisolSimulator cortisolSimulator = new CortisolSimulator(); + Brain brain = new Brain(3, 2, dopamineSimulator, cortisolSimulator); + + brain.resetNetwork(); + + for (Neuron neuron : brain.getInputNeurons()) { + assertEquals(0.0, neuron.getInputValue()); + assertEquals(0.0, neuron.getOutputValue()); + } + + for (Neuron neuron : brain.getOutputNeurons()) { + assertEquals(0.0, neuron.getInputValue()); + assertEquals(0.0, neuron.getOutputValue()); + } + + for (Connection connection : brain.getConnections()) { + assertFalse(connection.isActive()); + } + } +} + diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java new file mode 100644 index 000000000..c6dae7ef9 --- /dev/null +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java @@ -0,0 +1,57 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +import org.junit.jupiter.api.Test; +import static org.junit.jupiter.api.Assertions.*; + +public class ConnectionTest { + + @Test + public void testConnectionInitialization() { + Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Connection connection = new Connection(neuron1, neuron2, 0.5); + assertEquals(neuron1, connection.getFromNeuron()); + assertEquals(neuron2, connection.getToNeuron()); + assertEquals(0.5, connection.getWeight(), 1e-6); + } + + @Test + public void testConnectionPropagation() { + Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Connection connection = new Connection(neuron1, neuron2, 0.5); + neuron1.setInputValue(1.0); + neuron1.activate(); + connection.propagate(); + assertTrue(connection.isActive()); + assertEquals(0.5 * Math.tanh(1.0), neuron2.getInputValue(), 1e-6); + } + + @Test + public void testConnectionReset() { + Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Connection connection = new Connection(neuron1, neuron2, 0.5); + connection.propagate(); + connection.reset(); + assertFalse(connection.isActive()); + } + + @Test + public void testStrengthenConnection() { + Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Connection connection = new Connection(neuron1, neuron2, 0.5); + connection.scaleWeight(1.1); + assertEquals(0.55, connection.getWeight(), 1e-6); + } + + @Test + public void testWeakenConnection() { + Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Connection connection = new Connection(neuron1, neuron2, 0.5); + connection.scaleWeight(0.9); + assertEquals(0.45, connection.getWeight(), 1e-6); + } +} diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java new file mode 100644 index 000000000..d2def6175 --- /dev/null +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java @@ -0,0 +1,46 @@ +package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; + +import org.junit.jupiter.api.Test; + +import javax.vecmath.Vector3d; + +import static org.junit.jupiter.api.Assertions.*; + +public class NeuronTest { + @Test + public void testNeuronInitialization() { + Neuron neuron = new Neuron(0.0, 0.0, 0.0); + assertEquals(new Vector3d(0.0, 0.0, 0.0), neuron.getPosition()); + assertEquals(0.0, neuron.getInputValue()); + assertEquals(0.0, neuron.getOutputValue()); + } + + @Test + public void testNeuronActivation() { + Neuron neuron = new Neuron(0.0, 0.0, 0.0); + neuron.setInputValue(1.0); + neuron.activate(); + assertEquals(Math.tanh(1.0), neuron.getOutputValue(), 1e-6); + } + + @Test + public void testNeuronReset() { + Neuron neuron = new Neuron(0.0, 0.0, 0.0); + neuron.setInputValue(1.0); + neuron.activate(); + neuron.reset(); + assertEquals(0.0, neuron.getInputValue()); + assertEquals(0.0, neuron.getOutputValue()); + } + + @Test + public void testAddOutgoingConnection() { + Neuron neuron = new Neuron(0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Connection connection = new Connection(neuron, neuron2, 0.5); + neuron.addOutgoingConnection(connection); + assertEquals(1, neuron.getOutgoingConnections().size()); + assertEquals(connection, neuron.getOutgoingConnections().get(0)); + } +} + From cadb1155864103c7ad83aa858322cec2261f9894 Mon Sep 17 00:00:00 2001 From: github-actions <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 18:33:45 +0000 Subject: [PATCH 41/52] commit badge --- .github/badges/branches.svg | 2 +- .github/badges/jacoco.svg | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/badges/branches.svg b/.github/badges/branches.svg index 7cde8787e..31b43e276 100644 --- a/.github/badges/branches.svg +++ b/.github/badges/branches.svg @@ -1 +1 @@ -branches18.8% \ No newline at end of file +branches19.3% \ No newline at end of file diff --git a/.github/badges/jacoco.svg b/.github/badges/jacoco.svg index 3e4707e81..03e025368 100644 --- a/.github/badges/jacoco.svg +++ b/.github/badges/jacoco.svg @@ -1 +1 @@ -coverage20.4% \ No newline at end of file +coverage20.6% \ No newline at end of file From e9c8ab13e2a0d56e47d1503dc883df14de671878 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 15 May 2024 18:29:31 -0700 Subject: [PATCH 42/52] First connect of inputs to output neurons. --- .../nodes/odenode/CreatureController.java | 9 +- .../ro3/node/nodes/odenode/ODEHinge.java | 53 ++++++ .../ro3/node/nodes/odenode/ODEHingePanel.java | 24 +++ .../nodes/odenode/brain/BrainManager.java | 26 ++- .../node/nodes/odenode/brain/v2/Brain.java | 157 ++++++++++++++---- .../nodes/odenode/brain/v2/Connection.java | 4 + .../node/nodes/odenode/brain/v2/Neuron.java | 42 ++++- .../nodes/odenode/brain/v2/BrainTest.java | 33 +++- .../odenode/brain/v2/ConnectionTest.java | 20 +-- .../nodes/odenode/brain/v2/NeuronTest.java | 24 ++- 10 files changed, 329 insertions(+), 63 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java index a52bcd4a9..05a044aef 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/CreatureController.java @@ -30,6 +30,7 @@ public class CreatureController extends ODENode implements CollisionListener { private double maxForce = 0; // max experienced during simulation private double maxTorque = 0; + private double maxOutputTorque = 150000; // magic numbers are fun! public CreatureController() { super("CreatureController"); @@ -108,6 +109,8 @@ protected void onFirstUpdate() { bodies.clear(); bodies.addAll(findBodies()); brainManager.setNumInputs(bodies.size()+hinges.size()+1); + brainManager.setNumOutputs(hinges.size()); + brainManager.createInitialConnections(); // add feedback to hinges for(ODEHinge h : hinges) { @@ -195,12 +198,12 @@ private void convertHingeFeedbackToMatrix(DJoint.DJointFeedback feedback, Matrix private double calcMaxF(double f22) { maxForce = Math.max(maxForce,Math.abs(f22)); - return maxForce >0 ? (f22/ maxForce) : f22; + return maxForce >0 ? (f22 / maxForce) : f22; } private double calcMaxT(double t22) { maxTorque = Math.max(maxTorque,Math.abs(t22)); - return maxTorque >0 ? (t22/ maxTorque) : t22; + return maxTorque >0 ? (t22 / maxTorque) : t22; } private void sendBrainOutputToHinges() { @@ -209,7 +212,7 @@ private void sendBrainOutputToHinges() { for (ODEHinge h : hinges) { var force = brainManager.getOutput(i++); //System.out.print(force+"\t"); - h.addTorque(force * maxTorque); // 2.5e5 = 250k + h.addTorque(force * maxOutputTorque); } //System.out.println(); } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java index 7d2cf9de8..d6c4fa363 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java @@ -9,6 +9,7 @@ import org.ode4j.math.DVector3; import org.ode4j.ode.DBody; import org.ode4j.ode.DHingeJoint; +import org.ode4j.ode.DJoint; import org.ode4j.ode.OdeHelper; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -30,6 +31,8 @@ public class ODEHinge extends ODENode { private DHingeJoint hinge; private final NodePath partA = new NodePath<>(this,ODEBody.class); private final NodePath partB = new NodePath<>(this,ODEBody.class); + double top = Double.POSITIVE_INFINITY; + double bottom = Double.NEGATIVE_INFINITY; public ODEHinge() { this("ODE Hinge"); @@ -68,6 +71,8 @@ protected void onDetach() { private void createHinge() { hinge = OdeHelper.createHingeJoint(Registry.getPhysics().getODEWorld(), null); connect(); + setAngleMax(top); + setAngleMin(bottom); } private void destroyHinge() { @@ -173,6 +178,14 @@ public JSONObject toJSON() { var json = super.toJSON(); json.put("partA",partA.getUniqueID()); json.put("partB",partB.getUniqueID()); + double v = getAngleMax(); + if(!Double.isInfinite(v)) { + json.put("hiStop1",v); + } + v = getAngleMin(); + if(!Double.isInfinite(v)) { + json.put("loStop1",v); + } return json; } @@ -181,6 +194,12 @@ public void fromJSON(JSONObject from) { super.fromJSON(from); if(from.has("partA")) partA.setUniqueID(from.getString("partA")); if(from.has("partB")) partB.setUniqueID(from.getString("partB")); + if(from.has("hiStop1")) { + setAngleMax(from.getDouble("hiStop1")); + } + if(from.has("loStop1")) { + setAngleMin(from.getDouble("loStop1")); + } updatePhysicsFromWorld(); connect(); updateHingePose(); @@ -192,4 +211,38 @@ public void addTorque(double value) { hinge.addTorque(value); } } + + /** + * @return angle in degrees + */ + public double getAngleMax() { + if(hinge==null) return 0; + return Math.toDegrees(hinge.getParam(DJoint.PARAM_N.dParamHiStop1)); + } + + /** + * @return angle in degrees + */ + public double getAngleMin() { + if(hinge==null) return 0; + return Math.toDegrees(hinge.getParam(DJoint.PARAM_N.dParamLoStop1)); + } + + /** + * @param angle in degrees + */ + public void setAngleMax(double angle) { + top = angle; + if(hinge==null) return; + hinge.setParamHiStop(Math.toRadians(angle)); + } + + /** + * @param angle in degrees + */ + public void setAngleMin(double angle) { + bottom = angle; + if(hinge==null) return; + hinge.setParamLoStop(Math.toRadians(angle)); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingePanel.java index cb327db01..d052db3fb 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingePanel.java @@ -24,6 +24,30 @@ public ODEHingePanel(ODEHinge hinge) { addSelector("part A",hinge.getPartA(),hinge::setPartA); addSelector("part B",hinge.getPartB(),hinge::setPartB); addAction("Torque",hinge); + addLimit("Angle Max",hinge.getAngleMax(),hinge::setAngleMax,Double.POSITIVE_INFINITY); + addLimit("Angle Min",hinge.getAngleMin(),hinge::setAngleMin,Double.NEGATIVE_INFINITY); + } + + private void addLimit(String label, double value, Consumer consumer, double infinite) { + JCheckBox limitCheckBox = new JCheckBox("Has Limit", !Double.isInfinite(value)); + SpinnerNumberModel model = new SpinnerNumberModel(Double.isInfinite(value) ? 0 : value, -180, 180, 0.1); + JSpinner spinner = new JSpinner(model); + + limitCheckBox.addActionListener(e -> enableLimit(limitCheckBox.isSelected(),spinner,consumer,infinite) ); + spinner.addChangeListener(e -> { + if (limitCheckBox.isSelected()) { + consumer.accept((Double) spinner.getValue()); + } + }); + enableLimit(!Double.isInfinite(value),spinner,consumer,infinite); + + PanelHelper.addLabelAndComponent(this, label, limitCheckBox); + PanelHelper.addLabelAndComponent(this, "Value", spinner); + } + + private void enableLimit(boolean isSelected, JSpinner spinner, Consumer consumer,double infinite) { + spinner.setEnabled(isSelected); + consumer.accept( (!isSelected) ? infinite : (Double)spinner.getValue() ); } private void addSelector(String label, NodePath originalValue, Consumer setPartA) { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/BrainManager.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/BrainManager.java index 61fad4456..d29becdc1 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/BrainManager.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/BrainManager.java @@ -2,6 +2,8 @@ import com.marginallyclever.ro3.Registry; import com.marginallyclever.ro3.node.nodes.odenode.brain.v2.Brain; +import com.marginallyclever.ro3.node.nodes.odenode.brain.v2.CortisolSimulator; +import com.marginallyclever.ro3.node.nodes.odenode.brain.v2.DopamineSimulator; import javax.vecmath.Matrix4d; import java.awt.*; @@ -18,7 +20,8 @@ public class BrainManager { public static int MEMORY_SECONDS = 3; private final static int MEMORY_FRAMES = FPS * MEMORY_SECONDS; // fps * seconds private int k=0; - private Brain brain; + private final Brain brain = new Brain(new DopamineSimulator(),new CortisolSimulator()); + private int inputIndex=0; private BufferedImage image; @@ -42,6 +45,11 @@ public void setNumInputs(int size) { // force data from the hinges is 1 matrix each. image = new BufferedImage(size * 5, MEMORY_FRAMES, BufferedImage.TYPE_INT_RGB); eraseBrainScan(); + brain.setNumInputs(size * 12 + size); + } + + public void setNumOutputs(int size) { + brain.setNumOutputs(size); } private void eraseBrainScan() { @@ -61,7 +69,7 @@ public void setTouching(int i, boolean touching) { } public double getOutput(int i) { - return 0; + return brain.getOutput(i); } public void update(double dt) { @@ -73,7 +81,10 @@ public void update(double dt) { writeInputsToTopLineOfImage(); // update brain + brain.propagate(); + inputIndex=0; + brain.resetConnections(); } private void writeInputsToTopLineOfImage() { @@ -88,7 +99,9 @@ private void writeInputsToTopLineOfImage() { } for(int i=0; i inputNeurons = new ArrayList<>(); private List outputNeurons = new ArrayList<>(); - private List hiddenNeurons = new ArrayList<>(); + private List neurons = new ArrayList<>(); private List connections = new ArrayList<>(); private final DopamineSimulator dopamineSimulator; private final CortisolSimulator cortisolSimulator; - public Brain(int numInputs, int numOutputs, DopamineSimulator dopamineSimulator, CortisolSimulator cortisolSimulator) { + public Brain(DopamineSimulator dopamineSimulator, CortisolSimulator cortisolSimulator) { super(); this.dopamineSimulator = dopamineSimulator; this.cortisolSimulator = cortisolSimulator; + } + public void setNumInputs(int numInputs) { // Initialize input neurons on the x=0 plane for (int i = 0; i < numInputs; i++) { - inputNeurons.add(new Neuron(0, i, 0)); + var n = new Neuron(neurons.size()+i,0, i, 0); + inputNeurons.add(n); + neurons.add(n); } + } + public void setNumOutputs(int numOutputs) { // Initialize output neurons on the y=0 plane for (int i = 0; i < numOutputs; i++) { - outputNeurons.add(new Neuron(i, 0, 0)); + var n = new Neuron(neurons.size()+i, i,0, 0); + outputNeurons.add(n); + neurons.add(n); } + } + public void createInitialConnections() { // Create initial connections between input and output neurons for (Neuron inputNeuron : inputNeurons) { for (Neuron outputNeuron : outputNeurons) { - Connection connection = new Connection(inputNeuron, outputNeuron, Math.random() * 0.2 - 0.1); + Connection connection = new Connection(inputNeuron, outputNeuron, 0.000001); addConnection(connection); } } @@ -51,43 +65,43 @@ public void setInputs(List inputs) { * @param expectedOutputs List of expected output values */ public void train(List inputs, List expectedOutputs) { + resetConnections(); setInputs(inputs); - propagate(); + // Evaluate the network's output based on the input if(expectedOutputs.size() != outputNeurons.size()) { throw new IllegalArgumentException("Number of expected outputs must match the number of output neurons"); } - double[] output = getOutputs(); - for (int i = 0; i < expectedOutputs.size(); i++) { - double d = outputNeurons.get(i).getOutputValue(); - double error = expectedOutputs.get(i) - d; + double totalError = measureTotalError(expectedOutputs); + + // what happens here? + + } - // what happens here? + private double measureTotalError(List expectedOutputs) { + double totalError = 0; + for (int i = 0; i < expectedOutputs.size(); i++) { + double error = expectedOutputs.get(i) - getOutput(i); + totalError += Math.abs(error); } + return totalError; } - private void propagate() { + public void propagate() { // Activate input neurons - for (Neuron neuron : inputNeurons) { - neuron.activate(); - } - // Activate hidden and output neurons - for (Neuron neuron : hiddenNeurons) { + for (Neuron neuron : neurons) { neuron.activate(); } - for (Neuron neuron : outputNeurons) { - neuron.activate(); + + // Propagate the output value to outgoing connections + for (Connection connection : connections) { + connection.propagate(); } } - public double[] getOutputs() { - // Evaluate the network's output based on the input - double[] output = new double[outputNeurons.size()]; - for (int i = 0; i < outputNeurons.size(); i++) { - output[i] = outputNeurons.get(i).getOutputValue(); - } - return output; + public double getOutput(int index) { + return outputNeurons.get(index).getOutputValue(); } public List findActiveConnections() { @@ -101,22 +115,24 @@ public List findActiveConnections() { } public void resetNetwork() { - for (Neuron neuron : inputNeurons) { - neuron.reset(); - } - for (Neuron neuron : hiddenNeurons) { - neuron.reset(); - } - for (Neuron neuron : outputNeurons) { + resetNeurons(); + resetConnections(); + } + + public void resetNeurons() { + for (Neuron neuron : neurons) { neuron.reset(); } + } + + public void resetConnections() { for (Connection connection : connections) { connection.reset(); } } public void addNeuron(Neuron neuron) { - hiddenNeurons.add(neuron); + neurons.add(neuron); } public void addConnection(Connection connection) { @@ -135,5 +151,78 @@ public List getOutputNeurons() { public List getConnections() { return connections; } + + public JSONObject toJSON() { + JSONObject json = new JSONObject(); + json.put("neurons", getNeuronsAsJSON(neurons)); + json.put("connections", getConnectionsAsJSON(connections)); + json.put("inputNeurons", getNeuronListAsJSON(inputNeurons)); + json.put("outputNeurons", getNeuronListAsJSON(outputNeurons)); + return json; + } + + private JSONArray getNeuronListAsJSON(List neurons) { + JSONArray json = new JSONArray(); + for (Neuron neuron : neurons) { + json.put(neuron.getID()); + } + return json; + } + + private JSONArray getConnectionsAsJSON(List connections) { + JSONArray json = new JSONArray(); + for (int i = 0; i < connections.size(); i++) { + Connection connection = connections.get(i); + JSONObject connectionJSON = new JSONObject(); + connectionJSON.put("fromNeuron", connection.getFromNeuron().getID()); + connectionJSON.put("toNeuron", connection.getToNeuron().getID()); + connectionJSON.put("weight", connection.getWeight()); + json.put(connectionJSON); + } + return json; + } + + private JSONArray getNeuronsAsJSON(List neurons) { + JSONArray json = new JSONArray(); + for (Neuron neuron : neurons) { + json.put(neuron.toJSON()); + } + return json; + } + + public void setInput(int i, double value) { + inputNeurons.get(i).setInputValue(value); + } + + public void fromJSON(JSONObject json) { + JSONArray neuronList = json.getJSONArray("neurons"); + for (int i = 0; i < neuronList.length(); i++) { + Neuron neuron = new Neuron(i,0,0,0); + neurons.add(neuron); + neuron.fromJSON(neuronList.getJSONObject(i)); + } + + JSONArray connectionsJSON = json.getJSONArray("connections"); + for (int i = 0; i < connectionsJSON.length(); i++) { + JSONObject conn = connectionsJSON.getJSONObject(i); + int fromNeuronID = conn.getInt("fromNeuron"); + int toNeuronID = conn.getInt("toNeuron"); + double weight = conn.getDouble("weight"); + Connection connection = new Connection(neurons.get(fromNeuronID), neurons.get(toNeuronID), weight); + connections.add(connection); + } + + JSONArray inputNeuronIDs = json.getJSONArray("inputNeurons"); + for (int i = 0; i < inputNeuronIDs.length(); i++) { + int id = inputNeuronIDs.getInt(i); + inputNeurons.add(neurons.get(id)); + } + + JSONArray outputNeuronIDs = json.getJSONArray("outputNeurons"); + for (int i = 0; i < outputNeuronIDs.length(); i++) { + int id = outputNeuronIDs.getInt(i); + outputNeurons.add(neurons.get(id)); + } + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java index b8680416d..df56849d2 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Connection.java @@ -1,5 +1,7 @@ package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; +import org.json.JSONObject; + /** * Positive weights will act as excitatory connections. * Negative weights will act as inhibitory connections. @@ -18,6 +20,8 @@ public Connection(Neuron fromNeuron, Neuron toNeuron, double weight) { } public void propagate() { + if(weight==0) return; + double propagatedValue = fromNeuron.getOutputValue() * weight; toNeuron.addInputValue(propagatedValue); active = true; diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java index 0b7ae5600..d38ffc187 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/Neuron.java @@ -1,16 +1,23 @@ package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; +import org.json.JSONArray; +import org.json.JSONObject; + import javax.vecmath.Vector3d; import java.util.ArrayList; import java.util.List; +/** + * A neuron in the brain. + */ public class Neuron { private final Vector3d position = new Vector3d(); + private int id; private double inputValue; private double outputValue; private final List outgoingConnections = new ArrayList<>(); - public Neuron(double x, double y, double z) { + public Neuron(int id,double x, double y, double z) { this.inputValue = 0.0; this.outputValue = 0.0; position.set(x, y, z); @@ -39,10 +46,6 @@ public void addInputValue(double inputValue) { public void activate() { // Using tanh as the activation function to normalize between -1 and 1 this.outputValue = Math.tanh(this.inputValue); - // Propagate the output value to outgoing connections - for (Connection connection : outgoingConnections) { - connection.propagate(); - } } public void reset() { @@ -57,4 +60,33 @@ public void addOutgoingConnection(Connection connection) { public List getOutgoingConnections() { return outgoingConnections; } + + public int getID() { + return id; + } + + public JSONObject toJSON() { + JSONObject json = new JSONObject(); + json.put("id", getID()); + json.put("position", positionToJSON()); + json.put("inputValue", getInputValue()); + json.put("outputValue", getOutputValue()); + return json; + } + + public void fromJSON(JSONObject json) { + id = json.getInt("id"); + JSONArray p = json.getJSONArray("position"); + position.set(p.getDouble(0), p.getDouble(1), p.getDouble(2)); + setInputValue(json.getDouble("inputValue")); + outputValue = json.getDouble("outputValue"); + } + + private JSONArray positionToJSON() { + JSONArray json = new JSONArray(); + json.put(position.x); + json.put(position.y); + json.put(position.z); + return json; + } } diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java index 5198aa4fc..e9474e2bb 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/BrainTest.java @@ -1,5 +1,6 @@ package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; +import org.json.JSONObject; import org.junit.jupiter.api.Test; import static org.junit.jupiter.api.Assertions.*; @@ -11,7 +12,10 @@ public class BrainTest { public void testBrainInitialization() { DopamineSimulator dopamineSimulator = new DopamineSimulator(); CortisolSimulator cortisolSimulator = new CortisolSimulator(); - Brain brain = new Brain(3, 2, dopamineSimulator, cortisolSimulator); + Brain brain = new Brain( dopamineSimulator, cortisolSimulator); + brain.setNumInputs(3); + brain.setNumOutputs(2); + brain.createInitialConnections(); assertEquals(3, brain.getInputNeurons().size()); assertEquals(2, brain.getOutputNeurons().size()); @@ -22,7 +26,10 @@ public void testBrainInitialization() { public void testTrain() { DopamineSimulator dopamineSimulator = new DopamineSimulator(); CortisolSimulator cortisolSimulator = new CortisolSimulator(); - Brain brain = new Brain(3, 2, dopamineSimulator, cortisolSimulator); + Brain brain = new Brain(dopamineSimulator, cortisolSimulator); + brain.setNumInputs(3); + brain.setNumOutputs(2); + brain.createInitialConnections(); List inputs = new ArrayList<>(List.of(new Double[]{0.5, -0.5, 0.1})); List expectedOutputs = new ArrayList<>(List.of(new Double[]{0.3, -0.1})); @@ -41,7 +48,9 @@ public void testTrain() { public void testResetNetwork() { DopamineSimulator dopamineSimulator = new DopamineSimulator(); CortisolSimulator cortisolSimulator = new CortisolSimulator(); - Brain brain = new Brain(3, 2, dopamineSimulator, cortisolSimulator); + Brain brain = new Brain(dopamineSimulator, cortisolSimulator); + brain.setNumInputs(3); + brain.setNumOutputs(2); brain.resetNetwork(); @@ -59,5 +68,23 @@ public void testResetNetwork() { assertFalse(connection.isActive()); } } + + @Test + public void testJSON() { + DopamineSimulator dopamineSimulator = new DopamineSimulator(); + CortisolSimulator cortisolSimulator = new CortisolSimulator(); + Brain before = new Brain(dopamineSimulator, cortisolSimulator); + before.setNumInputs(3); + before.setNumOutputs(2); + before.createInitialConnections(); + + JSONObject json = before.toJSON(); + Brain after = new Brain(dopamineSimulator,cortisolSimulator); + after.fromJSON(json); + + assertEquals(before.getInputNeurons().size(), after.getInputNeurons().size()); + assertEquals(before.getOutputNeurons().size(), after.getOutputNeurons().size()); + assertEquals(before.getConnections().size(), after.getConnections().size()); + } } diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java index c6dae7ef9..2878a8420 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/ConnectionTest.java @@ -7,8 +7,8 @@ public class ConnectionTest { @Test public void testConnectionInitialization() { - Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); - Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Neuron neuron1 = new Neuron(0,0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1,1.0, 0.0, 0.0); Connection connection = new Connection(neuron1, neuron2, 0.5); assertEquals(neuron1, connection.getFromNeuron()); assertEquals(neuron2, connection.getToNeuron()); @@ -17,8 +17,8 @@ public void testConnectionInitialization() { @Test public void testConnectionPropagation() { - Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); - Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Neuron neuron1 = new Neuron(0,0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1,1.0, 0.0, 0.0); Connection connection = new Connection(neuron1, neuron2, 0.5); neuron1.setInputValue(1.0); neuron1.activate(); @@ -29,8 +29,8 @@ public void testConnectionPropagation() { @Test public void testConnectionReset() { - Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); - Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Neuron neuron1 = new Neuron(0,0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1,1.0, 0.0, 0.0); Connection connection = new Connection(neuron1, neuron2, 0.5); connection.propagate(); connection.reset(); @@ -39,8 +39,8 @@ public void testConnectionReset() { @Test public void testStrengthenConnection() { - Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); - Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Neuron neuron1 = new Neuron(0,0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1,1.0, 0.0, 0.0); Connection connection = new Connection(neuron1, neuron2, 0.5); connection.scaleWeight(1.1); assertEquals(0.55, connection.getWeight(), 1e-6); @@ -48,8 +48,8 @@ public void testStrengthenConnection() { @Test public void testWeakenConnection() { - Neuron neuron1 = new Neuron(0.0, 0.0, 0.0); - Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Neuron neuron1 = new Neuron(0,0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1,1.0, 0.0, 0.0); Connection connection = new Connection(neuron1, neuron2, 0.5); connection.scaleWeight(0.9); assertEquals(0.45, connection.getWeight(), 1e-6); diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java index d2def6175..0148da451 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/brain/v2/NeuronTest.java @@ -1,5 +1,6 @@ package com.marginallyclever.ro3.node.nodes.odenode.brain.v2; +import org.json.JSONObject; import org.junit.jupiter.api.Test; import javax.vecmath.Vector3d; @@ -9,7 +10,7 @@ public class NeuronTest { @Test public void testNeuronInitialization() { - Neuron neuron = new Neuron(0.0, 0.0, 0.0); + Neuron neuron = new Neuron(0,0.0, 0.0, 0.0); assertEquals(new Vector3d(0.0, 0.0, 0.0), neuron.getPosition()); assertEquals(0.0, neuron.getInputValue()); assertEquals(0.0, neuron.getOutputValue()); @@ -17,7 +18,7 @@ public void testNeuronInitialization() { @Test public void testNeuronActivation() { - Neuron neuron = new Neuron(0.0, 0.0, 0.0); + Neuron neuron = new Neuron(0,0.0, 0.0, 0.0); neuron.setInputValue(1.0); neuron.activate(); assertEquals(Math.tanh(1.0), neuron.getOutputValue(), 1e-6); @@ -25,7 +26,7 @@ public void testNeuronActivation() { @Test public void testNeuronReset() { - Neuron neuron = new Neuron(0.0, 0.0, 0.0); + Neuron neuron = new Neuron(0,0.0, 0.0, 0.0); neuron.setInputValue(1.0); neuron.activate(); neuron.reset(); @@ -35,12 +36,25 @@ public void testNeuronReset() { @Test public void testAddOutgoingConnection() { - Neuron neuron = new Neuron(0.0, 0.0, 0.0); - Neuron neuron2 = new Neuron(1.0, 0.0, 0.0); + Neuron neuron = new Neuron(0,0.0, 0.0, 0.0); + Neuron neuron2 = new Neuron(1,1.0, 0.0, 0.0); Connection connection = new Connection(neuron, neuron2, 0.5); neuron.addOutgoingConnection(connection); assertEquals(1, neuron.getOutgoingConnections().size()); assertEquals(connection, neuron.getOutgoingConnections().get(0)); } + + @Test + public void testJSON() { + Neuron before = new Neuron(4,3.0, 2.0, 1.0); + before.setInputValue(1.0); + before.activate(); + JSONObject json = before.toJSON(); + Neuron after = new Neuron(0,0,0,0); + after.fromJSON(json); + assertEquals(before.getPosition(), after.getPosition()); + assertEquals(before.getInputValue(), after.getInputValue()); + assertEquals(before.getOutputValue(), after.getOutputValue()); + } } From fd2ddf7048c05d72b216820ab3e8d2bd5b18c855 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 15 May 2024 18:29:40 -0700 Subject: [PATCH 43/52] 2.112.0 --- pom.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pom.xml b/pom.xml index e45191169..52f1b3928 100644 --- a/pom.xml +++ b/pom.xml @@ -6,7 +6,7 @@ com.marginallyclever RobotOverlord - 2.111.0 + 2.112.0 Robot Overlord A friendly 3D user interface for controlling robots. https://www.marginallyclever.com/ From 8114c2ada1296df8ff200fe5a58236293f1b6cdb Mon Sep 17 00:00:00 2001 From: github-actions <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 16 May 2024 01:32:00 +0000 Subject: [PATCH 44/52] commit badge --- .github/badges/branches.svg | 2 +- .github/badges/jacoco.svg | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/badges/branches.svg b/.github/badges/branches.svg index 31b43e276..f7364f18c 100644 --- a/.github/badges/branches.svg +++ b/.github/badges/branches.svg @@ -1 +1 @@ -branches19.3% \ No newline at end of file +branches19.5% \ No newline at end of file diff --git a/.github/badges/jacoco.svg b/.github/badges/jacoco.svg index 03e025368..c79ea436c 100644 --- a/.github/badges/jacoco.svg +++ b/.github/badges/jacoco.svg @@ -1 +1 @@ -coverage20.6% \ No newline at end of file +coverage21% \ No newline at end of file From 0fff31d6789f6a189470284cbb1c0470cbf7fb5d Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Mon, 20 May 2024 17:23:41 -0700 Subject: [PATCH 45/52] correctly restore mass after serialization --- .../ro3/node/nodes/odenode/odebody/ODEBody.java | 2 +- .../nodes/odenode/odebody/odebodies/ODEBox.java | 4 ++-- .../odenode/odebody/odebodies/ODEBoxPanel.java | 8 ++++++++ .../nodes/odenode/odebody/odebodies/ODECapsule.java | 4 ++-- .../odenode/odebody/odebodies/ODECapsulePanel.java | 7 +++++++ .../odenode/odebody/odebodies/ODECylinder.java | 4 ++-- .../odenode/odebody/odebodies/ODECylinderPanel.java | 7 +++++++ .../nodes/odenode/odebody/odebodies/ODESphere.java | 4 ++-- .../odenode/odebody/odebodies/ODESpherePanel.java | 13 ++++++++++--- 9 files changed, 41 insertions(+), 12 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java index e7a0f12cf..57bcdc848 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/ODEBody.java @@ -121,7 +121,7 @@ public Icon getIcon() { } public double getMassQty() { - return mass.getMass(); + return massQty; } /** diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java index b9837371c..3dc720390 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java @@ -41,7 +41,7 @@ protected void onFirstUpdate() { geom = createBox(Registry.getPhysics().getODESpace(), size.x, size.y, size.z); geom.setBody(body); - mass.setBoxTotal(ODE4JHelper.volumeBox(size.x,size.y,size.z), size.x, size.y, size.z); + mass.setBoxTotal(getMassQty(), size.x, size.y, size.z); body.setMass(mass); updateSize(); } @@ -82,7 +82,7 @@ private void updateSize() { ((DBox)geom).setLengths(size.x, size.y, size.z); geom.setBody(body); - mass.setBoxTotal(mass.getMass(), size.x, size.y, size.z); + mass.setBoxTotal(getMassQty(), size.x, size.y, size.z); body.setMass(mass); var meshInstance = findFirstChild(MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBoxPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBoxPanel.java index 8ae0bdb87..4f26490dd 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBoxPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBoxPanel.java @@ -2,6 +2,7 @@ import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.physics.ODE4JHelper; import javax.swing.*; import java.awt.*; @@ -22,6 +23,12 @@ public ODEBoxPanel(ODEBox body) { addField("Size X", body.getSizeX(), body::setSizeX); addField("Size Y", body.getSizeY(), body::setSizeY); addField("Size Z", body.getSizeZ(), body::setSizeZ); + + JButton setMassByVolume = new JButton("Set"); + setMassByVolume.addActionListener(e -> { + body.setMassQty(ODE4JHelper.volumeBox(body.getSizeX(),body.getSizeY(),body.getSizeZ())); + }); + PanelHelper.addLabelAndComponent(this,"Mass by Volume",setMassByVolume); } private void addField(String label, double originalValue, DoubleConsumer setSize) { @@ -32,5 +39,6 @@ private void addField(String label, double originalValue, DoubleConsumer setSize field.setValue(originalValue); field.addPropertyChangeListener("value", e -> setSize.accept( ((Number)field.getValue()).doubleValue() )); PanelHelper.addLabelAndComponent(this,label,field); + } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java index aa583b0bc..302154c42 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java @@ -42,7 +42,7 @@ protected void onFirstUpdate() { geom = OdeHelper.createCapsule(Registry.getPhysics().getODESpace(), radius, length); geom.setBody(body); - mass.setCapsuleTotal(ODE4JHelper.volumeCapsule(radius,length), 3, radius, length); + mass.setCapsuleTotal(getMassQty(), 3, radius, length); body.setMass(mass); updateSize(); @@ -74,7 +74,7 @@ private void updateSize() { ((DCapsule)geom).setParams(radius, length); geom.setBody(body); - mass.setCapsuleTotal(mass.getMass(), 3, radius, length); + mass.setCapsuleTotal(getMassQty(), 3, radius, length); body.setMass(mass); MeshInstance meshInstance = findFirstChild(MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsulePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsulePanel.java index db44057f8..aa5584c30 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsulePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsulePanel.java @@ -2,6 +2,7 @@ import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.physics.ODE4JHelper; import javax.swing.*; import java.awt.*; @@ -20,6 +21,12 @@ public ODECapsulePanel(ODECapsule body) { addField("Radius", body.getRadius(), body::setRadius); addField("Length", body.getLength(), body::setLength); + + JButton setMassByVolume = new JButton("Set"); + setMassByVolume.addActionListener(e -> { + body.setMassQty(ODE4JHelper.volumeCapsule(body.getRadius(),body.getLength())); + }); + PanelHelper.addLabelAndComponent(this,"Mass by Volume",setMassByVolume); } private void addField(String label, double originalValue, DoubleConsumer setSize) { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java index d6db927c6..60a5c2593 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java @@ -40,7 +40,7 @@ protected void onFirstUpdate() { geom = OdeHelper.createCylinder(Registry.getPhysics().getODESpace(), radius, length); geom.setBody(body); - mass.setCylinderTotal(ODE4JHelper.volumeCylinder(radius,length), 3, radius, length); + mass.setCylinderTotal(getMassQty(), 3, radius, length); body.setMass(mass); updateSize(); @@ -72,7 +72,7 @@ private void updateSize() { ((DCylinder)geom).setParams(radius, length); geom.setBody(body); - mass.setCylinderTotal(mass.getMass(), 3, radius, length); + mass.setCylinderTotal(getMassQty(), 3, radius, length); body.setMass(mass); MeshInstance meshInstance = findFirstChild(MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinderPanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinderPanel.java index f02264cd3..95129800e 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinderPanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinderPanel.java @@ -2,6 +2,7 @@ import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.physics.ODE4JHelper; import javax.swing.*; import java.awt.*; @@ -21,6 +22,12 @@ public ODECylinderPanel(ODECylinder body) { addField("Radius", body.getRadius(), body::setRadius); addField("Length", body.getLength(), body::setLength); + + JButton setMassByVolume = new JButton("Set"); + setMassByVolume.addActionListener(e -> { + body.setMassQty(ODE4JHelper.volumeCylinder(body.getRadius(),body.getLength())); + }); + PanelHelper.addLabelAndComponent(this,"Mass by Volume",setMassByVolume); } private void addField(String label, double originalValue, DoubleConsumer setSize) { diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java index a4639f530..33a00a9fe 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java @@ -40,7 +40,7 @@ protected void onFirstUpdate() { geom = createSphere(Registry.getPhysics().getODESpace(), radius); geom.setBody(body); - mass.setSphereTotal(ODE4JHelper.volumeSphere(radius), radius); + mass.setSphereTotal(getMassQty(), radius); body.setMass(mass); updateSize(); @@ -62,7 +62,7 @@ private void updateSize() { ((DSphere)geom).setRadius(radius); geom.setBody(body); - mass.setSphereTotal(mass.getMass(), radius); + mass.setSphereTotal(getMassQty(), radius); body.setMass(mass); var meshInstance = findFirstChild(MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESpherePanel.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESpherePanel.java index f43dd4121..ec218d4a6 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESpherePanel.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESpherePanel.java @@ -2,6 +2,7 @@ import com.marginallyclever.convenience.swing.NumberFormatHelper; import com.marginallyclever.ro3.PanelHelper; +import com.marginallyclever.ro3.physics.ODE4JHelper; import javax.swing.*; import java.awt.*; @@ -14,7 +15,7 @@ public ODESpherePanel() { this(new ODESphere()); } - public ODESpherePanel(ODESphere sphere) { + public ODESpherePanel(ODESphere body) { super(new GridLayout(0,2)); this.setName(ODESphere.class.getSimpleName()); @@ -22,8 +23,14 @@ public ODESpherePanel(ODESphere sphere) { formatter.setMinimum(0.001); JFormattedTextField radiusValue = new JFormattedTextField(formatter); - radiusValue.setValue(sphere.getRadius()); - radiusValue.addPropertyChangeListener("value", e -> sphere.setRadius( ((Number)radiusValue.getValue()).doubleValue() )); + radiusValue.setValue(body.getRadius()); + radiusValue.addPropertyChangeListener("value", e -> body.setRadius( ((Number)radiusValue.getValue()).doubleValue() )); PanelHelper.addLabelAndComponent(this,"Radius",radiusValue); + + JButton setMassByVolume = new JButton("Set"); + setMassByVolume.addActionListener(e -> { + body.setMassQty(ODE4JHelper.volumeSphere(body.getRadius())); + }); + PanelHelper.addLabelAndComponent(this,"Mass by Volume",setMassByVolume); } } From 04520d9dda9c3d5ca7346ed17290471291445ed6 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 22 May 2024 13:38:01 -0700 Subject: [PATCH 46/52] better sun distance and light depth map --- .../apps/viewport/renderpasses/DrawMeshes.java | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawMeshes.java b/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawMeshes.java index 27719d037..2ec577f98 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawMeshes.java +++ b/src/main/java/com/marginallyclever/ro3/apps/viewport/renderpasses/DrawMeshes.java @@ -39,7 +39,9 @@ public class DrawMeshes extends AbstractRenderPass { private final int shadowMapUnit = 1; public static final int SHADOW_WIDTH = 1024; public static final int SHADOW_HEIGHT = 1024; - public static final Vector3d sunlightSource = new Vector3d(5,15,75); + public static final double SUN_DISTANCE = 200; + public static final double DEPTH_BUFFER_LIMIT = SUN_DISTANCE*1.5; + public static final Vector3d sunlightSource = new Vector3d(50,150,750); public static Color sunlightColor = new Color(0xfd,0xfb,0xd3,255); public static Color ambientColor = new Color(0x20,0x20,0x20,255); public static final Matrix4d lightProjection = new Matrix4d(); @@ -208,8 +210,8 @@ private void keepOnlySelectedMeshMaterials(List list) { list.retainAll(toKeep); } + // sort meshMaterial list by material private void sortMeshMaterialList(List meshMaterial) { - // sort meshMaterial list by material meshMaterial.sort((o1, o2) -> { Material m1 = o1.material(); Material m2 = o2.material(); @@ -223,6 +225,7 @@ private void sortMeshMaterialList(List meshMaterial) { }); } + // draw the shadow quad into the world for debugging. private void drawShadowQuad(GL3 gl3, Camera camera) { meshShader.use(gl3); meshShader.setMatrix4d(gl3, "viewMatrix", camera.getViewMatrix()); @@ -265,7 +268,7 @@ private List collectAllMeshes() { private void collAllMeshesRecursively(Node node, List meshMaterials, Material lastMaterialSeen) { if (node instanceof MeshInstance meshInstance) { - // if they have a mesh, draw it. + // if they have a mesh, collect it. Mesh mesh = meshInstance.getMesh(); if (mesh != null) { meshMaterials.add(new MeshMaterial(meshInstance,lastMaterialSeen)); @@ -413,7 +416,7 @@ private void updateLightMatrix() { // orthographic projection from the light's point of view double r = 50;//Math.max(50,camera.getOrbitRadius()); - lightProjection.set(MatrixHelper.orthographicMatrix4d(-r,r,-r,r,1.0,150)); + lightProjection.set(MatrixHelper.orthographicMatrix4d(-r,r,-r,r,1.0,DEPTH_BUFFER_LIMIT)); Vector3d from = new Vector3d(sunlightSource); Vector3d to = camera.getOrbitPoint(); @@ -421,10 +424,10 @@ private void updateLightMatrix() { Vector3d up = Math.abs(sunlightSource.z)>0.99? new Vector3d(0,1,0) : new Vector3d(0,0,1); // look at the scene from the light's point of view - // not the same as MatrixHelper.lookAt(). lightView.set(lookAt(from, to, up)); } + // not the same as MatrixHelper.lookAt(). This is for the light source. public static Matrix4d lookAt(Vector3d eye, Vector3d center, Vector3d up) { org.joml.Matrix4d jm = new org.joml.Matrix4d(); jm.lookAt(eye.x,eye.y,eye.z,center.x,center.y,center.z,up.x,up.y,up.z); @@ -502,7 +505,7 @@ private Vector3d calculateSunPosition() { vx.scale(Math.sin(hourAngle)); result.add(vx, vy); - result.scale(75); + result.scale(SUN_DISTANCE); return result; } From fc4bb2d9572aaa450b4a9005a6608b6d2df33625 Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 22 May 2024 13:38:26 -0700 Subject: [PATCH 47/52] defer to existing meshes --- .../ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java | 5 ++++- .../node/nodes/odenode/odebody/odebodies/ODECapsule.java | 5 ++++- .../node/nodes/odenode/odebody/odebodies/ODECylinder.java | 7 +++++-- .../node/nodes/odenode/odebody/odebodies/ODESphere.java | 5 ++++- 4 files changed, 17 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java index 3dc720390..bcebbcf21 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODEBox.java @@ -87,7 +87,10 @@ private void updateSize() { var meshInstance = findFirstChild(MeshInstance.class); if(meshInstance!=null) { - meshInstance.setMesh(new Box(size.x,size.y,size.z)); + var mesh = meshInstance.getMesh(); + if(mesh==null || mesh instanceof Box) { + meshInstance.setMesh(new Box(size.x, size.y, size.z)); + } } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java index 302154c42..0351f466d 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECapsule.java @@ -79,7 +79,10 @@ private void updateSize() { MeshInstance meshInstance = findFirstChild(MeshInstance.class); if(null != meshInstance) { - meshInstance.setMesh(new Capsule(length, radius)); + var mesh = meshInstance.getMesh(); + if(mesh==null || mesh instanceof Capsule) { + meshInstance.setMesh(new Capsule(length, radius)); + } } MeshInstance b1 = findNodeByPath("Ball1/MeshInstance",MeshInstance.class); diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java index 60a5c2593..906a89c80 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODECylinder.java @@ -76,8 +76,11 @@ private void updateSize() { body.setMass(mass); MeshInstance meshInstance = findFirstChild(MeshInstance.class); - if(meshInstance!=null) { - meshInstance.setMesh(new Cylinder(length, radius, radius)); + if(null != meshInstance) { + var mesh = meshInstance.getMesh(); + if(mesh==null || mesh instanceof Cylinder) { + meshInstance.setMesh(new Cylinder(length, radius, radius)); + } } } diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java index 33a00a9fe..b04f1420f 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/odebody/odebodies/ODESphere.java @@ -67,7 +67,10 @@ private void updateSize() { var meshInstance = findFirstChild(MeshInstance.class); if(meshInstance!=null) { - meshInstance.setMesh(new Sphere((float) radius)); + var mesh = meshInstance.getMesh(); + if(mesh==null || mesh instanceof Sphere) { + meshInstance.setMesh(new Sphere((float) radius)); + } } } From be0a5559e37a6b4b729dfc849d9f9bf26bdc366f Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 22 May 2024 13:38:45 -0700 Subject: [PATCH 48/52] test serializing top/bottom angles --- .../ro3/node/nodes/odenode/ODEHinge.java | 6 ++--- .../ro3/node/nodes/odenode/ODEHingeTest.java | 23 +++++++++++++++++++ 2 files changed, 25 insertions(+), 4 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java index d6c4fa363..efa692bd9 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHinge.java @@ -216,16 +216,14 @@ public void addTorque(double value) { * @return angle in degrees */ public double getAngleMax() { - if(hinge==null) return 0; - return Math.toDegrees(hinge.getParam(DJoint.PARAM_N.dParamHiStop1)); + return top; } /** * @return angle in degrees */ public double getAngleMin() { - if(hinge==null) return 0; - return Math.toDegrees(hinge.getParam(DJoint.PARAM_N.dParamLoStop1)); + return bottom; } /** diff --git a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingeTest.java b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingeTest.java index 4cb1b60bd..352903c5e 100644 --- a/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingeTest.java +++ b/src/test/java/com/marginallyclever/ro3/node/nodes/odenode/ODEHingeTest.java @@ -50,4 +50,27 @@ public void test() { Assertions.assertNotNull(afterHinge2.getHinge().getBody(0)); Assertions.assertNotNull(afterHinge2.getHinge().getBody(1)); } + + // test that serializing with infinite limits works, and with non-infinite limits works. + @Test + public void testLimits() { + Registry.start(); + + ODEHinge before = new ODEHinge(); + before.setAngleMax(Double.POSITIVE_INFINITY); + before.setAngleMin(Double.NEGATIVE_INFINITY); + JSONObject json = before.toJSON(); + ODEHinge after = new ODEHinge(); + after.fromJSON(json); + Assertions.assertEquals(Double.POSITIVE_INFINITY,after.getAngleMax()); + Assertions.assertEquals(Double.NEGATIVE_INFINITY,after.getAngleMin()); + + before.setAngleMax(90); + before.setAngleMin(-90); + json = before.toJSON(); + after = new ODEHinge(); + after.fromJSON(json); + Assertions.assertEquals(90,after.getAngleMax()); + Assertions.assertEquals(-90,after.getAngleMin()); + } } From 8dde150a972ad1666c3e48e4cbeb600770daf83e Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 22 May 2024 13:38:54 -0700 Subject: [PATCH 49/52] documentation --- .../marginallyclever/ro3/node/nodes/pose/poses/Limb.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Limb.java b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Limb.java index 89807197e..caf37a1bd 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Limb.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/pose/poses/Limb.java @@ -14,9 +14,9 @@ import java.util.Objects; /** - *

    {@link Limb} is a linear chain of bones, joints, and muscles. Bones are represented by {@link Pose}s. Joints are - * represented by {@link HingeJoint}s. Muscles are represented by {@link Motor}s. The end of the chain is a - * {@link Pose} called the end effector.

    + *

    {@link Limb} is a linear chain of bones driven by joints powered by muscles. Bones are represented by + * {@link Pose}s. Joints are represented by {@link HingeJoint}s. Muscles are represented by {@link Motor}s. + * The end of the chain - at the wrist - is a {@link Pose} called the end effector.

    *

    {@link Limb}s only perform Forward Kinematics - * given the angle of each joint, they calculate the world space position of the end effector. For more sophisticated * behavior, use a {@link LimbSolver}.

    From e00c5aa9ab25cf97621b7ff0e1b01dd64b9dd24d Mon Sep 17 00:00:00 2001 From: github-actions <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 22 May 2024 20:40:07 +0000 Subject: [PATCH 50/52] commit badge --- .github/badges/branches.svg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/badges/branches.svg b/.github/badges/branches.svg index f7364f18c..2b82098a8 100644 --- a/.github/badges/branches.svg +++ b/.github/badges/branches.svg @@ -1 +1 @@ -branches19.5% \ No newline at end of file +branches19.6% \ No newline at end of file From d0ebab53e48f93ffbd07dbe803c5bf6cb1f8beba Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Wed, 22 May 2024 13:59:21 -0700 Subject: [PATCH 51/52] 2.112.1 --- pom.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pom.xml b/pom.xml index 52f1b3928..17b05582b 100644 --- a/pom.xml +++ b/pom.xml @@ -6,7 +6,7 @@ com.marginallyclever RobotOverlord - 2.112.0 + 2.112.1 Robot Overlord A friendly 3D user interface for controlling robots. https://www.marginallyclever.com/ From f1efeb1798a7244956b610ba182d38205f8dd64a Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Tue, 4 Jun 2024 10:21:43 -0700 Subject: [PATCH 52/52] separated main menu from frame; fixed look and feel menu bar. --- pom.xml | 4 +- .../java/com/marginallyclever/ro3/RO3.java | 22 +++ .../marginallyclever/ro3/apps/MainMenu.java | 163 +++++++++++++++ .../marginallyclever/ro3/apps/RO3Frame.java | 186 +++--------------- .../ro3/FlatLightLaf.properties | 14 ++ 5 files changed, 225 insertions(+), 164 deletions(-) create mode 100644 src/main/java/com/marginallyclever/ro3/apps/MainMenu.java create mode 100644 src/main/resources/com/marginallyclever/ro3/FlatLightLaf.properties diff --git a/pom.xml b/pom.xml index 17b05582b..d6f968ef7 100644 --- a/pom.xml +++ b/pom.xml @@ -6,7 +6,7 @@ com.marginallyclever RobotOverlord - 2.112.1 + 2.113.0 Robot Overlord A friendly 3D user interface for controlling robots. https://www.marginallyclever.com/ @@ -530,6 +530,7 @@ 0.3.12 + io.github.andrewauclair modern-docking-api @@ -545,6 +546,7 @@ modern-docking-ui 0.11.1 + com.formdev diff --git a/src/main/java/com/marginallyclever/ro3/RO3.java b/src/main/java/com/marginallyclever/ro3/RO3.java index d1f09af12..f36e01ee8 100644 --- a/src/main/java/com/marginallyclever/ro3/RO3.java +++ b/src/main/java/com/marginallyclever/ro3/RO3.java @@ -1,5 +1,7 @@ package com.marginallyclever.ro3; +import com.formdev.flatlaf.FlatLaf; +import com.formdev.flatlaf.FlatLightLaf; import com.marginallyclever.ro3.apps.RO3Frame; import javax.swing.*; @@ -10,11 +12,31 @@ * You can find the friendly user manual at mcr.dozuki.com. */ public class RO3 { + private static final org.slf4j.Logger logger = org.slf4j.LoggerFactory.getLogger(RO3.class); + public static void main(String[] args) { Registry.start(); + setLookAndFeel(); if(!GraphicsEnvironment.isHeadless()) { SwingUtilities.invokeLater(() -> (new RO3Frame()).setVisible(true)); } } + + private static void setLookAndFeel() { + logger.info("Setting look and feel..."); + FlatLaf.registerCustomDefaultsSource( "com.marginallyclever.ro3" ); + //FlatLaf.registerCustomDefaultsSource("docking"); + try { + UIManager.setLookAndFeel(new FlatLightLaf()); + // option 2: UIManager.setLookAndFeel(new FlatDarkLaf()); + } catch (Exception ignored) { + logger.warn("failed to set flat look and feel. falling back to default native look and feel"); + try { + UIManager.setLookAndFeel(UIManager.getSystemLookAndFeelClassName()); + } catch (Exception ex) { + logger.warn("failed to set native look and feel.", ex); + } + } + } } diff --git a/src/main/java/com/marginallyclever/ro3/apps/MainMenu.java b/src/main/java/com/marginallyclever/ro3/apps/MainMenu.java new file mode 100644 index 000000000..d86eddb50 --- /dev/null +++ b/src/main/java/com/marginallyclever/ro3/apps/MainMenu.java @@ -0,0 +1,163 @@ +package com.marginallyclever.ro3.apps; + +import ModernDocking.app.DockableMenuItem; +import com.marginallyclever.ro3.apps.actions.*; +import com.marginallyclever.ro3.apps.dialogs.AppSettingsDialog; +import com.marginallyclever.ro3.apps.shared.PersistentJFileChooser; + +import javax.swing.*; +import java.awt.*; +import java.awt.event.InputEvent; +import java.awt.event.KeyEvent; +import java.awt.event.WindowEvent; +import java.util.List; +import java.util.Locale; +import java.util.Objects; +import java.util.prefs.Preferences; + +public class MainMenu extends JMenuBar { + private final RO3Frame frame; + private final JFileChooser fileChooser; + private boolean isMacOS = false; + private int SHORTCUT_CTRL = InputEvent.CTRL_DOWN_MASK; + private int SHORTCUT_ALT = InputEvent.ALT_DOWN_MASK; + + public MainMenu(RO3Frame frame) { + super(); + this.frame = frame; + + fileChooser = new PersistentJFileChooser(); + fileChooser.setFileFilter(RO3Frame.FILE_FILTER); + + setSystemLookAndFeelForMacos(); + add(buildFileMenu()); + add(buildEditMenu()); + add(buildWindowsMenu()); + add(buildHelpMenu()); + updateUI(); + } + + private void setSystemLookAndFeelForMacos() { + String os = System.getProperty("os.name").toLowerCase(Locale.ENGLISH); + if ((os.contains("mac")) || (os.contains("darwin"))) { + isMacOS=true; + System.setProperty("apple.laf.useScreenMenuBar", "true"); + SHORTCUT_CTRL = InputEvent.META_DOWN_MASK; + SHORTCUT_ALT = InputEvent.META_DOWN_MASK; + } + } + + private JMenu buildFileMenu() { + // "load", "load recent", and "new" enable/disable save. + var loadRecentMenu = new RecentFilesMenu(Preferences.userNodeForPackage(LoadScene.class)); + var save = new SaveScene(loadRecentMenu); + save.setEnabled(false); + var load = new LoadScene(loadRecentMenu,null,fileChooser); + load.setSaveScene(save); + loadRecentMenu.setSaveScene(save); + var saveAs = new SaveAsScene(loadRecentMenu,fileChooser); + saveAs.setSaveScene(save); + + JMenu menuFile = new JMenu("File"); + menuFile.add(new JMenuItem(new NewScene(save))); + menuFile.add(new JSeparator()); + menuFile.add(new JMenuItem(load)); + menuFile.add(loadRecentMenu); + menuFile.add(new JMenuItem(new ImportScene(fileChooser))); + menuFile.add(new JMenuItem(save)); + menuFile.add(new JMenuItem(saveAs)); + menuFile.add(new JMenuItem(new ExportScene(fileChooser))); + + menuFile.add(new JSeparator()); + var settingsMenu = new JMenuItem("Settings"); + settingsMenu.setIcon(new ImageIcon(Objects.requireNonNull(getClass().getResource( + "/com/marginallyclever/ro3/apps/actions/icons8-settings-16.png")))); + menuFile.add(settingsMenu); + + settingsMenu.addActionListener( e -> frame.runAppSettingsDialog() ); + + if(!isMacOS) { + menuFile.add(new JSeparator()); + menuFile.add(new JMenuItem(new AbstractAction("Quit") { + { + putValue(Action.NAME, "Quit"); + putValue(Action.ACCELERATOR_KEY, KeyStroke.getKeyStroke(KeyEvent.VK_Q, SHORTCUT_CTRL)); + putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-stop-16.png")))); + putValue(Action.SHORT_DESCRIPTION, "Quit the application."); + } + + @Override + public void actionPerformed(java.awt.event.ActionEvent e) { + if (frame.confirmClose()) { + frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); + frame.dispatchEvent(new WindowEvent(frame, WindowEvent.WINDOW_CLOSING)); + } + } + })); + } + + return menuFile; + } + + private JMenu buildWindowsMenu() { + JMenu menuWindows = new JMenu("Windows"); + // add each panel to the windows menu with a checkbox if the current panel is visible. + int index=0; + for(DockingPanel w : frame.getDockingPanels()) { + DockableMenuItem item = new DockableMenuItem(w.getPersistentID(),w.getTabText()); + menuWindows.add(item); + item.setAccelerator(KeyStroke.getKeyStroke(KeyEvent.VK_F1 + index, InputEvent.SHIFT_DOWN_MASK)); + index++; + } + + menuWindows.add(new JSeparator()); + menuWindows.add(new JMenuItem(new AbstractAction() { + { + putValue(Action.NAME, "Reset default layout"); + // no accelerator key. + putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-reset-16.png")))); + putValue(Action.SHORT_DESCRIPTION, "Reset the layout to the default."); + } + + @Override + public void actionPerformed(java.awt.event.ActionEvent e) { + frame.resetDefaultLayout(); + } + })); + return menuWindows; + } + + private Component buildEditMenu() { + JMenu menu = new JMenu("Edit"); + menu.add(new JMenuItem(UndoSystem.getCommandUndo())); + menu.add(new JMenuItem(UndoSystem.getCommandRedo())); + //menu.add(new JSeparator()); + return menu; + } + + private Component buildHelpMenu() { + JMenu menuHelp = new JMenu("Help"); + var openManual = new BrowseURLAction("https://mcr.dozuki.com/c/Robot_Overlord_3"); + openManual.putValue(Action.NAME, "Read the friendly manual"); + openManual.putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-open-book-16.png")))); + openManual.putValue(Action.SHORT_DESCRIPTION, "Read the friendly manual. It has pictures and everything!"); + menuHelp.add(new JMenuItem(openManual)); + + var visitForum = new BrowseURLAction("https://discord.gg/VQ82jNvDBP"); + visitForum.putValue(Action.NAME, "Visit Forums"); + visitForum.putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-discord-16.png")))); + visitForum.putValue(Action.SHORT_DESCRIPTION, "Join us on Discord!"); + menuHelp.add(new JMenuItem(visitForum)); + + var visitIssues = new BrowseURLAction("https://github.com/MarginallyClever/Robot-Overlord-App/issues"); + visitIssues.putValue(Action.NAME, "Report an Issue"); + visitIssues.putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-bug-16.png")))); + visitIssues.putValue(Action.SHORT_DESCRIPTION, "Report an issue on GitHub"); + menuHelp.add(new JMenuItem(visitIssues)); + + menuHelp.add(new JMenuItem(new CheckForUpdateAction())); + + return menuHelp; + } + +} diff --git a/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java b/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java index c011dff3b..391dc60b7 100644 --- a/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java +++ b/src/main/java/com/marginallyclever/ro3/apps/RO3Frame.java @@ -2,7 +2,6 @@ import ModernDocking.DockingRegion; import ModernDocking.app.AppState; -import ModernDocking.app.DockableMenuItem; import ModernDocking.app.Docking; import ModernDocking.app.RootDockingPanel; import ModernDocking.exception.DockingLayoutException; @@ -13,14 +12,12 @@ import com.marginallyclever.convenience.helpers.FileHelper; import com.marginallyclever.ro3.RO3; import com.marginallyclever.ro3.apps.about.AboutPanel; -import com.marginallyclever.ro3.apps.actions.*; import com.marginallyclever.ro3.apps.dialogs.AppSettingsDialog; import com.marginallyclever.ro3.apps.editorpanel.EditorPanel; import com.marginallyclever.ro3.apps.logpanel.LogPanel; import com.marginallyclever.ro3.apps.nodedetailview.NodeDetailView; import com.marginallyclever.ro3.apps.nodetreeview.NodeTreeView; import com.marginallyclever.ro3.apps.ode4j.ODE4JPanel; -import com.marginallyclever.ro3.apps.shared.PersistentJFileChooser; import com.marginallyclever.ro3.apps.webcampanel.WebCamPanel; import com.marginallyclever.ro3.apps.viewport.OpenGLPanel; import com.marginallyclever.ro3.apps.viewport.Viewport; @@ -28,21 +25,16 @@ import org.slf4j.LoggerFactory; import java.awt.dnd.DropTarget; -import java.awt.event.InputEvent; -import java.awt.event.KeyEvent; import java.io.File; import java.io.IOException; import java.io.InputStream; -import java.util.List; -import java.util.ArrayList; +import java.util.*; import javax.swing.*; import javax.swing.filechooser.FileNameExtensionFilter; import java.awt.*; import java.awt.event.WindowAdapter; import java.awt.event.WindowEvent; -import java.util.Objects; -import java.util.Properties; -import java.util.prefs.Preferences; +import java.util.List; /** *

    {@link RO3Frame} is the main frame for the Robot Overlord 3 application. It contains the menu bar and docking @@ -51,7 +43,6 @@ public class RO3Frame extends JFrame { private static final Logger logger = LoggerFactory.getLogger(RO3Frame.class); private final List windows = new ArrayList<>(); - private final JFileChooser fileChooser; private final OpenGLPanel viewportPanel; private final LogPanel logPanel; private final EditorPanel editPanel; @@ -64,13 +55,10 @@ public class RO3Frame extends JFrame { public RO3Frame() { super("Robot Overlord 3"); loadVersion(); - setLookAndFeel(); + setLocationByPlatform(true); initDocking(); - fileChooser = new PersistentJFileChooser(); - setupFileChooser(); - logPanel = new LogPanel(); editPanel = new EditorPanel(); viewportPanel = new Viewport(); @@ -84,7 +72,8 @@ public RO3Frame() { UndoSystem.start(); - createMenus(); + setJMenuBar(new MainMenu(this)); + addQuitHandler(); addAboutHandler(); setupDropTarget(); @@ -105,21 +94,6 @@ private void setupDropTarget() { new DropTarget(this, new RO3FrameDropTarget()); } - private void setupFileChooser() { - fileChooser.setFileFilter(FILE_FILTER); - } - - private void setLookAndFeel() { - FlatLaf.registerCustomDefaultsSource("docking"); - try { - UIManager.setLookAndFeel(new FlatLightLaf()); - // option 2: UIManager.setLookAndFeel(new FlatDarkLaf()); - // option 3: UIManager.setLookAndFeel(UIManager.getSystemLookAndFeelClassName()); - } catch (Exception ignored) { - logger.error("Failed to set look and feel."); - } - } - private void initDocking() { Docking.initialize(this); DockingUI.initialize(); @@ -162,7 +136,7 @@ private void addAboutHandler() { if (Desktop.isDesktopSupported()) { Desktop desktop = Desktop.getDesktop(); if (desktop.isSupported(Desktop.Action.APP_ABOUT)) { - desktop.setAboutHandler((e) ->{ + desktop.setAboutHandler((e) -> { var panel = new AboutPanel(); JOptionPane.showMessageDialog(this, panel, "About", @@ -172,136 +146,6 @@ private void addAboutHandler() { } } - private void createMenus() { - JMenuBar menuBar = new JMenuBar(); - setJMenuBar(menuBar); - - menuBar.add(buildFileMenu()); - menuBar.add(buildEditMenu()); - menuBar.add(buildWindowsMenu()); - menuBar.add(buildHelpMenu()); - } - - private Component buildEditMenu() { - JMenu menu = new JMenu("Edit"); - menu.add(new JMenuItem(UndoSystem.getCommandUndo())); - menu.add(new JMenuItem(UndoSystem.getCommandRedo())); - //menu.add(new JSeparator()); - return menu; - } - - private Component buildHelpMenu() { - JMenu menuHelp = new JMenu("Help"); - var openManual = new BrowseURLAction("https://mcr.dozuki.com/c/Robot_Overlord_3"); - openManual.putValue(Action.NAME, "Read the friendly manual"); - openManual.putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-open-book-16.png")))); - openManual.putValue(Action.SHORT_DESCRIPTION, "Read the friendly manual. It has pictures and everything!"); - menuHelp.add(new JMenuItem(openManual)); - - var visitForum = new BrowseURLAction("https://discord.gg/VQ82jNvDBP"); - visitForum.putValue(Action.NAME, "Visit Forums"); - visitForum.putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-discord-16.png")))); - visitForum.putValue(Action.SHORT_DESCRIPTION, "Join us on Discord!"); - menuHelp.add(new JMenuItem(visitForum)); - - var visitIssues = new BrowseURLAction("https://github.com/MarginallyClever/Robot-Overlord-App/issues"); - visitIssues.putValue(Action.NAME, "Report an Issue"); - visitIssues.putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-bug-16.png")))); - visitIssues.putValue(Action.SHORT_DESCRIPTION, "Report an issue on GitHub"); - menuHelp.add(new JMenuItem(visitIssues)); - - menuHelp.add(new JMenuItem(new CheckForUpdateAction())); - - return menuHelp; - } - - private JMenu buildWindowsMenu() { - JMenu menuWindows = new JMenu("Windows"); - // add each panel to the windows menu with a checkbox if the current panel is visible. - int index=0; - for(DockingPanel w : windows) { - DockableMenuItem item = new DockableMenuItem(w.getPersistentID(),w.getTabText()); - menuWindows.add(item); - item.setAccelerator(KeyStroke.getKeyStroke(KeyEvent.VK_F1 + index, InputEvent.SHIFT_DOWN_MASK)); - index++; - } - - menuWindows.add(new JSeparator()); - menuWindows.add(new JMenuItem(new AbstractAction() { - { - putValue(Action.NAME, "Reset default layout"); - // no accelerator key. - putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-reset-16.png")))); - putValue(Action.SHORT_DESCRIPTION, "Reset the layout to the default."); - } - - @Override - public void actionPerformed(java.awt.event.ActionEvent e) { - resetDefaultLayout(); - } - })); - return menuWindows; - } - - private JMenu buildFileMenu() { - // "load", "load recent", and "new" enable/disable save. - var loadRecentMenu = new RecentFilesMenu(Preferences.userNodeForPackage(LoadScene.class)); - var save = new SaveScene(loadRecentMenu); - save.setEnabled(false); - var load = new LoadScene(loadRecentMenu,null,fileChooser); - load.setSaveScene(save); - loadRecentMenu.setSaveScene(save); - var saveAs = new SaveAsScene(loadRecentMenu,fileChooser); - saveAs.setSaveScene(save); - - JMenu menuFile = new JMenu("File"); - menuFile.add(new JMenuItem(new NewScene(save))); - menuFile.add(new JSeparator()); - menuFile.add(new JMenuItem(load)); - menuFile.add(loadRecentMenu); - menuFile.add(new JMenuItem(new ImportScene(fileChooser))); - menuFile.add(new JMenuItem(save)); - menuFile.add(new JMenuItem(saveAs)); - menuFile.add(new JMenuItem(new ExportScene(fileChooser))); - - menuFile.add(new JSeparator()); - var settingsMenu = new JMenuItem("Settings"); - settingsMenu.setIcon(new ImageIcon(Objects.requireNonNull(getClass().getResource( - "/com/marginallyclever/ro3/apps/actions/icons8-settings-16.png")))); - menuFile.add(settingsMenu); - settingsMenu.addActionListener(e -> { - var dialog = new AppSettingsDialog(List.of( - viewportPanel, - logPanel, - editPanel, - webCamPanel, - textInterface, - ode4jPanel - )); - dialog.run(this); - }); - - - menuFile.add(new JSeparator()); - menuFile.add(new JMenuItem(new AbstractAction("Quit") { - { - putValue(Action.NAME, "Quit"); - putValue(Action.ACCELERATOR_KEY, KeyStroke.getKeyStroke(KeyEvent.VK_Q, InputEvent.CTRL_DOWN_MASK)); - putValue(Action.SMALL_ICON, new ImageIcon(Objects.requireNonNull(getClass().getResource("icons8-stop-16.png")))); - putValue(Action.SHORT_DESCRIPTION, "Quit the application."); - } - @Override - public void actionPerformed(java.awt.event.ActionEvent e) { - if(confirmClose()) { - setDefaultCloseOperation(EXIT_ON_CLOSE); - RO3Frame.this.dispatchEvent(new WindowEvent(RO3Frame.this, WindowEvent.WINDOW_CLOSING)); - } - } - })); - - return menuFile; - } - public boolean confirmClose() { int result = JOptionPane.showConfirmDialog(this, "Are you sure you want to quit?", "Quit", JOptionPane.YES_NO_OPTION); if (result == JOptionPane.YES_OPTION) { @@ -362,7 +206,7 @@ private void createDefaultLayout() { /** * Reset the default layout. These depend on the order of creation in createDefaultLayout(). */ - private void resetDefaultLayout() { + public void resetDefaultLayout() { logger.info("Resetting layout to default."); setSize(1000, 750); @@ -394,4 +238,20 @@ private void saveAndRestoreLayout() { logger.error("Failed to restore docking layout.", e); } } + + public List getDockingPanels() { + return windows; + } + + public void runAppSettingsDialog() { + var dialog = new AppSettingsDialog(List.of( + viewportPanel, + logPanel, + editPanel, + webCamPanel, + textInterface, + ode4jPanel + )); + dialog.run(this); + } } diff --git a/src/main/resources/com/marginallyclever/ro3/FlatLightLaf.properties b/src/main/resources/com/marginallyclever/ro3/FlatLightLaf.properties new file mode 100644 index 000000000..f8a787e0a --- /dev/null +++ b/src/main/resources/com/marginallyclever/ro3/FlatLightLaf.properties @@ -0,0 +1,14 @@ +Component.arrowType = triangle +ScrollBar.showButtons = false +ScrollBar.thumbInsets = 2,2,2,2 +ScrollBar.thumbArc = 999 +TabbedPane.selectedBackground = #fff +ScrollBar.width = 14 +Panel.arc = 10 +Button.arc = 10 +Button.margin = 3, 4, 3, 4 +Component.arc = 10 +TextComponent.arc = 10 +ProgressBar.arc = 10 +Component.focusWidth = 2 +defaultFont = 12 \ No newline at end of file