add robotics learning grasp contact example
add wsg50 gripper with modified r2d2 gripper tip expose a fudge factor to scale inertia, to make grasping more stable (until we have better grasping contact model/implementation)
This commit is contained in:
@@ -9,11 +9,15 @@
|
||||
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||
#include "../SharedMemory/PhysicsServerSharedMemory.h"
|
||||
#include "../SharedMemory/PhysicsClientC_API.h"
|
||||
#include "../CommonInterfaces/CommonParameterInterface.h"
|
||||
#include <string>
|
||||
|
||||
#include "b3RobotSimAPI.h"
|
||||
#include "../Utils/b3Clock.h"
|
||||
|
||||
static btScalar sGripperVerticalVelocity = -0.2f;
|
||||
static btScalar sGripperClosingTargetVelocity = 0.5f;
|
||||
|
||||
///quick demo showing the right-handed coordinate system and positive rotations around each axis
|
||||
class R2D2GraspExample : public CommonExampleInterface
|
||||
{
|
||||
@@ -22,7 +26,8 @@ class R2D2GraspExample : public CommonExampleInterface
|
||||
b3RobotSimAPI m_robotSim;
|
||||
int m_options;
|
||||
int m_r2d2Index;
|
||||
|
||||
int m_gripperIndex;
|
||||
|
||||
float m_x;
|
||||
float m_y;
|
||||
float m_z;
|
||||
@@ -39,6 +44,7 @@ public:
|
||||
m_guiHelper(helper),
|
||||
m_options(options),
|
||||
m_r2d2Index(-1),
|
||||
m_gripperIndex(-1),
|
||||
m_x(0),
|
||||
m_y(0),
|
||||
m_z(0)
|
||||
@@ -61,36 +67,9 @@ public:
|
||||
b3Printf("robotSim connected = %d",connected);
|
||||
|
||||
|
||||
if ((m_options & eROBOTIC_LEARN_GRASP)!=0)
|
||||
if (m_options == eROBOTIC_LEARN_GRASP)
|
||||
{
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "r2d2.urdf";
|
||||
args.m_startPosition.setValue(0,0,.5);
|
||||
b3RobotSimLoadFileResults results;
|
||||
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
|
||||
{
|
||||
int m_r2d2Index = results.m_uniqueObjectIds[0];
|
||||
int numJoints = m_robotSim.getNumJoints(m_r2d2Index);
|
||||
b3Printf("numJoints = %d",numJoints);
|
||||
|
||||
for (int i=0;i<numJoints;i++)
|
||||
{
|
||||
b3JointInfo jointInfo;
|
||||
m_robotSim.getJointInfo(m_r2d2Index,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_r2d2Index,wheelJointIndices[i],controlArgs);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "kiva_shelf/model.sdf";
|
||||
@@ -109,38 +88,154 @@ public:
|
||||
args.m_forceOverrideFixedBase = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
m_robotSim.loadFile(args,results);
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,0));
|
||||
}
|
||||
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "r2d2.urdf";
|
||||
args.m_startPosition.setValue(0,0,.5);
|
||||
b3RobotSimLoadFileResults results;
|
||||
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
|
||||
{
|
||||
int m_r2d2Index = results.m_uniqueObjectIds[0];
|
||||
int numJoints = m_robotSim.getNumJoints(m_r2d2Index);
|
||||
b3Printf("numJoints = %d",numJoints);
|
||||
|
||||
for (int i=0;i<numJoints;i++)
|
||||
{
|
||||
b3JointInfo jointInfo;
|
||||
m_robotSim.getJointInfo(m_r2d2Index,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_r2d2Index,wheelJointIndices[i],controlArgs);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if ((m_options & eROBOTIC_LEARN_COMPLIANT_CONTACT)!=0)
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
b3RobotSimLoadFileResults results;
|
||||
{
|
||||
args.m_fileName = "cube.urdf";
|
||||
args.m_startPosition.setValue(0,0,2.5);
|
||||
args.m_startOrientation.setEulerZYX(0,0.2,0);
|
||||
m_robotSim.loadFile(args,results);
|
||||
}
|
||||
{
|
||||
args.m_fileName = "cube_no_friction.urdf";
|
||||
args.m_startPosition.setValue(0,2,2.5);
|
||||
args.m_startOrientation.setEulerZYX(0,0.2,0);
|
||||
m_robotSim.loadFile(args,results);
|
||||
}
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "plane.urdf";
|
||||
args.m_startPosition.setValue(0,0,0);
|
||||
args.m_startOrientation.setEulerZYX(0,0.2,0);
|
||||
args.m_forceOverrideFixedBase = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
m_robotSim.loadFile(args,results);
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
|
||||
}
|
||||
}
|
||||
if (m_options == eROBOTIC_LEARN_COMPLIANT_CONTACT)
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
b3RobotSimLoadFileResults results;
|
||||
{
|
||||
args.m_fileName = "cube.urdf";
|
||||
args.m_startPosition.setValue(0,0,2.5);
|
||||
args.m_startOrientation.setEulerZYX(0,0.2,0);
|
||||
m_robotSim.loadFile(args,results);
|
||||
}
|
||||
{
|
||||
args.m_fileName = "cube_no_friction.urdf";
|
||||
args.m_startPosition.setValue(0,2,2.5);
|
||||
args.m_startOrientation.setEulerZYX(0,0.2,0);
|
||||
m_robotSim.loadFile(args,results);
|
||||
}
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "plane.urdf";
|
||||
args.m_startPosition.setValue(0,0,0);
|
||||
args.m_startOrientation.setEulerZYX(0,0.2,0);
|
||||
args.m_forceOverrideFixedBase = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
m_robotSim.loadFile(args,results);
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
|
||||
}
|
||||
}
|
||||
|
||||
if (m_options == eROBOTIC_LEARN_GRASP_CONTACT)
|
||||
{
|
||||
|
||||
{
|
||||
SliderParams slider("Vertical velocity",&sGripperVerticalVelocity);
|
||||
slider.m_minVal=-2;
|
||||
slider.m_maxVal=2;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
{
|
||||
SliderParams slider("Closing velocity",&sGripperClosingTargetVelocity
|
||||
);
|
||||
slider.m_minVal=-1;
|
||||
slider.m_maxVal=1;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf";
|
||||
args.m_fileType = B3_SDF_FILE;
|
||||
b3RobotSimLoadFileResults results;
|
||||
|
||||
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
|
||||
{
|
||||
|
||||
m_gripperIndex = results.m_uniqueObjectIds[0];
|
||||
int numJoints = m_robotSim.getNumJoints(m_gripperIndex);
|
||||
b3Printf("numJoints = %d",numJoints);
|
||||
|
||||
for (int i=0;i<numJoints;i++)
|
||||
{
|
||||
b3JointInfo jointInfo;
|
||||
m_robotSim.getJointInfo(m_gripperIndex,i,&jointInfo);
|
||||
b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName);
|
||||
}
|
||||
|
||||
/*
|
||||
int fingerJointIndices[2]={1,3};
|
||||
double fingerTargetPositions[2]={-0.04,0.04};
|
||||
for (int i=0;i<2;i++)
|
||||
{
|
||||
b3JointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
|
||||
controlArgs.m_targetPosition = fingerTargetPositions[i];
|
||||
controlArgs.m_kp = 5.0;
|
||||
controlArgs.m_kd = 3.0;
|
||||
controlArgs.m_maxTorqueValue = 1.0;
|
||||
m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
|
||||
}
|
||||
*/
|
||||
int fingerJointIndices[3]={0,1,3};
|
||||
double fingerTargetVelocities[3]={-0.2,.5,-.5};
|
||||
double maxTorqueValues[3]={40.0,50.0,50.0};
|
||||
for (int i=0;i<3;i++)
|
||||
{
|
||||
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
|
||||
controlArgs.m_targetVelocity = fingerTargetVelocities[i];
|
||||
controlArgs.m_maxTorqueValue = maxTorqueValues[i];
|
||||
controlArgs.m_kd = 1.;
|
||||
m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
|
||||
}
|
||||
}
|
||||
}
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
b3RobotSimLoadFileResults results;
|
||||
args.m_fileName = "cube_small.urdf";
|
||||
args.m_startPosition.setValue(0,0,.107);
|
||||
args.m_startOrientation.setEulerZYX(0,0,0);
|
||||
m_robotSim.loadFile(args,results);
|
||||
}
|
||||
if (1)
|
||||
{
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
args.m_fileName = "plane.urdf";
|
||||
args.m_startPosition.setValue(0,0,0);
|
||||
args.m_startOrientation.setEulerZYX(0,0,0);
|
||||
args.m_forceOverrideFixedBase = true;
|
||||
b3RobotSimLoadFileResults results;
|
||||
m_robotSim.loadFile(args,results);
|
||||
|
||||
}
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
@@ -150,6 +245,22 @@ public:
|
||||
}
|
||||
virtual void stepSimulation(float deltaTime)
|
||||
{
|
||||
if ((m_options == eROBOTIC_LEARN_GRASP_CONTACT) && (m_gripperIndex>=0))
|
||||
{
|
||||
int fingerJointIndices[3]={0,1,3};
|
||||
double fingerTargetVelocities[3]={sGripperVerticalVelocity,sGripperClosingTargetVelocity
|
||||
,-sGripperClosingTargetVelocity
|
||||
};
|
||||
double maxTorqueValues[3]={40.0,50.0,50.0};
|
||||
for (int i=0;i<3;i++)
|
||||
{
|
||||
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
|
||||
controlArgs.m_targetVelocity = fingerTargetVelocities[i];
|
||||
controlArgs.m_maxTorqueValue = maxTorqueValues[i];
|
||||
controlArgs.m_kd = 1.;
|
||||
m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
|
||||
}
|
||||
}
|
||||
m_robotSim.stepSimulation();
|
||||
}
|
||||
virtual void renderScene()
|
||||
@@ -179,9 +290,9 @@ public:
|
||||
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 3;
|
||||
float pitch = -75;
|
||||
float yaw = 30;
|
||||
float dist = 1.5;
|
||||
float pitch = 12;
|
||||
float yaw = -10;
|
||||
float targetPos[3]={-0.2,0.8,0.3};
|
||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||
{
|
||||
|
||||
@@ -20,6 +20,7 @@ enum RobotLearningExampleOptions
|
||||
{
|
||||
eROBOTIC_LEARN_GRASP=1,
|
||||
eROBOTIC_LEARN_COMPLIANT_CONTACT=2,
|
||||
eROBOTIC_LEARN_GRASP_CONTACT=3,
|
||||
};
|
||||
|
||||
class CommonExampleInterface* R2D2GraspExampleCreateFunc(struct CommonExampleOptions& options);
|
||||
|
||||
@@ -560,6 +560,7 @@ void b3RobotSimAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const
|
||||
b3JointInfo jointInfo;
|
||||
b3GetJointInfo(m_data->m_physicsClient, bodyUniqueId, jointIndex, &jointInfo);
|
||||
int uIndex = jointInfo.m_uIndex;
|
||||
b3JointControlSetKd(command,uIndex,args.m_kd);
|
||||
b3JointControlSetDesiredVelocity(command,uIndex,args.m_targetVelocity);
|
||||
b3JointControlSetMaximumForce(command,uIndex,args.m_maxTorqueValue);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClient, command);
|
||||
@@ -627,6 +628,7 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS
|
||||
}
|
||||
statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
|
||||
b3Assert(statusType==CMD_URDF_LOADING_COMPLETED);
|
||||
robotUniqueId = b3GetStatusBodyIndex(statusHandle);
|
||||
results.m_uniqueObjectIds.push_back(robotUniqueId);
|
||||
|
||||
@@ -61,7 +61,7 @@ struct b3JointMotorArgs
|
||||
m_targetPosition(0),
|
||||
m_kp(0.1),
|
||||
m_targetVelocity(0),
|
||||
m_kd(0.1),
|
||||
m_kd(0.9),
|
||||
m_maxTorqueValue(1000)
|
||||
{
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user