btGeneric6DofConstraint as a motor

clusher
Posts: 1
Joined: Thu May 31, 2012 4:38 pm

btGeneric6DofConstraint as a motor

Post by clusher »

Hello everyone,

I have been bashing my head around this problem for over a month. I am trying to make a simple simulator to model a robotic leg, using a python implementation of bullet (python-ogre, to be precise). This has been really hard, because the documentation of bullet is not very self-explanatory and the python version is even worse.

In an effort to understand how the btRotationalLimitMotor works I created a simulation with a fixed body connected to a movable body through a btGeneric6DofConstraint. I lock all Dofs except for rotation around X. When I start the simulation, the body rotates around the x axis, by action of gravity. But I can't get it to move to a position I want. The m_enableMotor is set to True and the limits are set for +pi/2 to -pi/2.

I tried changing the m_maxMotorForce, m_maxLimitForce, m_targetVelocity, but I get no controlled movement. This is probably because I don't understand how Bullet controls the motor. Can someone please explain this or is there some demo I can try? I tried searching in the forum and in the documentation, but I must be missing something simple...

Thanks
2entysix
Posts: 1
Joined: Tue Jun 05, 2012 1:09 am

Re: btGeneric6DofConstraint as a motor

Post by 2entysix »

I've been having this exact same issue except using jbullet instead of python-ogre.

Having dug through these forums I've seen a lot of posts recommending the use of Generic6DofConstraints due to their versatility, yet there is a distinct lack of tutorials, examples, or really any documentation on using the RotationalLimitMotor and TranslationalLimitMotor structures that the 6dof constraints provide. Currently all I can find is the API documentation which only has a few sparse two to three word comments.

Similar to clusher I have two rigid bodies connected by a 6dof constraint that is free on one axis. I've tried just about every possible variation of values for the targetVelocity, MaxLimitForce, maxMotorForce, and hi/loLimit values. I have ensured that enableMotor is set to true. Regardless, I fail to see any motion outside of gravity (which is set to a light -10).

If anyone could shed some light on this, whether it be an example, a demo, or an explanation of how these motors are supposed to be used, it would be immensely helpful.
quzox
Posts: 7
Joined: Wed Aug 01, 2012 9:08 pm

Re: btGeneric6DofConstraint as a motor

Post by quzox »

Haven't tried to make a 6dof move with an angular motor but have had some success with the hinge constraint, and given that you only need to rotate around a single axis for the robot leg then a hinge constraint will work. You can even set limits on how far the rotation should be allowed.

Actually you could try and hack movement with the 6dof by setting the upper and lower limits for the axis in question, on every frame.
cmeyer
Posts: 4
Joined: Tue Aug 14, 2012 9:24 pm

Re: btGeneric6DofConstraint as a motor

Post by cmeyer »

