Add table and tray.

This commit is contained in:
YunfeiBai 2016-09-26 11:31:30 -07:00
parent 60d07a6f6e
commit 539fe505a4
4 changed files with 568 additions and 3 deletions

View File

@ -0,0 +1,400 @@
<?xml version="1.0" ?>
<sdf version='1.6'>
<world name='default'>
<model name='wsg50_with_gripper'>
<link name='world'>
<pose frame=''>0 0 0 0 0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
</link>
<joint name='base_joint' type='prismatic'>
<parent>world</parent>
<child>base_link</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-0.0001</lower>
<upper>0.0001</upper>
<effort>1</effort>
<velocity>1</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</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>
<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>
</link>
<link name='motor'>
<pose frame=''>0 0 0.03 0 0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 0 0</pose>
<mass>0.1</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>
<visual name='motor_visual'>
<pose frame=''>0 0 0.01 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.02 0.02 </size>
</box>
</geometry>
</visual>
</link>
<joint name='base_joint_motor' type='prismatic'>
<child>motor</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-0.055</lower>
<upper>0.001</upper>
<effort>10.0</effort>
<velocity>10.0</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='left_hinge'>
<pose frame=''>0 0 0.04 0 0 0</pose>
<inertial>
<pose frame=''>0 0 0.035 0 0 0</pose>
<mass>0.1</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>
<visual name='motor_visual'>
<pose frame=''>-0.03 0 0.01 0 -1.2 0</pose>
<geometry>
<box>
<size>0.02 0.02 0.07 </size>
</box>
</geometry>
</visual>
</link>
<joint name='motor_left_hinge_joint' type='revolute'>
<child>left_hinge</child>
<parent>motor</parent>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-20.0</lower>
<upper>20.0</upper>
<effort>10</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>0</use_parent_model_frame>
</axis>
</joint>
<link name='right_hinge'>
<pose frame=''>0 0 0.04 0 0 0</pose>
<inertial>
<pose frame=''>0 0 0.035 0 0 0</pose>
<mass>0.1</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>
<visual name='motor_visual'>
<pose frame=''>0.03 0 0.01 0 1.2 0</pose>
<geometry>
<box>
<size>0.02 0.02 0.07 </size>
</box>
</geometry>
</visual>
</link>
<joint name='motor_right_hinge_joint' type='revolute'>
<child>right_hinge</child>
<parent>motor</parent>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-20.0</lower>
<upper>20.0</upper>
<effort>10</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>0</use_parent_model_frame>
</axis>
</joint>
<link name='gripper_left'>
<pose frame=''>-0.055 0 0.06 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>
<visual name='gripper_left_visual'>
<pose frame=''>0 0 -0.06 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.037 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='gripper_left_hinge_joint' type='revolute'>
<child>gripper_left</child>
<parent>left_hinge</parent>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.0</lower>
<upper>1.0</upper>
<effort>10</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.01</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>0</use_parent_model_frame>
</axis>
</joint>
<link name='gripper_right'>
<pose frame=''>0.055 0 0.06 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>
<visual name='gripper_right_visual'>
<pose frame=''>0 0 -0.06 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.037 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='gripper_right_hinge_joint' type='revolute'>
<child>gripper_right</child>
<parent>right_hinge</parent>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.0</lower>
<upper>1.0</upper>
<effort>10</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.01</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>0</use_parent_model_frame>
</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>

61
data/table.urdf Normal file
View File

@ -0,0 +1,61 @@
<?xml version="0.0" ?>
<robot name="urdf_table">
<link name="world"/>
<joint name="fixed" type="fixed">
<parent link="world"/>
<child link="baseLink"/>
<origin xyz="0 0 0"/>
</joint>
<link name="baseLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.6"/>
<mass value="0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.6"/>
<geometry>
<box size="1.5 1.0 0.08"/>
</geometry>
<material name="framemat0">
<color
rgba="1 1 1 1" />
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.65 -0.4 0.28"/>
<geometry>
<box size="0.1 0.1 0.56"/>
</geometry>
<material name="framemat0"/>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.65 0.4 0.28"/>
<geometry>
<box size="0.1 0.1 0.56"/>
</geometry>
<material name="framemat0"/>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.65 -0.4 0.28"/>
<geometry>
<box size="0.1 0.1 0.56"/>
</geometry>
<material name="framemat0"/>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.65 0.4 0.28"/>
<geometry>
<box size="0.1 0.1 0.56"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.6"/>
<geometry>
<box size="1.5 1.0 0.08"/>
</geometry>
</collision>
</link>
</robot>

