2016-08-30 21:44:11 +00:00
|
|
|
|
|
|
|
#include "KukaGraspExample.h"
|
2016-09-08 22:15:58 +00:00
|
|
|
#include "../SharedMemory/IKTrajectoryHelper.h"
|
2016-08-30 21:44:11 +00:00
|
|
|
|
|
|
|
#include "../CommonInterfaces/CommonGraphicsAppInterface.h"
|
|
|
|
#include "Bullet3Common/b3Quaternion.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 <string>
|
2017-05-13 18:15:20 +00:00
|
|
|
#include "../RobotSimulator/b3RobotSimulatorClientAPI.h"
|
2016-08-30 21:44:11 +00:00
|
|
|
|
|
|
|
#include "../Utils/b3Clock.h"
|
|
|
|
|
|
|
|
///quick demo showing the right-handed coordinate system and positive rotations around each axis
|
|
|
|
class KukaGraspExample : public CommonExampleInterface
|
|
|
|
{
|
|
|
|
CommonGraphicsApp* m_app;
|
|
|
|
GUIHelperInterface* m_guiHelper;
|
2017-05-13 18:15:20 +00:00
|
|
|
b3RobotSimulatorClientAPI m_robotSim;
|
|
|
|
|
2016-08-30 21:44:11 +00:00
|
|
|
int m_kukaIndex;
|
|
|
|
|
|
|
|
IKTrajectoryHelper m_ikHelper;
|
|
|
|
int m_targetSphereInstance;
|
|
|
|
b3Vector3 m_targetPos;
|
2016-09-11 01:48:57 +00:00
|
|
|
b3Vector3 m_worldPos;
|
2016-09-20 00:04:05 +00:00
|
|
|
b3Vector4 m_targetOri;
|
|
|
|
b3Vector4 m_worldOri;
|
2016-08-30 21:44:11 +00:00
|
|
|
double m_time;
|
2017-01-16 06:26:11 +00:00
|
|
|
// int m_options;
|
2016-08-30 21:44:11 +00:00
|
|
|
|
|
|
|
b3AlignedObjectArray<int> m_movingInstances;
|
|
|
|
enum
|
|
|
|
{
|
|
|
|
numCubesX = 20,
|
|
|
|
numCubesY = 20
|
|
|
|
};
|
|
|
|
public:
|
|
|
|
|
2017-01-16 06:26:11 +00:00
|
|
|
KukaGraspExample(GUIHelperInterface* helper, int /* options */)
|
2016-08-30 21:44:11 +00:00
|
|
|
:m_app(helper->getAppInterface()),
|
|
|
|
m_guiHelper(helper),
|
2017-01-16 06:26:11 +00:00
|
|
|
// m_options(options),
|
2016-08-30 21:44:11 +00:00
|
|
|
m_kukaIndex(-1),
|
|
|
|
m_time(0)
|
|
|
|
{
|
|
|
|
m_targetPos.setValue(0.5,0,1);
|
2016-09-11 01:48:57 +00:00
|
|
|
m_worldPos.setValue(0, 0, 0);
|
2016-08-30 21:44:11 +00:00
|
|
|
m_app->setUpAxis(2);
|
|
|
|
}
|
|
|
|
virtual ~KukaGraspExample()
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2017-05-13 20:37:49 +00:00
|
|
|
|
2016-08-30 21:44:11 +00:00
|
|
|
virtual void initPhysics()
|
|
|
|
{
|
|
|
|
|
|
|
|
///create some graphics proxy for the tracking target
|
|
|
|
///the endeffector tries to track it using Inverse Kinematics
|
|
|
|
{
|
|
|
|
int sphereId = m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_MEDIUM);
|
|
|
|
b3Quaternion orn(0, 0, 0, 1);
|
|
|
|
b3Vector4 color = b3MakeVector4(1., 0.3, 0.3, 1);
|
|
|
|
b3Vector3 scaling = b3MakeVector3(.02, .02, .02);
|
|
|
|
m_targetSphereInstance = m_app->m_renderer->registerGraphicsInstance(sphereId, m_targetPos, orn, color, scaling);
|
|
|
|
}
|
|
|
|
m_app->m_renderer->writeTransforms();
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
2017-05-13 18:15:20 +00:00
|
|
|
int mode = eCONNECT_EXISTING_EXAMPLE_BROWSER;
|
|
|
|
m_robotSim.setGuiHelper(m_guiHelper);
|
|
|
|
bool connected = m_robotSim.connect(mode);
|
|
|
|
|
|
|
|
// 0;//m_robotSim.connect(m_guiHelper);
|
2016-08-30 21:44:11 +00:00
|
|
|
b3Printf("robotSim connected = %d",connected);
|
|
|
|
|
|
|
|
|
|
|
|
{
|
2017-05-13 18:15:20 +00:00
|
|
|
m_kukaIndex = m_robotSim.loadURDF("kuka_iiwa/model.urdf");
|
|
|
|
if (m_kukaIndex >=0)
|
2016-08-30 21:44:11 +00:00
|
|
|
{
|
|
|
|
int numJoints = m_robotSim.getNumJoints(m_kukaIndex);
|
|
|
|
b3Printf("numJoints = %d",numJoints);
|
|
|
|
|
|
|
|
for (int i=0;i<numJoints;i++)
|
|
|
|
{
|
|
|
|
b3JointInfo jointInfo;
|
|
|
|
m_robotSim.getJointInfo(m_kukaIndex,i,&jointInfo);
|
|
|
|
b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName);
|
|
|
|
}
|
|
|
|
/*
|
|
|
|
int wheelJointIndices[4]={2,3,6,7};
|
|
|
|
int wheelTargetVelocities[4]={-10,-10,-10,-10};
|
|
|
|
for (int i=0;i<4;i++)
|
|
|
|
{
|
|
|
|
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
|
|
|
|
controlArgs.m_targetVelocity = wheelTargetVelocities[i];
|
|
|
|
controlArgs.m_maxTorqueValue = 1e30;
|
|
|
|
m_robotSim.setJointMotorControl(m_kukaIndex,wheelJointIndices[i],controlArgs);
|
|
|
|
}
|
|
|
|
*/
|
|
|
|
}
|
2017-05-13 18:15:20 +00:00
|
|
|
|
2016-08-30 21:44:11 +00:00
|
|
|
{
|
2017-05-13 18:15:20 +00:00
|
|
|
m_robotSim.loadURDF("plane.urdf");
|
2018-05-27 00:42:33 +00:00
|
|
|
m_robotSim.setGravity(btVector3(0,0,0));
|
2016-08-30 21:44:11 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
virtual void exitPhysics()
|
|
|
|
{
|
|
|
|
m_robotSim.disconnect();
|
|
|
|
}
|
|
|
|
virtual void stepSimulation(float deltaTime)
|
|
|
|
{
|
2016-09-08 22:15:58 +00:00
|
|
|
float dt = deltaTime;
|
|
|
|
btClamp(dt,0.0001f,0.01f);
|
|
|
|
|
|
|
|
m_time+=dt;
|
|
|
|
m_targetPos.setValue(0.4-0.4*b3Cos( m_time), 0, 0.8+0.4*b3Cos( m_time));
|
2016-09-20 00:04:05 +00:00
|
|
|
m_targetOri.setValue(0, 1.0, 0, 0);
|
2017-02-01 06:58:37 +00:00
|
|
|
m_targetPos.setValue(0.2*b3Cos( m_time), 0.2*b3Sin( m_time), 1.1);
|
2016-08-30 21:44:11 +00:00
|
|
|
|
|
|
|
|
|
|
|
int numJoints = m_robotSim.getNumJoints(m_kukaIndex);
|
|
|
|
|
|
|
|
if (numJoints==7)
|
|
|
|
{
|
|
|
|
double q_current[7]={0,0,0,0,0,0,0};
|
2016-09-13 22:37:46 +00:00
|
|
|
|
2017-05-13 18:15:20 +00:00
|
|
|
b3JointStates2 jointStates;
|
2016-09-13 22:37:46 +00:00
|
|
|
|
2016-08-30 21:44:11 +00:00
|
|
|
if (m_robotSim.getJointStates(m_kukaIndex,jointStates))
|
|
|
|
{
|
|
|
|
//skip the base positions (7 values)
|
|
|
|
b3Assert(7+numJoints == jointStates.m_numDegreeOfFreedomQ);
|
|
|
|
for (int i=0;i<numJoints;i++)
|
|
|
|
{
|
|
|
|
q_current[i] = jointStates.m_actualStateQ[i+7];
|
|
|
|
}
|
|
|
|
}
|
2016-09-20 00:04:05 +00:00
|
|
|
// compute body position and orientation
|
2017-05-13 18:15:20 +00:00
|
|
|
b3LinkState linkState;
|
2018-06-13 00:00:16 +00:00
|
|
|
bool computeVelocity=true;
|
|
|
|
bool computeForwardKinematics=true;
|
|
|
|
m_robotSim.getLinkState(0, 6, computeVelocity,computeForwardKinematics, &linkState);
|
2017-05-13 18:15:20 +00:00
|
|
|
|
|
|
|
m_worldPos.setValue(linkState.m_worldLinkFramePosition[0], linkState.m_worldLinkFramePosition[1], linkState.m_worldLinkFramePosition[2]);
|
|
|
|
m_worldOri.setValue(linkState.m_worldLinkFrameOrientation[0], linkState.m_worldLinkFrameOrientation[1], linkState.m_worldLinkFrameOrientation[2], linkState.m_worldLinkFrameOrientation[3]);
|
|
|
|
|
|
|
|
|
2016-09-20 00:04:05 +00:00
|
|
|
b3Vector3DoubleData targetPosDataOut;
|
|
|
|
m_targetPos.serializeDouble(targetPosDataOut);
|
2016-09-13 22:37:46 +00:00
|
|
|
b3Vector3DoubleData worldPosDataOut;
|
|
|
|
m_worldPos.serializeDouble(worldPosDataOut);
|
2016-09-20 00:04:05 +00:00
|
|
|
b3Vector3DoubleData targetOriDataOut;
|
|
|
|
m_targetOri.serializeDouble(targetOriDataOut);
|
|
|
|
b3Vector3DoubleData worldOriDataOut;
|
|
|
|
m_worldOri.serializeDouble(worldOriDataOut);
|
2016-09-13 22:37:46 +00:00
|
|
|
|
|
|
|
|
2017-05-13 18:15:20 +00:00
|
|
|
b3RobotSimulatorInverseKinematicArgs ikargs;
|
|
|
|
b3RobotSimulatorInverseKinematicsResults ikresults;
|
2016-09-08 22:15:58 +00:00
|
|
|
|
|
|
|
|
|
|
|
ikargs.m_bodyUniqueId = m_kukaIndex;
|
2016-09-13 22:37:46 +00:00
|
|
|
// ikargs.m_currentJointPositions = q_current;
|
|
|
|
// ikargs.m_numPositions = 7;
|
2016-09-20 00:04:05 +00:00
|
|
|
ikargs.m_endEffectorTargetPosition[0] = targetPosDataOut.m_floats[0];
|
|
|
|
ikargs.m_endEffectorTargetPosition[1] = targetPosDataOut.m_floats[1];
|
|
|
|
ikargs.m_endEffectorTargetPosition[2] = targetPosDataOut.m_floats[2];
|
2016-09-08 22:15:58 +00:00
|
|
|
|
2017-02-03 19:08:44 +00:00
|
|
|
//ikargs.m_flags |= B3_HAS_IK_TARGET_ORIENTATION;
|
|
|
|
ikargs.m_flags |= B3_HAS_JOINT_DAMPING;
|
2016-09-22 20:27:09 +00:00
|
|
|
|
2016-09-20 00:04:05 +00:00
|
|
|
ikargs.m_endEffectorTargetOrientation[0] = targetOriDataOut.m_floats[0];
|
|
|
|
ikargs.m_endEffectorTargetOrientation[1] = targetOriDataOut.m_floats[1];
|
|
|
|
ikargs.m_endEffectorTargetOrientation[2] = targetOriDataOut.m_floats[2];
|
|
|
|
ikargs.m_endEffectorTargetOrientation[3] = targetOriDataOut.m_floats[3];
|
2016-09-22 20:27:09 +00:00
|
|
|
ikargs.m_endEffectorLinkIndex = 6;
|
2016-09-30 07:05:00 +00:00
|
|
|
|
2016-09-30 08:03:40 +00:00
|
|
|
// Settings based on default KUKA arm setting
|
|
|
|
ikargs.m_lowerLimits.resize(numJoints);
|
|
|
|
ikargs.m_upperLimits.resize(numJoints);
|
|
|
|
ikargs.m_jointRanges.resize(numJoints);
|
|
|
|
ikargs.m_restPoses.resize(numJoints);
|
2017-02-03 19:08:44 +00:00
|
|
|
ikargs.m_jointDamping.resize(numJoints,0.5);
|
2016-09-30 08:03:40 +00:00
|
|
|
ikargs.m_lowerLimits[0] = -2.32;
|
|
|
|
ikargs.m_lowerLimits[1] = -1.6;
|
|
|
|
ikargs.m_lowerLimits[2] = -2.32;
|
|
|
|
ikargs.m_lowerLimits[3] = -1.6;
|
|
|
|
ikargs.m_lowerLimits[4] = -2.32;
|
|
|
|
ikargs.m_lowerLimits[5] = -1.6;
|
|
|
|
ikargs.m_lowerLimits[6] = -2.4;
|
|
|
|
ikargs.m_upperLimits[0] = 2.32;
|
|
|
|
ikargs.m_upperLimits[1] = 1.6;
|
|
|
|
ikargs.m_upperLimits[2] = 2.32;
|
|
|
|
ikargs.m_upperLimits[3] = 1.6;
|
|
|
|
ikargs.m_upperLimits[4] = 2.32;
|
|
|
|
ikargs.m_upperLimits[5] = 1.6;
|
|
|
|
ikargs.m_upperLimits[6] = 2.4;
|
|
|
|
ikargs.m_jointRanges[0] = 5.8;
|
|
|
|
ikargs.m_jointRanges[1] = 4;
|
|
|
|
ikargs.m_jointRanges[2] = 5.8;
|
|
|
|
ikargs.m_jointRanges[3] = 4;
|
|
|
|
ikargs.m_jointRanges[4] = 5.8;
|
|
|
|
ikargs.m_jointRanges[5] = 4;
|
|
|
|
ikargs.m_jointRanges[6] = 6;
|
|
|
|
ikargs.m_restPoses[0] = 0;
|
|
|
|
ikargs.m_restPoses[1] = 0;
|
|
|
|
ikargs.m_restPoses[2] = 0;
|
|
|
|
ikargs.m_restPoses[3] = SIMD_HALF_PI;
|
|
|
|
ikargs.m_restPoses[4] = 0;
|
|
|
|
ikargs.m_restPoses[5] = -SIMD_HALF_PI*0.66;
|
|
|
|
ikargs.m_restPoses[6] = 0;
|
2017-02-03 19:08:44 +00:00
|
|
|
ikargs.m_jointDamping[0] = 10.0;
|
2016-09-30 07:05:00 +00:00
|
|
|
ikargs.m_numDegreeOfFreedom = numJoints;
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
if (m_robotSim.calculateInverseKinematics(ikargs,ikresults))
|
|
|
|
{
|
2016-09-13 22:37:46 +00:00
|
|
|
//copy the IK result to the desired state of the motor/actuator
|
|
|
|
for (int i=0;i<numJoints;i++)
|
|
|
|
{
|
2017-05-13 18:15:20 +00:00
|
|
|
b3RobotSimulatorJointMotorArgs t(CONTROL_MODE_POSITION_VELOCITY_PD);
|
2016-09-13 22:37:46 +00:00
|
|
|
t.m_targetPosition = ikresults.m_calculatedJointPositions[i];
|
2016-09-30 07:43:15 +00:00
|
|
|
t.m_maxTorqueValue = 100.0;
|
|
|
|
t.m_kp= 1.0;
|
2016-09-23 02:48:26 +00:00
|
|
|
t.m_targetVelocity = 0;
|
2016-09-30 07:43:15 +00:00
|
|
|
t.m_kd = 1.0;
|
2016-09-13 22:37:46 +00:00
|
|
|
m_robotSim.setJointMotorControl(m_kukaIndex,i,t);
|
2016-08-30 21:44:11 +00:00
|
|
|
|
2016-09-13 22:37:46 +00:00
|
|
|
}
|
2016-08-30 21:44:11 +00:00
|
|
|
}
|
2017-05-13 18:15:20 +00:00
|
|
|
|
2016-08-30 21:44:11 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
m_robotSim.stepSimulation();
|
|
|
|
}
|
|
|
|
virtual void renderScene()
|
|
|
|
{
|
|
|
|
m_robotSim.renderScene();
|
|
|
|
|
|
|
|
|
|
|
|
b3Quaternion orn(0, 0, 0, 1);
|
|
|
|
|
|
|
|
|
|
|
|
m_app->m_renderer->writeSingleInstanceTransformToCPU(m_targetPos, orn, m_targetSphereInstance);
|
|
|
|
m_app->m_renderer->writeTransforms();
|
|
|
|
|
|
|
|
//draw the end-effector target sphere
|
|
|
|
|
|
|
|
//m_app->m_renderer->renderScene();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2017-05-13 20:37:49 +00:00
|
|
|
virtual void physicsDebugDraw(int debugDrawMode)
|
2016-08-30 21:44:11 +00:00
|
|
|
{
|
2017-05-13 20:37:49 +00:00
|
|
|
m_robotSim.debugDraw(debugDrawMode);
|
2016-08-30 21:44:11 +00:00
|
|
|
}
|
|
|
|
virtual bool mouseMoveCallback(float x,float y)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
virtual bool mouseButtonCallback(int button, int state, float x, float y)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
virtual bool keyboardCallback(int key, int state)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual void resetCamera()
|
|
|
|
{
|
|
|
|
float dist = 3;
|
2017-06-01 22:30:37 +00:00
|
|
|
float pitch = -30;
|
|
|
|
float yaw = 0;
|
2016-08-30 21:44:11 +00:00
|
|
|
float targetPos[3]={-0.2,0.8,0.3};
|
|
|
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
|
|
|
{
|
|
|
|
m_app->m_renderer->getActiveCamera()->setCameraDistance(dist);
|
|
|
|
m_app->m_renderer->getActiveCamera()->setCameraPitch(pitch);
|
|
|
|
m_app->m_renderer->getActiveCamera()->setCameraYaw(yaw);
|
|
|
|
m_app->m_renderer->getActiveCamera()->setCameraTargetPosition(targetPos[0],targetPos[1],targetPos[2]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
class CommonExampleInterface* KukaGraspExampleCreateFunc(struct CommonExampleOptions& options)
|
|
|
|
{
|
|
|
|
return new KukaGraspExample(options.m_guiHelper, options.m_option);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|