mimicJointConstraint.py creates actual differential drive
See https://www.youtube.com/watch?v=pK3PTPlRTGA :-)
This commit is contained in:
BIN
data/differential/diff_arm.stl
Normal file
BIN
data/differential/diff_arm.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_carrier.stl
Normal file
BIN
data/differential/diff_carrier.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_carrier_cover.stl
Normal file
BIN
data/differential/diff_carrier_cover.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_leftshaft.stl
Normal file
BIN
data/differential/diff_leftshaft.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_motor_cover.stl
Normal file
BIN
data/differential/diff_motor_cover.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_pinion.stl
Normal file
BIN
data/differential/diff_pinion.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_rightshaft.stl
Normal file
BIN
data/differential/diff_rightshaft.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_ring.stl
Normal file
BIN
data/differential/diff_ring.stl
Normal file
Binary file not shown.
198
data/differential/diff_ring.urdf
Normal file
198
data/differential/diff_ring.urdf
Normal file
@@ -0,0 +1,198 @@
|
|||||||
|
|
||||||
|
<?xml version="1.0" ?>
|
||||||
|
<robot name="husky_robot" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
|
<material name="White">
|
||||||
|
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||||
|
</material>
|
||||||
|
<link name="world"/>
|
||||||
|
<link name="diff_ring">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="1.0"/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<stiffness value="30000"/>
|
||||||
|
<damping value="1000"/>
|
||||||
|
</contact>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<mass value="2.637"/>
|
||||||
|
<origin xyz="0 0 0"/>
|
||||||
|
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh scale="0.001 0.001 0.001" filename="differential/diff_ring.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="DarkGrey"/>
|
||||||
|
</visual>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh scale="0.001 0.001 0.001" filename="differential/diff_carrier.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="DarkGrey"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="1.570795 0 0" xyz="0 0.025 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.01" radius="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="diff_ring_world" type="continuous">
|
||||||
|
<parent link="world"/>
|
||||||
|
<child link="diff_ring"/>
|
||||||
|
<origin rpy="0 0 0" xyz="0.256 0.2854 0.03282"/>
|
||||||
|
<axis rpy="0 0 0" xyz="0 1 0"/>
|
||||||
|
</joint>
|
||||||
|
<link name="diff_spiderA">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="1.0"/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<stiffness value="30000"/>
|
||||||
|
<damping value="1000"/>
|
||||||
|
</contact>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<mass value="2.637"/>
|
||||||
|
<origin xyz="0 0 0"/>
|
||||||
|
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="DarkGrey"/>
|
||||||
|
</visual>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.01" radius="0.015"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="diff_spiderA_ring" type="continuous">
|
||||||
|
<parent link="diff_ring"/>
|
||||||
|
<child link="diff_spiderA"/>
|
||||||
|
<origin rpy="0 0 1.570795" xyz="0.0 0.0 0.0"/>
|
||||||
|
<axis rpy="0 0 0" xyz="0 1 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="diff_spiderB">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="1.0"/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<stiffness value="30000"/>
|
||||||
|
<damping value="1000"/>
|
||||||
|
</contact>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<mass value="2.637"/>
|
||||||
|
<origin xyz="0 0 0"/>
|
||||||
|
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="DarkGrey"/>
|
||||||
|
</visual>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.01" radius="0.015"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="diff_spiderB_ring" type="continuous">
|
||||||
|
<parent link="diff_ring"/>
|
||||||
|
<child link="diff_spiderB"/>
|
||||||
|
<origin rpy="0 0 -1.570795" xyz="0.0 0.0 0.0"/>
|
||||||
|
<axis rpy="0 0 0" xyz="0 1 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
<link name="diff_sideA">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="1.0"/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<stiffness value="30000"/>
|
||||||
|
<damping value="1000"/>
|
||||||
|
</contact>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<mass value="2.637"/>
|
||||||
|
<origin xyz="0 0 0"/>
|
||||||
|
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="DarkGrey"/>
|
||||||
|
</visual>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.01" radius="0.015"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="diff_sideA_ring" type="continuous">
|
||||||
|
<parent link="diff_ring"/>
|
||||||
|
<child link="diff_sideA"/>
|
||||||
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||||
|
<axis rpy="0 0 0" xyz="0 1 0"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="diff_sideB">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="1.0"/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<stiffness value="30000"/>
|
||||||
|
<damping value="1000"/>
|
||||||
|
</contact>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<mass value="2.637"/>
|
||||||
|
<origin xyz="0 0 0"/>
|
||||||
|
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="-1.570795 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="DarkGrey"/>
|
||||||
|
</visual>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<origin rpy="-1.570795 0 0" xyz="0 -0.01 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.01" radius="0.015"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="diff_sideB_ring" type="continuous">
|
||||||
|
<parent link="diff_ring"/>
|
||||||
|
<child link="diff_sideB"/>
|
||||||
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
||||||
|
<axis rpy="0 0 0" xyz="0 1 0"/>
|
||||||
|
</joint>
|
||||||
|
</robot>
|
||||||
BIN
data/differential/diff_side.stl
Normal file
BIN
data/differential/diff_side.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_spider.stl
Normal file
BIN
data/differential/diff_spider.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_spider_shaft.stl
Normal file
BIN
data/differential/diff_spider_shaft.stl
Normal file
Binary file not shown.
BIN
data/differential/diff_stand.stl
Normal file
BIN
data/differential/diff_stand.stl
Normal file
Binary file not shown.
2
data/differential/modelorigin.txt
Normal file
2
data/differential/modelorigin.txt
Normal file
@@ -0,0 +1,2 @@
|
|||||||
|
stl files were copied from http://www.otvinta.com/download09.html
|
||||||
|
URDF file was manually created, along with mimicJointConstraint.py
|
||||||
@@ -323,8 +323,10 @@ bool UrdfParser::parseInertia(UrdfInertia& inertia, TiXmlElement* config, ErrorL
|
|||||||
|
|
||||||
bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* logger)
|
bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* logger)
|
||||||
{
|
{
|
||||||
btAssert(g);
|
// btAssert(g);
|
||||||
|
if (g==0)
|
||||||
|
return false;
|
||||||
|
|
||||||
TiXmlElement *shape = g->FirstChildElement();
|
TiXmlElement *shape = g->FirstChildElement();
|
||||||
if (!shape)
|
if (!shape)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -4,13 +4,22 @@
|
|||||||
import pybullet as p
|
import pybullet as p
|
||||||
import time
|
import time
|
||||||
p.connect(p.GUI)
|
p.connect(p.GUI)
|
||||||
wheelA = p.loadURDF("wheel.urdf",[0,0,0])
|
p.loadURDF("plane.urdf",0,0,-2)
|
||||||
wheelB = p.loadURDF("wheel.urdf",[0,0,1])
|
wheelA = p.loadURDF("differential/diff_ring.urdf",[0,0,0])
|
||||||
p.setJointMotorControl2(wheelA,0,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
for i in range(p.getNumJoints(wheelA)):
|
||||||
p.setJointMotorControl2(wheelB,0,p.VELOCITY_CONTROL,targetVelocity=1,force=1)
|
print(p.getJointInfo(wheelA,i))
|
||||||
|
p.setJointMotorControl2(wheelA,i,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
||||||
|
|
||||||
|
|
||||||
|
c = p.createConstraint(wheelA,1,wheelA,3,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||||
|
p.changeConstraint(c,gearRatio=1, maxForce=10000)
|
||||||
|
|
||||||
|
c = p.createConstraint(wheelA,2,wheelA,4,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||||
|
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||||
|
|
||||||
|
c = p.createConstraint(wheelA,1,wheelA,4,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||||
|
p.changeConstraint(c,gearRatio=-1, maxForce=10000)
|
||||||
|
|
||||||
c = p.createConstraint(wheelA,0,wheelB,0,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
|
||||||
p.changeConstraint(c,gearRatio=-0.1, maxForce=10000)
|
|
||||||
|
|
||||||
p.setRealTimeSimulation(1)
|
p.setRealTimeSimulation(1)
|
||||||
while(1):
|
while(1):
|
||||||
|
|||||||
Reference in New Issue
Block a user