diff --git a/src/main/java/com/marginallyclever/ro3/node/nodes/Camera.java b/src/main/java/com/marginallyclever/ro3/node/nodes/Camera.java index f53479114..b4855c319 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodes/Camera.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodes/Camera.java @@ -177,6 +177,45 @@ private void translate(Vector3d direction,double delta) { this.setLocal(local); } + /** + * Rotate relative to camera's current orientation + * TODO test + * @param delta degrees to rotate. Positive is left. + */ + public void pan(double delta) { + rotate(MatrixHelper.getYAxis(this.getLocal()),delta); + } + + /** + * Rotate relative to camera's current orientation + * TODO test + * @param delta degrees to rotate. Positive is up. + */ + public void tilt(double delta) { + rotate(MatrixHelper.getXAxis(this.getLocal()),delta); + } + + /** + * Rotate relative to camera's current orientation + * TODO test + * @param delta degrees to rotate. Positive is counter-clockwise. + */ + public void roll(double delta) { + rotate(MatrixHelper.getZAxis(this.getLocal()),delta); + } + + /** + * Rotate relative to camera's current orientation + * @param axis axis to rotate around + * @param delta degrees to rotate. Positive is clockwise. + */ + private void rotate(Vector3d axis,double delta) { + Matrix3d m = MatrixHelper.getMatrixFromAxisAndRotation(axis,delta); + Matrix4d m4 = new Matrix4d(); + m4.set(m); + getLocal().mul(m4); + } + /** * Set the pan and tilt values such that the camera is looking at the target. * Set the orbit distance to the distance between the camera and the target. diff --git a/src/main/java/com/marginallyclever/ro3/node/nodetreeview/NodeTreeTransferHandler.java b/src/main/java/com/marginallyclever/ro3/node/nodetreeview/NodeTreeTransferHandler.java index 18fc75408..97b295e7c 100644 --- a/src/main/java/com/marginallyclever/ro3/node/nodetreeview/NodeTreeTransferHandler.java +++ b/src/main/java/com/marginallyclever/ro3/node/nodetreeview/NodeTreeTransferHandler.java @@ -34,11 +34,8 @@ protected Transferable createTransferable(JComponent c) { @Override public boolean canImport(TransferHandler.TransferSupport support) { - if (!support.isDrop() || !support.isDataFlavorSupported(NodeTransferable.nodeFlavor)) { - return false; - } + return support.isDrop() && support.isDataFlavorSupported(NodeTransferable.nodeFlavor); // Additional checks can be added here if needed - return true; } @Override diff --git a/src/main/java/com/marginallyclever/ro3/render/Viewport.java b/src/main/java/com/marginallyclever/ro3/render/Viewport.java index 01e9406a8..c5640cfca 100644 --- a/src/main/java/com/marginallyclever/ro3/render/Viewport.java +++ b/src/main/java/com/marginallyclever/ro3/render/Viewport.java @@ -4,7 +4,6 @@ import com.jogamp.opengl.GLEventListener; import com.marginallyclever.convenience.helpers.MatrixHelper; import com.marginallyclever.ro3.Registry; -import com.marginallyclever.ro3.node.Node; import com.marginallyclever.ro3.node.nodes.Camera; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -31,6 +30,8 @@ public class Viewport extends OpenGLPanel implements GLEventListener { private final JPopupMenu renderPassMenu = new JPopupMenu(); private final List buttonPressed = new ArrayList<>(); private int mx, my; + private double orbitRadius = 100; + private final double orbitChangeFactor = 1.1; // must always be greater than 1 public Viewport() { @@ -222,12 +223,23 @@ public void mouseDragged(MouseEvent e) { int dy = py - my; my = py; - if(buttonPressed.get(MouseEvent.BUTTON1)) {} + boolean shift = (e.getModifiersEx() & MouseEvent.SHIFT_DOWN_MASK) != 0; + + //if(buttonPressed.get(MouseEvent.BUTTON1)) {} if(buttonPressed.get(MouseEvent.BUTTON2)) { // middle button - panTiltCamera(dx,dy); + if(!shift) { + panTiltCamera(dx, dy); + } else { + camera.dolly(dy); + } } if(buttonPressed.get(MouseEvent.BUTTON3)) { // right button - moveCamera(dx,dy); + if(!shift) { + orbitCamera(dx,dy); + } else { + camera.truck(-dx); + camera.pedestal(dy); + } } } @@ -235,27 +247,76 @@ public void mouseDragged(MouseEvent e) { public void mouseWheelMoved(MouseWheelEvent e) { super.mouseWheelMoved(e); int dz = e.getWheelRotation(); + changeOrbitRadius(dz); + } + + /** + * Change the distance from the camera to the orbit point. The orbit point does not move. In effect the camera + * is performing a dolly in/out. + * @param dz mouse wheel movement + */ + private void changeOrbitRadius(int dz) { + Matrix4d local = camera.getLocal(); + Vector3d orbitPoint = getOrbitPoint(); + + orbitRadius = dz > 0 ? orbitRadius * orbitChangeFactor : orbitRadius / orbitChangeFactor; + orbitRadius = Math.max(1,orbitRadius); + //logger.debug("wheel "+dz + " orbitRadius=" + orbitRadius); + + Vector3d orbitVector = MatrixHelper.getZAxis(local); + orbitVector.scaleAdd(orbitRadius,orbitPoint); + local.setTranslation(orbitVector); } private void panTiltCamera(int dx, int dy) { Matrix4d local = camera.getLocal(); + Vector3d t = new Vector3d(); + local.get(t); double [] panTiltAngles = getPanTiltFromMatrix(local); panTiltAngles[0] = (panTiltAngles[0] + dx+360) % 360; panTiltAngles[1] = Math.max(0,Math.min(180,panTiltAngles[1] + dy)); Matrix3d panTilt = buildPanTiltMatrix(panTiltAngles); - Vector3d t = new Vector3d(); - local.get(t); local.set(panTilt); local.setTranslation(t); camera.setLocal(local); } - private void moveCamera(int dx,int dy) { - camera.truck(-dx); - camera.dolly(dy); + /** + * Orbit the camera around a point orbitRadius ahead of the camera. + * @param dx mouse movement in x + * @param dy mouse movement in y + */ + void orbitCamera(int dx,int dy) { + Matrix4d local = camera.getLocal(); + Vector3d orbitPoint = getOrbitPoint(); + //logger.debug("before {}",orbitPoint); + double [] panTiltAngles = getPanTiltFromMatrix(local); + panTiltAngles[0] = (panTiltAngles[0] + dx+360) % 360; + panTiltAngles[1] = Math.max(0,Math.min(180,panTiltAngles[1] + dy)); + Matrix3d panTilt = buildPanTiltMatrix(panTiltAngles); + Matrix4d newLocal = new Matrix4d(); + newLocal.set(panTilt); + Vector3d orbitVector = MatrixHelper.getZAxis(newLocal); + orbitVector.scaleAdd(orbitRadius,orbitPoint); + newLocal.setTranslation(orbitVector); + camera.setLocal(newLocal); + //logger.debug("after {}",getOrbitPoint()); + } + + /** + * @return the point that the camera is orbiting around. + */ + Vector3d getOrbitPoint() { + Matrix4d local = camera.getLocal(); + Vector3d position = MatrixHelper.getPosition(local); + // z axis points away from the direction the camera is facing. + Vector3d zAxis = MatrixHelper.getZAxis(local); + zAxis.scale(-orbitRadius); + position.add(zAxis); + return position; } - public double[] getPanTiltFromMatrix(Matrix4d matrix) { + double[] getPanTiltFromMatrix(Matrix4d matrix) { Vector3d v = MatrixHelper.matrixToEuler(matrix); double pan = Math.toDegrees(-v.z); double tilt = Math.toDegrees(v.x); @@ -266,7 +327,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. */ - public Matrix3d buildPanTiltMatrix(double [] panTiltAngles) { + Matrix3d buildPanTiltMatrix(double [] panTiltAngles) { Matrix3d a = new Matrix3d(); a.rotZ(Math.toRadians(panTiltAngles[0])); diff --git a/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawBackground.java b/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawBackground.java index e2737b096..6331a5d94 100644 --- a/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawBackground.java +++ b/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawBackground.java @@ -147,7 +147,6 @@ public void draw() { Camera camera = Registry.getActiveCamera(); if (camera == null) { gl3.glClear(GL3.GL_COLOR_BUFFER_BIT | GL3.GL_DEPTH_BUFFER_BIT | GL.GL_STENCIL_BUFFER_BIT); - return; } else { gl3.glClear(GL3.GL_DEPTH_BUFFER_BIT | GL.GL_STENCIL_BUFFER_BIT); gl3.glDisable(GL3.GL_DEPTH_TEST); diff --git a/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawHingeJoints.java b/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawHingeJoints.java index 5b5cf54db..fcd08a936 100644 --- a/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawHingeJoints.java +++ b/src/main/java/com/marginallyclever/ro3/render/renderpasses/DrawHingeJoints.java @@ -28,7 +28,7 @@ public class DrawHingeJoints implements RenderPass { private final Mesh circleFan = new Mesh(); private ShaderProgram shader; private int canvasWidth,canvasHeight; - private float ringScale = 3; + private final float ringScale = 3; public DrawHingeJoints() { super();