Add joint limit example.
The demo artifically exceeds joint limit due to numerical errors caused by large ratio.
This commit is contained in:
112
examples/BulletRobotics/JointLimit.cpp
Normal file
112
examples/BulletRobotics/JointLimit.cpp
Normal file
@@ -0,0 +1,112 @@
|
|||||||
|
|
||||||
|
#include "JointLimit.h"
|
||||||
|
|
||||||
|
#include "../CommonInterfaces/CommonGraphicsAppInterface.h"
|
||||||
|
#include "Bullet3Common/b3AlignedObjectArray.h"
|
||||||
|
#include "../CommonInterfaces/CommonRenderInterface.h"
|
||||||
|
#include "../CommonInterfaces/CommonExampleInterface.h"
|
||||||
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
|
#include "../SharedMemory/PhysicsServerSharedMemory.h"
|
||||||
|
#include "../SharedMemory/PhysicsClientC_API.h"
|
||||||
|
#include "../SharedMemory/SharedMemoryPublic.h"
|
||||||
|
#include "../CommonInterfaces/CommonParameterInterface.h"
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include "../RobotSimulator/b3RobotSimulatorClientAPI.h"
|
||||||
|
#include "../Utils/b3Clock.h"
|
||||||
|
|
||||||
|
class JointLimit : public CommonExampleInterface
|
||||||
|
{
|
||||||
|
GUIHelperInterface* m_guiHelper;
|
||||||
|
b3RobotSimulatorClientAPI m_robotSim;
|
||||||
|
int m_options;
|
||||||
|
|
||||||
|
public:
|
||||||
|
JointLimit(GUIHelperInterface* helper, int options)
|
||||||
|
: m_guiHelper(helper),
|
||||||
|
m_options(options)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual ~JointLimit()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void physicsDebugDraw(int debugDrawMode)
|
||||||
|
{
|
||||||
|
m_robotSim.debugDraw(debugDrawMode);
|
||||||
|
}
|
||||||
|
virtual void initPhysics()
|
||||||
|
{
|
||||||
|
int mode = eCONNECT_EXISTING_EXAMPLE_BROWSER;
|
||||||
|
m_robotSim.setGuiHelper(m_guiHelper);
|
||||||
|
bool connected = m_robotSim.connect(mode);
|
||||||
|
|
||||||
|
b3Printf("robotSim connected = %d", connected);
|
||||||
|
|
||||||
|
m_robotSim.configureDebugVisualizer(COV_ENABLE_RGB_BUFFER_PREVIEW, 0);
|
||||||
|
m_robotSim.configureDebugVisualizer(COV_ENABLE_DEPTH_BUFFER_PREVIEW, 0);
|
||||||
|
m_robotSim.configureDebugVisualizer(COV_ENABLE_SEGMENTATION_MARK_PREVIEW, 0);
|
||||||
|
|
||||||
|
b3RobotSimulatorSetPhysicsEngineParameters physicsArgs;
|
||||||
|
physicsArgs.m_constraintSolverType = eConstraintSolverLCP_DANTZIG;
|
||||||
|
|
||||||
|
b3Printf(m_robotSim.getSolvername());
|
||||||
|
|
||||||
|
physicsArgs.m_defaultGlobalCFM = 1e-6;
|
||||||
|
|
||||||
|
m_robotSim.setNumSolverIterations(10);
|
||||||
|
|
||||||
|
|
||||||
|
b3RobotSimulatorLoadUrdfFileArgs loadArgs;
|
||||||
|
int humanoid = m_robotSim.loadURDF("test_joints_MB.urdf", loadArgs);
|
||||||
|
|
||||||
|
b3RobotSimulatorChangeDynamicsArgs dynamicsArgs;
|
||||||
|
dynamicsArgs.m_linearDamping = 0;
|
||||||
|
dynamicsArgs.m_angularDamping = 0;
|
||||||
|
m_robotSim.changeDynamics(humanoid, -1, dynamicsArgs);
|
||||||
|
|
||||||
|
m_robotSim.setGravity(btVector3(0, 0, -10));
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void exitPhysics()
|
||||||
|
{
|
||||||
|
m_robotSim.disconnect();
|
||||||
|
}
|
||||||
|
virtual void stepSimulation(float deltaTime)
|
||||||
|
{
|
||||||
|
m_robotSim.stepSimulation();
|
||||||
|
}
|
||||||
|
virtual void renderScene()
|
||||||
|
{
|
||||||
|
m_robotSim.renderScene();
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual bool mouseMoveCallback(float x, float y)
|
||||||
|
{
|
||||||
|
return m_robotSim.mouseMoveCallback(x, y);
|
||||||
|
}
|
||||||
|
virtual bool mouseButtonCallback(int button, int state, float x, float y)
|
||||||
|
{
|
||||||
|
return m_robotSim.mouseButtonCallback(button, state, x, y);
|
||||||
|
}
|
||||||
|
virtual bool keyboardCallback(int key, int state)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void resetCamera()
|
||||||
|
{
|
||||||
|
float dist = 3;
|
||||||
|
float pitch = -10;
|
||||||
|
float yaw = 18;
|
||||||
|
float targetPos[3] = {0.6, 0.8, 0.3};
|
||||||
|
|
||||||
|
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class CommonExampleInterface* JointLimitCreateFunc(struct CommonExampleOptions& options)
|
||||||
|
{
|
||||||
|
return new JointLimit(options.m_guiHelper, options.m_option);
|
||||||
|
}
|
||||||
21
examples/BulletRobotics/JointLimit.h
Normal file
21
examples/BulletRobotics/JointLimit.h
Normal file
@@ -0,0 +1,21 @@
|
|||||||
|
/*
|
||||||
|
Bullet Continuous Collision Detection and Physics Library
|
||||||
|
Copyright (c) 2016 Google Inc. http://bulletphysics.org
|
||||||
|
|
||||||
|
This software is provided 'as-is', without any express or implied warranty.
|
||||||
|
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||||
|
Permission is granted to anyone to use this software for any purpose,
|
||||||
|
including commercial applications, and to alter it and redistribute it freely,
|
||||||
|
subject to the following restrictions:
|
||||||
|
|
||||||
|
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||||
|
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||||
|
3. This notice may not be removed or altered from any source distribution.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef JOINT_LIMIT_EXAMPLE_H
|
||||||
|
#define JOINT_LIMIT_EXAMPLE_H
|
||||||
|
|
||||||
|
class CommonExampleInterface* JointLimitCreateFunc(struct CommonExampleOptions& options);
|
||||||
|
|
||||||
|
#endif //JOINT_LIMIT_EXAMPLE_H
|
||||||
@@ -147,6 +147,7 @@ SET(BulletExampleBrowser_SRCS
|
|||||||
../BulletRobotics/FixJointBoxes.cpp
|
../BulletRobotics/FixJointBoxes.cpp
|
||||||
|
|
||||||
../BulletRobotics/BoxStack.cpp
|
../BulletRobotics/BoxStack.cpp
|
||||||
|
../BulletRobotics/JointLimit.cpp
|
||||||
|
|
||||||
../TinyRenderer/geometry.cpp
|
../TinyRenderer/geometry.cpp
|
||||||
../TinyRenderer/model.cpp
|
../TinyRenderer/model.cpp
|
||||||
|
|||||||
@@ -3,7 +3,9 @@
|
|||||||
#include "../BlockSolver/BlockSolverExample.h"
|
#include "../BlockSolver/BlockSolverExample.h"
|
||||||
#include "LinearMath/btAlignedObjectArray.h"
|
#include "LinearMath/btAlignedObjectArray.h"
|
||||||
#include "EmptyExample.h"
|
#include "EmptyExample.h"
|
||||||
|
#include "../BulletRobotics/BoxStack.h"
|
||||||
#include "../BulletRobotics/FixJointBoxes.h"
|
#include "../BulletRobotics/FixJointBoxes.h"
|
||||||
|
#include "../BulletRobotics/JointLimit.h"
|
||||||
#include "../RenderingExamples/RenderInstancingDemo.h"
|
#include "../RenderingExamples/RenderInstancingDemo.h"
|
||||||
#include "../RenderingExamples/CoordinateSystemDemo.h"
|
#include "../RenderingExamples/CoordinateSystemDemo.h"
|
||||||
#include "../RenderingExamples/RaytracerSetup.h"
|
#include "../RenderingExamples/RaytracerSetup.h"
|
||||||
@@ -131,8 +133,8 @@ static ExampleEntry gDefaultExamples[] =
|
|||||||
ExampleEntry(1, "Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.", RigidBodySoftContactCreateFunc),
|
ExampleEntry(1, "Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.", RigidBodySoftContactCreateFunc),
|
||||||
|
|
||||||
ExampleEntry(0, "Bullet Robotics"),
|
ExampleEntry(0, "Bullet Robotics"),
|
||||||
ExampleEntry(1, "Box Stack", "Create a stack of boxes using C API", BoxStackExampleCreateFunc),
|
ExampleEntry(1, "Box Stack", "Create a stack of boxes of large mass ratio.", BoxStackExampleCreateFunc),
|
||||||
ExampleEntry(1, "FixJoint Boxes", "FixJoint Boxes", FixJointBoxesCreateFunc),
|
ExampleEntry(1, "Joint Limit", "Create three objects joint together", JointLimitCreateFunc),
|
||||||
|
|
||||||
ExampleEntry(0, "MultiBody"),
|
ExampleEntry(0, "MultiBody"),
|
||||||
ExampleEntry(1, "MultiDof", "Create a basic btMultiBody with 3-DOF spherical joints (mobilizers). The demo uses a fixed base or a floating base at restart.", MultiDofCreateFunc),
|
ExampleEntry(1, "MultiDof", "Create a basic btMultiBody with 3-DOF spherical joints (mobilizers). The demo uses a fixed base or a floating base at restart.", MultiDofCreateFunc),
|
||||||
|
|||||||
Reference in New Issue
Block a user