91
data/tray.urdf Normal file
View File

@ -0,0 +1,91 @@
<?xml version="1.0"?>
<robot name="tray">
<link name="baseLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.29 0.0 0.05"/>
<geometry>
<box size="0.02 0.6 0.06"/>
</geometry>
<material name="framemat0">
<color rgba="0.6 0.6 0.6 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.29 0.0 0.05"/>
<geometry>
<box size="0.02 0.6 0.06"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0.29 0.0 0.05"/>
<geometry>
<box size="0.02 0.6 0.06"/>
</geometry>
<material name="framemat0">
<color rgba="0.6 0.6 0.6 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.29 0.0 0.05"/>
<geometry>
<box size="0.02 0.6 0.06"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0.0 -0.29 0.05"/>
<geometry>
<box size="0.56 0.02 0.06"/>
</geometry>
<material name="framemat0">
<color rgba="0.6 0.6 0.6 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 -0.29 0.05"/>
<geometry>
<box size="0.56 0.02 0.06"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.29 0.05"/>
<geometry>
<box size="0.56 0.02 0.06"/>
</geometry>
<material name="framemat0">
<color rgba="0.6 0.6 0.6 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.29 0.05"/>
<geometry>
<box size="0.56 0.02 0.06"/>
</geometry>
</collision>
<!-- base -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
<geometry>
<box size="0.6 0.6 0.02"/>
</geometry>
<material name="framemat0"/>
<color rgba="0.4 0.4 0.4 1"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
<geometry>
<box size="0.6 0.6 0.02"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -2951,7 +2951,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
loadUrdf("sphere2.urdf", btVector3(-5, 0, 3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("sphere2.urdf", btVector3(-5, 0, 3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("r2d2.urdf", btVector3(2, -2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("r2d2.urdf", btVector3(2, -2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("kuka_iiwa/model.urdf", btVector3(2.0, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("kuka_iiwa/model.urdf", btVector3(0, -2.3, 0.6), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
m_data->m_KukaId = bodyId; m_data->m_KukaId = bodyId;
// Load one motor gripper for kuka // Load one motor gripper for kuka
@ -3070,11 +3070,14 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
} }
loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true); loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true);
loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("teddy_vhacd.urdf", btVector3(1.6, -0.2, 0.1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("cube_small.urdf", btVector3(1.5, -0.3, 0.1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("cup_small.urdf", btVector3(3, 2, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); //loadUrdf("cup_small.urdf", btVector3(3, 2, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("pitcher_small.urdf", btVector3(4, 2, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); //loadUrdf("pitcher_small.urdf", btVector3(4, 2, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("table.urdf", btVector3(0, -1.9, 0.0), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("tray.urdf", btVector3(0, -1.7, 0.64), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, -1.9, 0.7), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("cube_small.urdf", btVector3(0.1, -1.8, 0.7), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("sphere_small.urdf", btVector3(-0.2, -1.7, 0.7), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10)); m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
@ -3162,11 +3165,20 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
static btScalar t=0.f; static btScalar t=0.f;
t+=0.01; t+=0.01;
double dampIk = 0.99; double dampIk = 0.99;
/*
for (int i=0;i<numDofs;i++) for (int i=0;i<numDofs;i++)
{ {
btScalar desiredPosition = btSin(t*0.1)*SIMD_HALF_PI; btScalar desiredPosition = btSin(t*0.1)*SIMD_HALF_PI;
q_new[i] = dampIk*q_current[i]+(1-dampIk)*desiredPosition; q_new[i] = dampIk*q_current[i]+(1-dampIk)*desiredPosition;
} }
*/
q_new[0] = 1.376;
q_new[1] = 1.102;
q_new[2] = 1.634;
q_new[3] = -0.406;
q_new[4] = 1.714;
q_new[5] = -2.023;
q_new[6] = -1.306;
if (closeToKuka) if (closeToKuka)
{ {
@ -3303,6 +3315,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
{ {
btScalar desiredVelocity = 0.f; btScalar desiredVelocity = 0.f;
btScalar desiredPosition = q_new[link]; btScalar desiredPosition = q_new[link];
//printf("link %d: %f", link, q_new[link]);
motor->setVelocityTarget(desiredVelocity,1); motor->setVelocityTarget(desiredVelocity,1);
motor->setPositionTarget(desiredPosition,0.6); motor->setPositionTarget(desiredPosition,0.6);
btScalar maxImp = 1.f; btScalar maxImp = 1.f;