mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 05:10:08 +00:00
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:
parent
77b9e1a3e2
commit
a6216f4f24
33
data/cube_small.urdf
Normal file
33
data/cube_small.urdf
Normal file
@ -0,0 +1,33 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<rolling_friction value="0.0"/>
|
||||
<inertia_scaling value="3.0"/>
|
||||
<contact_cfm value="0.0"/>
|
||||
<contact_erp value="1.0"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value=".1"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="cube.obj" scale=".05 .05 .05"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".05 .05 .05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
BIN
data/gripper/meshes/GUIDE_WSG50_110.stl
Normal file
BIN
data/gripper/meshes/GUIDE_WSG50_110.stl
Normal file
Binary file not shown.
BIN
data/gripper/meshes/WSG-FMF.stl
Normal file
BIN
data/gripper/meshes/WSG-FMF.stl
Normal file
Binary file not shown.
BIN
data/gripper/meshes/WSG50_110.stl
Normal file
BIN
data/gripper/meshes/WSG50_110.stl
Normal file
Binary file not shown.
BIN
data/gripper/meshes/l_gripper_tip_scaled.stl
Normal file
BIN
data/gripper/meshes/l_gripper_tip_scaled.stl
Normal file
Binary file not shown.
298
data/gripper/wsg50_with_r2d2_gripper.sdf
Normal file
298
data/gripper/wsg50_with_r2d2_gripper.sdf
Normal file
@ -0,0 +1,298 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='wsg50_with_gripper'>
|
||||
<pose frame=''>0 0 0.27 3.14 0 0</pose>
|
||||
|
||||
<link name='world'>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint' type='prismatic'>
|
||||
<parent>world</parent>
|
||||
<child>base_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.5</lower>
|
||||
<upper>10</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<friction>100</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='base_link'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<mass>1.2</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='base_link_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.2 0.05 0.05 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='base_link_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
|
||||
</material>
|
||||
</visual>
|
||||
<gravity>1</gravity>
|
||||
<velocity_decay/>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
|
||||
<link name='gripper_left'>
|
||||
<pose frame=''>-0.055 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 0 -0 0</pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name='gripper_left_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision name='gripper_left_fixed_joint_lump__finger_left_collision_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='gripper_left_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_left_fixed_joint_lump__finger_left_visual_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
<joint name='base_joint_gripper_left' type='prismatic'>
|
||||
<child>gripper_left</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.001</lower>
|
||||
<upper>0.055</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<friction>100</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='gripper_right'>
|
||||
<pose frame=''>0.055 0 0 0 -0 3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 0 -0 0</pose>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name='gripper_right_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision name='gripper_right_fixed_joint_lump__finger_right_collision_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='gripper_right_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_right_fixed_joint_lump__finger_right_visual_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint_gripper_right' type='prismatic'>
|
||||
<child>gripper_right</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>-1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.055</lower>
|
||||
<upper>0.001</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<friction>100</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='finger_right'>
|
||||
<pose frame=''>0.062 0 0.145 0 0 1.5708</pose>
|
||||
<inertial>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name='finger_right_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_right_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_right' type='fixed'>
|
||||
<parent>gripper_right</parent>
|
||||
<child>finger_right</child>
|
||||
</joint>
|
||||
|
||||
<link name='finger_left'>
|
||||
<pose frame=''>-0.062 0 0.145 0 0 4.71239</pose>
|
||||
<inertial>
|
||||
<mass>0.2</mass>
|
||||
<inertia>
|
||||
<ixx>0.1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name='finger_left_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_left_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_left' type='fixed'>
|
||||
<parent>gripper_left</parent>
|
||||
<child>finger_left</child>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
@ -249,6 +249,7 @@ static ExampleEntry gDefaultExamples[]=
|
||||
|
||||
ExampleEntry(1,"R2D2 Grasp","Load the R2D2 robot from URDF file and control it to grasp objects", R2D2GraspExampleCreateFunc, eROBOTIC_LEARN_GRASP),
|
||||
ExampleEntry(1,"URDF Compliant Contact","Work-in-progress, experiment/improve compliant rigid contact using parameters from URDF file (contact_cfm, contact_erp, lateral_friction, rolling_friction)", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_COMPLIANT_CONTACT),
|
||||
ExampleEntry(1,"Contact for Grasp","Grasp experiment to improve contact model", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_GRASP_CONTACT),
|
||||
|
||||
|
||||
|
||||
|
@ -519,6 +519,8 @@ void MyStatusBarError(const char* msg)
|
||||
gui2->textOutput(msg);
|
||||
gui2->forceUpdateScrollBars();
|
||||
}
|
||||
btAssert(0);
|
||||
|
||||
}
|
||||
|
||||
struct MyMenuItemHander :public Gwen::Event::Handler
|
||||
|
@ -232,6 +232,13 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
if (mass)
|
||||
{
|
||||
compoundShape->calculateLocalInertia(mass, localInertiaDiagonal);
|
||||
URDFLinkContactInfo contactInfo;
|
||||
u2b.getLinkContactInfo(urdfLinkIndex,contactInfo);
|
||||
//temporary inertia scaling until we load inertia from URDF
|
||||
if (contactInfo.m_flags & URDF_CONTACT_HAS_INERTIA_SCALING)
|
||||
{
|
||||
localInertiaDiagonal*=contactInfo.m_inertiaScaling;
|
||||
}
|
||||
}
|
||||
|
||||
btRigidBody* linkRigidBody = 0;
|
||||
|
@ -17,7 +17,8 @@ enum URDF_LinkContactFlags
|
||||
{
|
||||
URDF_CONTACT_HAS_LATERAL_FRICTION=1,
|
||||
URDF_CONTACT_HAS_ROLLING_FRICTION=2,
|
||||
URDF_CONTACT_HAS_CONTACT_CFM=4,
|
||||
URDF_CONTACT_HAS_INERTIA_SCALING=2,
|
||||
URDF_CONTACT_HAS_CONTACT_CFM=4,
|
||||
URDF_CONTACT_HAS_CONTACT_ERP=8
|
||||
};
|
||||
|
||||
@ -25,6 +26,7 @@ struct URDFLinkContactInfo
|
||||
{
|
||||
btScalar m_lateralFriction;
|
||||
btScalar m_rollingFriction;
|
||||
btScalar m_inertiaScaling;
|
||||
btScalar m_contactCfm;
|
||||
btScalar m_contactErp;
|
||||
int m_flags;
|
||||
@ -32,6 +34,7 @@ struct URDFLinkContactInfo
|
||||
URDFLinkContactInfo()
|
||||
:m_lateralFriction(0.5),
|
||||
m_rollingFriction(0),
|
||||
m_inertiaScaling(1),
|
||||
m_contactCfm(0),
|
||||
m_contactErp(0)
|
||||
{
|
||||
|
@ -606,6 +606,28 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi
|
||||
TiXmlElement* ci = config->FirstChildElement("contact");
|
||||
if (ci)
|
||||
{
|
||||
|
||||
TiXmlElement *damping_xml = ci->FirstChildElement("inertia_scaling");
|
||||
if (damping_xml)
|
||||
{
|
||||
if (m_parseSDF)
|
||||
{
|
||||
link.m_contactInfo.m_inertiaScaling = urdfLexicalCast<double>(damping_xml->GetText());
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_INERTIA_SCALING;
|
||||
} else
|
||||
{
|
||||
if (!damping_xml->Attribute("value"))
|
||||
{
|
||||
logger->reportError("Link/contact: damping element must have value attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
link.m_contactInfo.m_inertiaScaling = urdfLexicalCast<double>(damping_xml->Attribute("value"));
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_INERTIA_SCALING;
|
||||
|
||||
}
|
||||
}
|
||||
{
|
||||
TiXmlElement *friction_xml = ci->FirstChildElement("lateral_friction");
|
||||
if (friction_xml)
|
||||
{
|
||||
@ -623,6 +645,7 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi
|
||||
link.m_contactInfo.m_lateralFriction = urdfLexicalCast<double>(friction_xml->Attribute("value"));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -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)
|
||||
{
|
||||
}
|
||||
|
@ -1216,16 +1216,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
}
|
||||
|
||||
bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes);
|
||||
|
||||
//serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
|
||||
serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size();
|
||||
int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies);
|
||||
for (int i=0;i<maxBodies;i++)
|
||||
if (completedOk)
|
||||
{
|
||||
serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[i] = m_data->m_sdfRecentLoadedBodies[i];
|
||||
}
|
||||
//serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
|
||||
serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size();
|
||||
int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies);
|
||||
for (int i=0;i<maxBodies;i++)
|
||||
{
|
||||
serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[i] = m_data->m_sdfRecentLoadedBodies[i];
|
||||
}
|
||||
|
||||
serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED;
|
||||
serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED;
|
||||
} else
|
||||
{
|
||||
serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
|
||||
}
|
||||
hasStatus = true;
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user