I am trying to use the btGeneric6DofConstraint with its motors too. Limits and rotational motors are working for me (haven't tried the translational ones). Basically all I did was setting maxMotorForce to 1, enabled the motor and set angularSleepingThreshold to 0 for the rigid body that is moved by the joint. The last step is necessary to prevent bullet from deactivating the body when moving slowly. It will not be reactivated by motor force.

My aim is to move a ragdoll using proportional-derivative control for physics-based animation. But I don't really understand how the motors are moving the connected rigid body exactly. I am unable to synchronize the joint with an unsimulated 3D object. For example I cannot freely rotate around the Y-axis although there are no limits active. I would really love to learn more about motor control and see a few examples. The demos are not really helping me because there is none using btGeneric6DofConstraint.

Here is some example java code. I am using bullet via jmonkeyengine (http://jmonkeyengine.org/).

Code: Select all

package com.jme3test.motor;

import java.util.logging.Logger;

import jme3test.bullet.PhysicsTestHelper;

import com.jme3.app.SimpleApplication;
import com.jme3.bullet.BulletAppState;
import com.jme3.bullet.collision.shapes.BoxCollisionShape;
import com.jme3.bullet.control.RigidBodyControl;
import com.jme3.bullet.joints.SixDofJoint;
import com.jme3.bullet.joints.motors.RotationalLimitMotor;
import com.jme3.input.KeyInput;
import com.jme3.input.controls.ActionListener;
import com.jme3.input.controls.KeyTrigger;
import com.jme3.material.Material;
import com.jme3.math.ColorRGBA;
import com.jme3.math.Quaternion;
import com.jme3.math.Vector3f;
import com.jme3.scene.Geometry;
import com.jme3.scene.Node;
import com.jme3.scene.debug.Arrow;

/**
 * Joint vs. spatial rotational behaviour.<p>
 * I/K: desired pitch velocity<br>
 * U/O: desired yaw velocity<br>
 * J/L: desired roll velocity<br>
 * R: reset desired orientation<br>
 * SPACE: enable/disable motor control<p>
 * Pink arrow: spatial<br>
 * Green arrow: joint<br>
 * Blue box: weight node<p>
 * @author cmeyer
 *
 */
public class TestRotationalMotor extends SimpleApplication implements ActionListener {
    private static final Logger logger =
            Logger.getLogger(TestRotationalMotor.class.getName());

    protected BulletAppState bulletAppState;
    protected Geometry arrow;
    
    // current velocity for every axis
    protected float desiredPitchVelocity = 0;
    protected float desiredYawVelocity = 0;
    protected float desiredRollVelocity = 0;

    protected boolean motorEnabled = true;
    
    protected SixDofJoint joint;
    protected RotationalLimitMotor pitchMotor;
    protected RotationalLimitMotor yawMotor;
    protected RotationalLimitMotor rollMotor;
    
    /**
     * Initialization
     */
    @Override
    public void simpleInitApp() {
        // create the bullet state for physics simulation
        bulletAppState = new BulletAppState();
        stateManager.attach(bulletAppState);
        bulletAppState.getPhysicsSpace().enableDebug(assetManager);
        
        setupKeys();
        setupJoint();
        setupArrows();
    }

    /**
     * Key bindings
     */
    private void setupKeys() {
        inputManager.addMapping("PitchPlus", new KeyTrigger(KeyInput.KEY_I));
        inputManager.addMapping("PitchMinus", new KeyTrigger(KeyInput.KEY_K));
        inputManager.addMapping("YawPlus", new KeyTrigger(KeyInput.KEY_O));
        inputManager.addMapping("YawMinus", new KeyTrigger(KeyInput.KEY_U));
        inputManager.addMapping("RollPlus", new KeyTrigger(KeyInput.KEY_L));
        inputManager.addMapping("RollMinus", new KeyTrigger(KeyInput.KEY_J));
        inputManager.addMapping("Reset", new KeyTrigger(KeyInput.KEY_R));
        inputManager.addMapping("toggleEnableMotors", new KeyTrigger(
                KeyInput.KEY_SPACE));
        inputManager.addListener(this, "RollMinus", "RollPlus", "PitchMinus", "PitchPlus", "YawMinus", "YawPlus", "Reset", "toggleEnableMotors");
    }

    /**
     * Create the joint and weight node.
     */
    private void setupJoint() {
        // Static nodes have zero mass
        Node holderNode =
                PhysicsTestHelper.createPhysicsTestNode(assetManager,
                        new BoxCollisionShape(new Vector3f(.1f, .1f, .1f)), 0);
        holderNode.getControl(RigidBodyControl.class).setPhysicsLocation(
                Vector3f.ZERO);
        rootNode.attachChild(holderNode);
        bulletAppState.getPhysicsSpace().add(holderNode);
    
        // dynamic node with mass of 1
        Node weightNode =
                PhysicsTestHelper.createPhysicsTestNode(assetManager,
                        new BoxCollisionShape(new Vector3f(.3f, .3f, .3f)), 1);
        RigidBodyControl weightNodeControl = weightNode.getControl(RigidBodyControl.class);
        weightNodeControl.setPhysicsLocation(
                new Vector3f(0f, 1, 0f));
        rootNode.attachChild(weightNode);
        bulletAppState.getPhysicsSpace().add(weightNode);
    
        // Joint with six degrees of freedom, we will only use 3 of them
        joint =
                new SixDofJoint(holderNode.getControl(RigidBodyControl.class),
                        weightNode.getControl(RigidBodyControl.class),
                        Vector3f.ZERO, new Vector3f(0f, -1, 0f), true);
        bulletAppState.getPhysicsSpace().add(joint);
        
        // fetch the reference for the rotational motors and enable them
        pitchMotor = joint.getRotationalLimitMotor(0);
        yawMotor = joint.getRotationalLimitMotor(1);
        rollMotor = joint.getRotationalLimitMotor(2);
        setEnableMotors(motorEnabled);
        
        // Default maxMotorForce is too weak to lift the weight node
        pitchMotor.setMaxMotorForce(1);
        yawMotor.setMaxMotorForce(1);
        rollMotor.setMaxMotorForce(1);
        
        // physics simulation puts objects to sleep when moving slower than
        // sleeping threshold. We do not want that.
        weightNodeControl.setAngularSleepingThreshold(0);
        weightNodeControl.setGravity(Vector3f.ZERO);
    }

    private void setupArrows() {
        Arrow desiredArrowMesh = new Arrow(Vector3f.UNIT_Y);
        arrow = new Geometry("arrow", desiredArrowMesh);
        
        Material pinkMat = new Material(assetManager, "Common/MatDefs/Misc/Unshaded.j3md");
        pinkMat.setColor("Color", ColorRGBA.Pink);
        arrow.setMaterial(pinkMat);
        
        rootNode.attachChild(arrow);
    }

    @Override
    public void onAction(String name, boolean isPressed, float tpf) {
        if (name.equals("PitchPlus") && isPressed) {
            desiredPitchVelocity += 1;
        }
        if (name.equals("PitchMinus") && isPressed) {
            desiredPitchVelocity -= 1;
        }
        if (name.equals("YawPlus") && isPressed) {
            desiredYawVelocity += 1;
        }
        if (name.equals("YawMinus") && isPressed) {
            desiredYawVelocity -= 1;
        }
        if (name.equals("RollPlus") && isPressed) {
            desiredRollVelocity += 1;
        }
        if (name.equals("RollMinus") && isPressed) {
            desiredRollVelocity -= 1;
        }
        if (name.equals("Reset") && isPressed) {
            desiredPitchVelocity = 0;
            desiredYawVelocity = 0;
            desiredRollVelocity = 0;
            arrow.setLocalRotation(new Quaternion());
            
            joint.getBodyB().clearForces();
            joint.getBodyB().setPhysicsLocation(Vector3f.UNIT_Y);
            joint.getBodyB().setPhysicsRotation(new Quaternion());
        }
        if (name.equals("toggleEnableMotors") && isPressed ) {
            setEnableMotors(!motorEnabled);
            logger.info("motorEnabled = " + motorEnabled);
        }
    }
    
    /**
     * Enable/disable all 3 motors.
     * @param enableMotors
     */
    private void setEnableMotors(boolean enableMotors) {
        motorEnabled = enableMotors;
        
        pitchMotor.setEnableMotor(enableMotors);
        yawMotor.setEnableMotor(enableMotors);
        rollMotor.setEnableMotor(enableMotors);
    }

    @Override
    public void simpleUpdate(float tpf) {
        // calculate rotation step for this frame from velocities
        Quaternion rotationStep = new Quaternion();
        rotationStep.multLocal(new Quaternion().fromAngleNormalAxis(-desiredYawVelocity * tpf, Vector3f.UNIT_Y));
        rotationStep.multLocal(new Quaternion().fromAngleNormalAxis(-desiredRollVelocity * tpf, Vector3f.UNIT_Z));
        rotationStep.multLocal(new Quaternion().fromAngleNormalAxis(-desiredPitchVelocity * tpf, Vector3f.UNIT_X));
        arrow.rotate(rotationStep);
        
        // set motors to desired velocity 
        yawMotor.setTargetVelocity(desiredYawVelocity);
        rollMotor.setTargetVelocity(desiredRollVelocity);
        pitchMotor.setTargetVelocity(desiredPitchVelocity);
    }
    
    /**
     * @param args
     */
    public static void main(String[] args) {
        TestRotationalMotor app = new TestRotationalMotor();
        app.start();
    }

}