mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-19 05:20:06 +00:00
Merge branch 'master' of github.com:erwincoumans/bullet3
This commit is contained in:
commit
75351f3682
@ -11,12 +11,6 @@ matrix:
|
||||
env:
|
||||
- BUILD_NAME=TRUSTY_CLANG
|
||||
- SUDO=sudo
|
||||
- os: linux
|
||||
compiler: gcc
|
||||
env:
|
||||
- BUILD_NAME=XENIAL_GCC
|
||||
- DOCKER_FILE="ubuntu-xenial"
|
||||
services: docker
|
||||
- os: linux
|
||||
compiler: clang
|
||||
env:
|
||||
|
@ -3701,6 +3701,8 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3CreateRaycastCommandInit(b3PhysicsCl
|
||||
command->m_requestRaycastIntersections.m_numCommandRays = 1;
|
||||
command->m_requestRaycastIntersections.m_numStreamingRays = 0;
|
||||
command->m_requestRaycastIntersections.m_numThreads = 1;
|
||||
command->m_requestRaycastIntersections.m_parentObjectUniqueId = -1;
|
||||
command->m_requestRaycastIntersections.m_parentLinkIndex=-1;
|
||||
|
||||
command->m_requestRaycastIntersections.m_numCommandRays = 1;
|
||||
command->m_requestRaycastIntersections.m_fromToRays[0].m_rayFromPosition[0] = rayFromWorldX;
|
||||
|
42
examples/pybullet/examples/deformable_add_remove_objects.py
Normal file
42
examples/pybullet/examples/deformable_add_remove_objects.py
Normal file
@ -0,0 +1,42 @@
|
||||
import pybullet as p
|
||||
physicsClient = p.connect(p.GUI)
|
||||
import pybullet_data
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||
|
||||
gravZ=-10
|
||||
p.setGravity(0, 0, gravZ)
|
||||
|
||||
planeOrn = [0,0,0,1]
|
||||
planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
|
||||
|
||||
def _load_softbody(basePos):
|
||||
return p.loadSoftBody("cloth_z_up.obj", basePosition = basePos, scale = 0.5, mass = 1., useNeoHookean = 0, useBendingSprings=1,useMassSpring=1, springElasticStiffness=40, springDampingStiffness=.1, springDampingAllDirections = 1, useSelfCollision = 0, frictionCoeff = .5, useFaceContact=1, collisionMargin = 0.04)
|
||||
|
||||
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
|
||||
|
||||
#load two objects and step
|
||||
cloth1 = _load_softbody([0,0,1])
|
||||
cloth2 = _load_softbody([0,1,0])
|
||||
|
||||
for i in range(300):
|
||||
p.stepSimulation()
|
||||
|
||||
# remove one object, add two and then step
|
||||
p.removeBody(cloth2)
|
||||
_load_softbody([0,1,1])
|
||||
_load_softbody([0,-1,1])
|
||||
|
||||
for i in range(300):
|
||||
p.stepSimulation()
|
||||
|
||||
# reset simulation, add objects then step
|
||||
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||
p.setGravity(0, 0, gravZ)
|
||||
planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
|
||||
_load_softbody([0,1,0])
|
||||
_load_softbody([0,1,1])
|
||||
|
||||
while p.isConnected():
|
||||
p.stepSimulation()
|
375
examples/pybullet/gym/pybullet_data/a1/LICENSE
Normal file
375
examples/pybullet/gym/pybullet_data/a1/LICENSE
Normal file
@ -0,0 +1,375 @@
|
||||
|
||||
Mozilla Public License Version 2.0
|
||||
==================================
|
||||
|
||||
1. Definitions
|
||||
--------------
|
||||
|
||||
1.1. "Contributor"
|
||||
means each individual or legal entity that creates, contributes to
|
||||
the creation of, or owns Covered Software.
|
||||
|
||||
1.2. "Contributor Version"
|
||||
means the combination of the Contributions of others (if any) used
|
||||
by a Contributor and that particular Contributor's Contribution.
|
||||
|
||||
1.3. "Contribution"
|
||||
means Covered Software of a particular Contributor.
|
||||
|
||||
1.4. "Covered Software"
|
||||
means Source Code Form to which the initial Contributor has attached
|
||||
the notice in Exhibit A, the Executable Form of such Source Code
|
||||
Form, and Modifications of such Source Code Form, in each case
|
||||
including portions thereof.
|
||||
|
||||
1.5. "Incompatible With Secondary Licenses"
|
||||
means
|
||||
|
||||
(a) that the initial Contributor has attached the notice described
|
||||
in Exhibit B to the Covered Software; or
|
||||
|
||||
(b) that the Covered Software was made available under the terms of
|
||||
version 1.1 or earlier of the License, but not also under the
|
||||
terms of a Secondary License.
|
||||
|
||||
1.6. "Executable Form"
|
||||
means any form of the work other than Source Code Form.
|
||||
|
||||
1.7. "Larger Work"
|
||||
means a work that combines Covered Software with other material, in
|
||||
a separate file or files, that is not Covered Software.
|
||||
|
||||
1.8. "License"
|
||||
means this document.
|
||||
|
||||
1.9. "Licensable"
|
||||
means having the right to grant, to the maximum extent possible,
|
||||
whether at the time of the initial grant or subsequently, any and
|
||||
all of the rights conveyed by this License.
|
||||
|
||||
1.10. "Modifications"
|
||||
means any of the following:
|
||||
|
||||
(a) any file in Source Code Form that results from an addition to,
|
||||
deletion from, or modification of the contents of Covered
|
||||
Software; or
|
||||
|
||||
(b) any new file in Source Code Form that contains any Covered
|
||||
Software.
|
||||
|
||||
1.11. "Patent Claims" of a Contributor
|
||||
means any patent claim(s), including without limitation, method,
|
||||
process, and apparatus claims, in any patent Licensable by such
|
||||
Contributor that would be infringed, but for the grant of the
|
||||
License, by the making, using, selling, offering for sale, having
|
||||
made, import, or transfer of either its Contributions or its
|
||||
Contributor Version.
|
||||
|
||||
1.12. "Secondary License"
|
||||
means either the GNU General Public License, Version 2.0, the GNU
|
||||
Lesser General Public License, Version 2.1, the GNU Affero General
|
||||
Public License, Version 3.0, or any later versions of those
|
||||
licenses.
|
||||
|
||||
1.13. "Source Code Form"
|
||||
means the form of the work preferred for making modifications.
|
||||
|
||||
1.14. "You" (or "Your")
|
||||
means an individual or a legal entity exercising rights under this
|
||||
License. For legal entities, "You" includes any entity that
|
||||
controls, is controlled by, or is under common control with You. For
|
||||
purposes of this definition, "control" means (a) the power, direct
|
||||
or indirect, to cause the direction or management of such entity,
|
||||
whether by contract or otherwise, or (b) ownership of more than
|
||||
fifty percent (50%) of the outstanding shares or beneficial
|
||||
ownership of such entity.
|
||||
|
||||
2. License Grants and Conditions
|
||||
--------------------------------
|
||||
|
||||
2.1. Grants
|
||||
|
||||
Each Contributor hereby grants You a world-wide, royalty-free,
|
||||
non-exclusive license:
|
||||
|
||||
(a) under intellectual property rights (other than patent or trademark)
|
||||
Licensable by such Contributor to use, reproduce, make available,
|
||||
modify, display, perform, distribute, and otherwise exploit its
|
||||
Contributions, either on an unmodified basis, with Modifications, or
|
||||
as part of a Larger Work; and
|
||||
|
||||
(b) under Patent Claims of such Contributor to make, use, sell, offer
|
||||
for sale, have made, import, and otherwise transfer either its
|
||||
Contributions or its Contributor Version.
|
||||
|
||||
2.2. Effective Date
|
||||
|
||||
The licenses granted in Section 2.1 with respect to any Contribution
|
||||
become effective for each Contribution on the date the Contributor first
|
||||
distributes such Contribution.
|
||||
|
||||
2.3. Limitations on Grant Scope
|
||||
|
||||
The licenses granted in this Section 2 are the only rights granted under
|
||||
this License. No additional rights or licenses will be implied from the
|
||||
distribution or licensing of Covered Software under this License.
|
||||
Notwithstanding Section 2.1(b) above, no patent license is granted by a
|
||||
Contributor:
|
||||
|
||||
(a) for any code that a Contributor has removed from Covered Software;
|
||||
or
|
||||
|
||||
(b) for infringements caused by: (i) Your and any other third party's
|
||||
modifications of Covered Software, or (ii) the combination of its
|
||||
Contributions with other software (except as part of its Contributor
|
||||
Version); or
|
||||
|
||||
(c) under Patent Claims infringed by Covered Software in the absence of
|
||||
its Contributions.
|
||||
|
||||
This License does not grant any rights in the trademarks, service marks,
|
||||
or logos of any Contributor (except as may be necessary to comply with
|
||||
the notice requirements in Section 3.4).
|
||||
|
||||
2.4. Subsequent Licenses
|
||||
|
||||
No Contributor makes additional grants as a result of Your choice to
|
||||
distribute the Covered Software under a subsequent version of this
|
||||
License (see Section 10.2) or under the terms of a Secondary License (if
|
||||
permitted under the terms of Section 3.3).
|
||||
|
||||
2.5. Representation
|
||||
|
||||
Each Contributor represents that the Contributor believes its
|
||||
Contributions are its original creation(s) or it has sufficient rights
|
||||
to grant the rights to its Contributions conveyed by this License.
|
||||
|
||||
2.6. Fair Use
|
||||
|
||||
This License is not intended to limit any rights You have under
|
||||
applicable copyright doctrines of fair use, fair dealing, or other
|
||||
equivalents.
|
||||
|
||||
2.7. Conditions
|
||||
|
||||
Sections 3.1, 3.2, 3.3, and 3.4 are conditions of the licenses granted
|
||||
in Section 2.1.
|
||||
|
||||
3. Responsibilities
|
||||
-------------------
|
||||
|
||||
3.1. Distribution of Source Form
|
||||
|
||||
All distribution of Covered Software in Source Code Form, including any
|
||||
Modifications that You create or to which You contribute, must be under
|
||||
the terms of this License. You must inform recipients that the Source
|
||||
Code Form of the Covered Software is governed by the terms of this
|
||||
License, and how they can obtain a copy of this License. You may not
|
||||
attempt to alter or restrict the recipients' rights in the Source Code
|
||||
Form.
|
||||
|
||||
3.2. Distribution of Executable Form
|
||||
|
||||
If You distribute Covered Software in Executable Form then:
|
||||
|
||||
(a) such Covered Software must also be made available in Source Code
|
||||
Form, as described in Section 3.1, and You must inform recipients of
|
||||
the Executable Form how they can obtain a copy of such Source Code
|
||||
Form by reasonable means in a timely manner, at a charge no more
|
||||
than the cost of distribution to the recipient; and
|
||||
|
||||
(b) You may distribute such Executable Form under the terms of this
|
||||
License, or sublicense it under different terms, provided that the
|
||||
license for the Executable Form does not attempt to limit or alter
|
||||
the recipients' rights in the Source Code Form under this License.
|
||||
|
||||
3.3. Distribution of a Larger Work
|
||||
|
||||
You may create and distribute a Larger Work under terms of Your choice,
|
||||
provided that You also comply with the requirements of this License for
|
||||
the Covered Software. If the Larger Work is a combination of Covered
|
||||
Software with a work governed by one or more Secondary Licenses, and the
|
||||
Covered Software is not Incompatible With Secondary Licenses, this
|
||||
License permits You to additionally distribute such Covered Software
|
||||
under the terms of such Secondary License(s), so that the recipient of
|
||||
the Larger Work may, at their option, further distribute the Covered
|
||||
Software under the terms of either this License or such Secondary
|
||||
License(s).
|
||||
|
||||
3.4. Notices
|
||||
|
||||
You may not remove or alter the substance of any license notices
|
||||
(including copyright notices, patent notices, disclaimers of warranty,
|
||||
or limitations of liability) contained within the Source Code Form of
|
||||
the Covered Software, except that You may alter any license notices to
|
||||
the extent required to remedy known factual inaccuracies.
|
||||
|
||||
3.5. Application of Additional Terms
|
||||
|
||||
You may choose to offer, and to charge a fee for, warranty, support,
|
||||
indemnity or liability obligations to one or more recipients of Covered
|
||||
Software. However, You may do so only on Your own behalf, and not on
|
||||
behalf of any Contributor. You must make it absolutely clear that any
|
||||
such warranty, support, indemnity, or liability obligation is offered by
|
||||
You alone, and You hereby agree to indemnify every Contributor for any
|
||||
liability incurred by such Contributor as a result of warranty, support,
|
||||
indemnity or liability terms You offer. You may include additional
|
||||
disclaimers of warranty and limitations of liability specific to any
|
||||
jurisdiction.
|
||||
|
||||
4. Inability to Comply Due to Statute or Regulation
|
||||
---------------------------------------------------
|
||||
|
||||
If it is impossible for You to comply with any of the terms of this
|
||||
License with respect to some or all of the Covered Software due to
|
||||
statute, judicial order, or regulation then You must: (a) comply with
|
||||
the terms of this License to the maximum extent possible; and (b)
|
||||
describe the limitations and the code they affect. Such description must
|
||||
be placed in a text file included with all distributions of the Covered
|
||||
Software under this License. Except to the extent prohibited by statute
|
||||
or regulation, such description must be sufficiently detailed for a
|
||||
recipient of ordinary skill to be able to understand it.
|
||||
|
||||
5. Termination
|
||||
--------------
|
||||
|
||||
5.1. The rights granted under this License will terminate automatically
|
||||
if You fail to comply with any of its terms. However, if You become
|
||||
compliant, then the rights granted under this License from a particular
|
||||
Contributor are reinstated (a) provisionally, unless and until such
|
||||
Contributor explicitly and finally terminates Your grants, and (b) on an
|
||||
ongoing basis, if such Contributor fails to notify You of the
|
||||
non-compliance by some reasonable means prior to 60 days after You have
|
||||
come back into compliance. Moreover, Your grants from a particular
|
||||
Contributor are reinstated on an ongoing basis if such Contributor
|
||||
notifies You of the non-compliance by some reasonable means, this is the
|
||||
first time You have received notice of non-compliance with this License
|
||||
from such Contributor, and You become compliant prior to 30 days after
|
||||
Your receipt of the notice.
|
||||
|
||||
5.2. If You initiate litigation against any entity by asserting a patent
|
||||
infringement claim (excluding declaratory judgment actions,
|
||||
counter-claims, and cross-claims) alleging that a Contributor Version
|
||||
directly or indirectly infringes any patent, then the rights granted to
|
||||
You by any and all Contributors for the Covered Software under Section
|
||||
2.1 of this License shall terminate.
|
||||
|
||||
5.3. In the event of termination under Sections 5.1 or 5.2 above, all
|
||||
end user license agreements (excluding distributors and resellers) which
|
||||
have been validly granted by You or Your distributors under this License
|
||||
prior to termination shall survive termination.
|
||||
|
||||
************************************************************************
|
||||
* *
|
||||
* 6. Disclaimer of Warranty *
|
||||
* ------------------------- *
|
||||
* *
|
||||
* Covered Software is provided under this License on an "as is" *
|
||||
* basis, without warranty of any kind, either expressed, implied, or *
|
||||
* statutory, including, without limitation, warranties that the *
|
||||
* Covered Software is free of defects, merchantable, fit for a *
|
||||
* particular purpose or non-infringing. The entire risk as to the *
|
||||
* quality and performance of the Covered Software is with You. *
|
||||
* Should any Covered Software prove defective in any respect, You *
|
||||
* (not any Contributor) assume the cost of any necessary servicing, *
|
||||
* repair, or correction. This disclaimer of warranty constitutes an *
|
||||
* essential part of this License. No use of any Covered Software is *
|
||||
* authorized under this License except under this disclaimer. *
|
||||
* *
|
||||
************************************************************************
|
||||
|
||||
************************************************************************
|
||||
* *
|
||||
* 7. Limitation of Liability *
|
||||
* -------------------------- *
|
||||
* *
|
||||
* Under no circumstances and under no legal theory, whether tort *
|
||||
* (including negligence), contract, or otherwise, shall any *
|
||||
* Contributor, or anyone who distributes Covered Software as *
|
||||
* permitted above, be liable to You for any direct, indirect, *
|
||||
* special, incidental, or consequential damages of any character *
|
||||
* including, without limitation, damages for lost profits, loss of *
|
||||
* goodwill, work stoppage, computer failure or malfunction, or any *
|
||||
* and all other commercial damages or losses, even if such party *
|
||||
* shall have been informed of the possibility of such damages. This *
|
||||
* limitation of liability shall not apply to liability for death or *
|
||||
* personal injury resulting from such party's negligence to the *
|
||||
* extent applicable law prohibits such limitation. Some *
|
||||
* jurisdictions do not allow the exclusion or limitation of *
|
||||
* incidental or consequential damages, so this exclusion and *
|
||||
* limitation may not apply to You. *
|
||||
* *
|
||||
************************************************************************
|
||||
|
||||
8. Litigation
|
||||
-------------
|
||||
|
||||
Any litigation relating to this License may be brought only in the
|
||||
courts of a jurisdiction where the defendant maintains its principal
|
||||
place of business and such litigation shall be governed by laws of that
|
||||
jurisdiction, without reference to its conflict-of-law provisions.
|
||||
Nothing in this Section shall prevent a party's ability to bring
|
||||
cross-claims or counter-claims.
|
||||
|
||||
9. Miscellaneous
|
||||
----------------
|
||||
|
||||
This License represents the complete agreement concerning the subject
|
||||
matter hereof. If any provision of this License is held to be
|
||||
unenforceable, such provision shall be reformed only to the extent
|
||||
necessary to make it enforceable. Any law or regulation which provides
|
||||
that the language of a contract shall be construed against the drafter
|
||||
shall not be used to construe this License against a Contributor.
|
||||
|
||||
10. Versions of the License
|
||||
---------------------------
|
||||
|
||||
10.1. New Versions
|
||||
|
||||
Mozilla Foundation is the license steward. Except as provided in Section
|
||||
10.3, no one other than the license steward has the right to modify or
|
||||
publish new versions of this License. Each version will be given a
|
||||
distinguishing version number.
|
||||
|
||||
10.2. Effect of New Versions
|
||||
|
||||
You may distribute the Covered Software under the terms of the version
|
||||
of the License under which You originally received the Covered Software,
|
||||
or under the terms of any subsequent version published by the license
|
||||
steward.
|
||||
|
||||
10.3. Modified Versions
|
||||
|
||||
If you create software not governed by this License, and you want to
|
||||
create a new license for such software, you may create and use a
|
||||
modified version of this License if you rename the license and remove
|
||||
any references to the name of the license steward (except to note that
|
||||
such modified license differs from this License).
|
||||
|
||||
10.4. Distributing Source Code Form that is Incompatible With Secondary
|
||||
Licenses
|
||||
|
||||
If You choose to distribute Source Code Form that is Incompatible With
|
||||
Secondary Licenses under the terms of this version of the License, the
|
||||
notice described in Exhibit B of this License must be attached.
|
||||
|
||||
Exhibit A - Source Code Form License Notice
|
||||
-------------------------------------------
|
||||
|
||||
This Source Code Form is subject to the terms of the Mozilla Public
|
||||
License, v. 2.0. If a copy of the MPL was not distributed with this
|
||||
file, You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
|
||||
If it is not possible or desirable to put the notice in a particular
|
||||
file, then You may include the notice in a location (such as a LICENSE
|
||||
file in a relevant directory) where a recipient would be likely to look
|
||||
for such a notice.
|
||||
|
||||
You may add additional accurate notices of copyright ownership.
|
||||
|
||||
Exhibit B - "Incompatible With Secondary Licenses" Notice
|
||||
---------------------------------------------------------
|
||||
|
||||
This Source Code Form is "Incompatible With Secondary Licenses", as
|
||||
defined by the Mozilla Public License, v. 2.0.
|
||||
|
58
examples/pybullet/gym/pybullet_data/a1/a1.py
Normal file
58
examples/pybullet/gym/pybullet_data/a1/a1.py
Normal file
@ -0,0 +1,58 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data as pd
|
||||
import numpy as np
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
dt = 1./240.
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
p.loadURDF("plane.urdf")
|
||||
robot = p.loadURDF("a1/a1.urdf",[0,0,0.5])
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
p.setGravity(0,0,-9.8)
|
||||
|
||||
A1_DEFAULT_ABDUCTION_ANGLE = 0
|
||||
A1_DEFAULT_HIP_ANGLE = 0.9
|
||||
A1_DEFAULT_KNEE_ANGLE = -1.8
|
||||
NUM_LEGS = 4
|
||||
INIT_MOTOR_ANGLES = np.array([
|
||||
A1_DEFAULT_ABDUCTION_ANGLE,
|
||||
A1_DEFAULT_HIP_ANGLE,
|
||||
A1_DEFAULT_KNEE_ANGLE
|
||||
] * NUM_LEGS)
|
||||
|
||||
MOTOR_NAMES = [
|
||||
"FR_hip_joint",
|
||||
"FR_upper_joint",
|
||||
"FR_lower_joint",
|
||||
"FL_hip_joint",
|
||||
"FL_upper_joint",
|
||||
"FL_lower_joint",
|
||||
"RR_hip_joint",
|
||||
"RR_upper_joint",
|
||||
"RR_lower_joint",
|
||||
"RL_hip_joint",
|
||||
"RL_upper_joint",
|
||||
"RL_lower_joint",
|
||||
]
|
||||
motor_ids = []
|
||||
|
||||
for j in range (p.getNumJoints(robot)):
|
||||
joint_info = p.getJointInfo(robot,j)
|
||||
name = joint_info[1].decode('utf-8')
|
||||
print("joint_info[1]=",name)
|
||||
if name in MOTOR_NAMES:
|
||||
motor_ids.append(j)
|
||||
|
||||
for index in range (12):
|
||||
joint_id = motor_ids[index]
|
||||
p.setJointMotorControl2(robot, joint_id, p.POSITION_CONTROL, INIT_MOTOR_ANGLES[index])
|
||||
p.resetJointState(robot, joint_id, INIT_MOTOR_ANGLES[index])
|
||||
|
||||
print("motor_ids=",motor_ids)
|
||||
while p.isConnected():
|
||||
p.stepSimulation()
|
||||
time.sleep(dt)
|
||||
|
||||
|
688
examples/pybullet/gym/pybullet_data/a1/a1.urdf
Normal file
688
examples/pybullet/gym/pybullet_data/a1/a1.urdf
Normal file
@ -0,0 +1,688 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="a1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/trunk.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.267 0.194 0.114"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.012731 0.002186 0.000515"/>
|
||||
<mass value="4.713"/>
|
||||
<inertia ixx="0.01683993" ixy="8.3902e-05" ixz="0.000597679" iyy="0.056579028" iyz="2.5134e-05" izz="0.064713601"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.183 -0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/hip.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003311 -0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_upper_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FR_upper_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_upper_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08505 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_upper"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FR_upper">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/thigh_mirror.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_lower_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FR_upper"/>
|
||||
<child link="FR_lower"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FR_lower">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/calf.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_toe_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FR_lower"/>
|
||||
<child link="FR_toe"/>
|
||||
</joint>
|
||||
<link name="FR_toe">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_upper_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_upper_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_upper_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_lower_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_lower_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_lower_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="FL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.183 0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/hip.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003311 0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_upper_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FL_upper_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FL_upper_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.08505 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_upper"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FL_upper">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/thigh.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_lower_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FL_upper"/>
|
||||
<child link="FL_lower"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="FL_lower">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/calf.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_toe_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="FL_lower"/>
|
||||
<child link="FL_toe"/>
|
||||
</joint>
|
||||
<link name="FL_toe">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_upper_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_upper_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_upper_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_lower_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_lower_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_lower_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.183 -0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/hip.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.003311 -0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_upper_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RR_upper_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RR_upper_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08505 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_upper"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RR_upper">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/thigh_mirror.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_lower_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RR_upper"/>
|
||||
<child link="RR_lower"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RR_lower">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/calf.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_toe_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RR_lower"/>
|
||||
<child link="RR_toe"/>
|
||||
</joint>
|
||||
<link name="RR_toe">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_upper_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_upper_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_upper_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_lower_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_lower_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_lower_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.183 0.047 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/hip.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.003311 0.000635 3.1e-05"/>
|
||||
<mass value="0.696"/>
|
||||
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_upper_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RL_upper_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RL_upper_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.08505 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_upper"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RL_upper">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/thigh.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
|
||||
<mass value="1.013"/>
|
||||
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_lower_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RL_upper"/>
|
||||
<child link="RL_lower"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
|
||||
</joint>
|
||||
<link name="RL_lower">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/calf.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
|
||||
<geometry>
|
||||
<box size="0.2 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
|
||||
<mass value="0.166"/>
|
||||
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_toe_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
|
||||
<parent link="RL_lower"/>
|
||||
<child link="RL_toe"/>
|
||||
</joint>
|
||||
<link name="RL_toe">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_upper_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_upper_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_upper_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_lower_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_lower_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_lower_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</robot>
|
||||
|
12
examples/pybullet/gym/pybullet_data/a1/meshes/calf.mtl
Normal file
12
examples/pybullet/gym/pybullet_data/a1/meshes/calf.mtl
Normal file
@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl 材质
|
||||
Ns 96.078431
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.900000 0.900000 0.900000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
13564
examples/pybullet/gym/pybullet_data/a1/meshes/calf.obj
Normal file
13564
examples/pybullet/gym/pybullet_data/a1/meshes/calf.obj
Normal file
File diff suppressed because it is too large
Load Diff
12
examples/pybullet/gym/pybullet_data/a1/meshes/hip.mtl
Normal file
12
examples/pybullet/gym/pybullet_data/a1/meshes/hip.mtl
Normal file
@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl 材质.001
|
||||
Ns 96.078431
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.400000 0.400000 0.400000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
5219
examples/pybullet/gym/pybullet_data/a1/meshes/hip.obj
Normal file
5219
examples/pybullet/gym/pybullet_data/a1/meshes/hip.obj
Normal file
File diff suppressed because it is too large
Load Diff
12
examples/pybullet/gym/pybullet_data/a1/meshes/thigh.mtl
Normal file
12
examples/pybullet/gym/pybullet_data/a1/meshes/thigh.mtl
Normal file
@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl 材质.002
|
||||
Ns 96.078431
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.400000 0.400000 0.400000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
8971
examples/pybullet/gym/pybullet_data/a1/meshes/thigh.obj
Normal file
8971
examples/pybullet/gym/pybullet_data/a1/meshes/thigh.obj
Normal file
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl 材质.003
|
||||
Ns 96.078431
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.400000 0.400000 0.400000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
9318
examples/pybullet/gym/pybullet_data/a1/meshes/thigh_mirror.obj
Normal file
9318
examples/pybullet/gym/pybullet_data/a1/meshes/thigh_mirror.obj
Normal file
File diff suppressed because it is too large
Load Diff
13
examples/pybullet/gym/pybullet_data/a1/meshes/trunk.mtl
Normal file
13
examples/pybullet/gym/pybullet_data/a1/meshes/trunk.mtl
Normal file
@ -0,0 +1,13 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl 材质.004
|
||||
Ns 96.078431
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.640000 0.640000 0.640000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
map_Kd trunk_A1.png
|
83622
examples/pybullet/gym/pybullet_data/a1/meshes/trunk.obj
Normal file
83622
examples/pybullet/gym/pybullet_data/a1/meshes/trunk.obj
Normal file
File diff suppressed because it is too large
Load Diff
BIN
examples/pybullet/gym/pybullet_data/a1/meshes/trunk_A1.png
Normal file
BIN
examples/pybullet/gym/pybullet_data/a1/meshes/trunk_A1.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 70 KiB |
63
examples/pybullet/gym/pybullet_data/quadruped/spirit40.py
Normal file
63
examples/pybullet/gym/pybullet_data/quadruped/spirit40.py
Normal file
@ -0,0 +1,63 @@
|
||||
from __future__ import print_function
|
||||
import time
|
||||
import numpy as np
|
||||
import argparse
|
||||
|
||||
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data as pd
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
dt = 1./240.
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
p.loadURDF("plane.urdf")
|
||||
robot = p.loadURDF("quadruped/spirit40.urdf",[0,0,.5], useFixedBase=False)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
p.setGravity(0,0,-9.8)
|
||||
|
||||
|
||||
#j= (0, b'8', 0, 7, 6, 1, 0.0, 0.0, -0.707, 0.707, 40.0, 30.0, b'hip0', (1.0, 0.0, 0.0), (0.2263, 0.07, 0.0), (0.0, 0.0, 0.0, 1.0), -1)
|
||||
#j= (1, b'0', 0, 8, 7, 1, 0.0, 0.0, -6.28318530718, 6.28318530718, 40.0, 30.0, b'upper0', (0.0, -1.0, 0.0), (0.0, 0.10098, 0.0), (0.0, 0.0, 0.0, 1.0), 0)
|
||||
#j= (2, b'1', 0, 9, 8, 1, 0.0, 0.0, 0.0, 3.14159265359, 40.0, 30.0, b'lower0', (0.0, 1.0, 0.0), (-0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 1)
|
||||
#j= (3, b'jtoe0', 4, -1, -1, 0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'toe0', (0.0, 0.0, 0.0), (0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 2)
|
||||
#j= (4, b'9', 0, 10, 9, 1, 0.0, 0.0, -0.707, 0.707, 40.0, 30.0, b'hip1', (1.0, 0.0, 0.0), (-0.2263, 0.07, 0.0), (0.0, 0.0, 0.0, 1.0), -1)
|
||||
#j= (5, b'2', 0, 11, 10, 1, 0.0, 0.0, -6.28318530718, 6.28318530718, 40.0, 30.0, b'upper1', (0.0, -1.0, 0.0), (0.0, 0.10098, 0.0), (0.0, 0.0, 0.0, 1.0), 4)
|
||||
#j= (6, b'3', 0, 12, 11, 1, 0.0, 0.0, 0.0, 3.14159265359, 40.0, 30.0, b'lower1', (0.0, 1.0, 0.0), (-0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 5)
|
||||
#j= (7, b'jtoe1', 4, -1, -1, 0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'toe1', (0.0, 0.0, 0.0), (0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 6)
|
||||
#j= (8, b'10', 0, 13, 12, 1, 0.0, 0.0, -0.707, 0.707, 40.0, 30.0, b'hip2', (1.0, 0.0, 0.0), (0.2263, -0.07, 0.0), (0.0, 0.0, 0.0, 1.0), -1)
|
||||
#j= (9, b'4', 0, 14, 13, 1, 0.0, 0.0, -6.28318530718, 6.28318530718, 40.0, 30.0, b'upper2', (0.0, -1.0, 0.0), (0.0, -0.10098, 0.0), (0.0, 0.0, 0.0, 1.0), 8)
|
||||
#j= (10, b'5', 0, 15, 14, 1, 0.0, 0.0, 0.0, 3.14159265359, 40.0, 30.0, b'lower2', (0.0, 1.0, 0.0), (-0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 9)
|
||||
#j= (11, b'jtoe2', 4, -1, -1, 0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'toe2', (0.0, 0.0, 0.0), (0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 10)
|
||||
#j= (12, b'11', 0, 16, 15, 1, 0.0, 0.0, -0.707, 0.707, 40.0, 30.0, b'hip3', (1.0, 0.0, 0.0), (-0.2263, -0.07, 0.0), (0.0, 0.0, 0.0, 1.0), -1)
|
||||
#j= (13, b'6', 0, 17, 16, 1, 0.0, 0.0, -6.28318530718, 6.28318530718, 40.0, 30.0, b'upper3', (0.0, -1.0, 0.0), (0.0, -0.10098, 0.0), (0.0, 0.0, 0.0, 1.0), 12)
|
||||
#j= (14, b'7', 0, 18, 17, 1, 0.0, 0.0, 0.0, 3.14159265359, 40.0, 30.0, b'lower3', (0.0, 1.0, 0.0), (-0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 13)
|
||||
#j= (15, b'jtoe3', 4, -1, -1, 0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'toe3', (0.0, 0.0, 0.0), (0.206, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), 14)
|
||||
|
||||
toes=[3,7,11,15]
|
||||
revolute_joints=[1,2, 5,6, 9,10, 13,14, 0, 4, 8, 12]
|
||||
|
||||
joint_positions = [0.11321902, 0.1833849, 0.11935401, 0.1723926, 0.13162422, 0.2013433,
|
||||
0.09736967, 0.16855788, -0.08001328, -0.140342, 0.0006392, 0.11989117]
|
||||
|
||||
|
||||
joint_positions = [0.74833727, 1.4664032, 0.76712584, 1.4589894, 0.74642015, 1.4782903,
|
||||
0.7488482, 1.4464638 , -0.01239824 ,-0.02952504, 0.02939725, 0.05764484]
|
||||
|
||||
for j in range (p.getNumJoints(robot)):
|
||||
print("j=", p.getJointInfo(robot,j))
|
||||
|
||||
for j in range (12):
|
||||
joint_index = revolute_joints[j]
|
||||
print("revolute_joint index=", joint_index)
|
||||
p.resetJointState(robot, joint_index, joint_positions[j])
|
||||
p.setJointMotorControl(robot,joint_index,p.POSITION_CONTROL, joint_positions[j])
|
||||
|
||||
count = 0
|
||||
while p.isConnected():
|
||||
count+=1
|
||||
p.stepSimulation()
|
||||
time.sleep(dt)
|
||||
print("sitting!")
|
||||
|
580
examples/pybullet/gym/pybullet_data/quadruped/spirit40.urdf
Normal file
580
examples/pybullet/gym/pybullet_data/quadruped/spirit40.urdf
Normal file
@ -0,0 +1,580 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from spirit.urdf.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<!--
|
||||
MIT License (modified)
|
||||
|
||||
Copyright (c) 2020 Ghost Robotics
|
||||
Authors:
|
||||
Avik De <avik@ghostrobotics.io>
|
||||
Tom Jacobs <tom.jacobs@ghostrobotics.io>
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
of this **file** (the "Software"), to deal
|
||||
in the Software without restriction, including without limitation the rights
|
||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all
|
||||
copies or substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
SOFTWARE.
|
||||
-->
|
||||
<robot name="ngr" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<!-- Define parameters -->
|
||||
<!-- bodyLength + hipdx should be equal to front to back hip distance -->
|
||||
<!-- dy + dPodAxisToEdge + upperLegWidth should be equal to the center to toe distance along y axis-->
|
||||
<!-- guess -->
|
||||
<!-- guess -->
|
||||
<!-- guess -->
|
||||
<!-- guess -->
|
||||
<!-- guess -->
|
||||
<!-- guess -->
|
||||
<!--visual only-->
|
||||
<!--center of pod cylinder to the ab axis-->
|
||||
<!-- Define materials -->
|
||||
<material name="darkgray">
|
||||
<color rgba="0.1 0.1 0.1 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.3 0.3 0.3 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.2 1.0"/>
|
||||
</material>
|
||||
<!-- Body -->
|
||||
<link name="body">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.335 0.24 0.104"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="5.75"/>
|
||||
<!-- Uniform box -->
|
||||
<!-- <inertia ixx="1/12*${bodyMass}*(${bodyWidth}*${bodyWidth} + ${bodyHeight}*${bodyHeight})" ixy="0" ixz="0" iyy="1/12*${bodyMass}*(${bodyLength}*${bodyLength} + ${bodyHeight}*${bodyHeight})" iyz="0" izz="1/12*${bodyMass}*(${bodyLength}*${bodyLength} + ${bodyWidth}*${bodyWidth})"/> -->
|
||||
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
|
||||
</inertial>
|
||||
<!-- Just copy geometry for collision -->
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.335 0.24 0.104"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!-- Define our leg macro -->
|
||||
<!-- Our four legs -->
|
||||
<!-- Hip motor -->
|
||||
<link name="hip0">
|
||||
<visual>
|
||||
<origin rpy="1.5707963268 0 0" xyz="0.0 0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963268 0 0" xyz="0 0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.575"/>
|
||||
<!-- <inertia ixx="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" ixy="0" ixz="0" iyy="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" iyz="0" izz="1/2*${podMass}*${podRadius}*$
|
||||
{podRadius}" /> -->
|
||||
<inertia ixx="0.00066963541" ixy="0" ixz="0" iyy="0.00066963541" iyz="0" izz="0.0008696875"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Abduction joint. Joint names are: 8 9 10 11 -->
|
||||
<joint name="8" type="revolute">
|
||||
<parent link="body"/>
|
||||
<child link="hip0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin xyz="0.2263 0.07 0"/>
|
||||
<limit effort="40" lower="-0.707" upper="0.707" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Upper leg -->
|
||||
<link name="upper0">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.103 -0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="-0.103 -0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.775"/>
|
||||
<inertia ixx="5e-05" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 -->
|
||||
<joint name="0" type="revolute">
|
||||
<parent link="hip0"/>
|
||||
<child link="upper0"/>
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin xyz="0.0 0.10098 0"/>
|
||||
<!-- rpy="0 -0.3 0" -->
|
||||
<limit effort="40" lower="-6.28318530718" upper="6.28318530718" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Lower leg -->
|
||||
<link name="lower0">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.075"/>
|
||||
<inertia ixx="5e-06" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Knee joint. Joint names are: 1 3 5 7 -->
|
||||
<joint name="1" type="revolute">
|
||||
<parent link="upper0"/>
|
||||
<child link="lower0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<origin xyz="-0.206 0 0"/>
|
||||
<!--rpy="0 0.5 0"-->
|
||||
<limit effort="40" lower="0" upper="3.14159265359" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Toe -->
|
||||
<link name="toe0">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.015"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
<!-- <inertia ixx="2/5*${toeMass}*${toeRadius}*${toeRadius}" ixy="0" ixz="0" iyy="2/5*${toeMass}*${toeRadius}*${toeRadius}" iyz="0" izz="2/5*${toeMass}*${toeRadius}*${toeRadius}" /> -->
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoe0" type="fixed">
|
||||
<parent link="lower0"/>
|
||||
<child link="toe0"/>
|
||||
<origin xyz="0.206 0 -0.0"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Hip motor -->
|
||||
<link name="hip1">
|
||||
<visual>
|
||||
<origin rpy="1.5707963268 0 0" xyz="-0.0 0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963268 0 0" xyz="0 0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.575"/>
|
||||
<!-- <inertia ixx="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" ixy="0" ixz="0" iyy="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" iyz="0" izz="1/2*${podMass}*${podRadius}*$
|
||||
{podRadius}" /> -->
|
||||
<inertia ixx="0.00066963541" ixy="0" ixz="0" iyy="0.00066963541" iyz="0" izz="0.0008696875"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Abduction joint. Joint names are: 8 9 10 11 -->
|
||||
<joint name="9" type="revolute">
|
||||
<parent link="body"/>
|
||||
<child link="hip1"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin xyz="-0.2263 0.07 0"/>
|
||||
<limit effort="40" lower="-0.707" upper="0.707" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Upper leg -->
|
||||
<link name="upper1">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.103 -0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="-0.103 -0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.775"/>
|
||||
<inertia ixx="5e-05" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 -->
|
||||
<joint name="2" type="revolute">
|
||||
<parent link="hip1"/>
|
||||
<child link="upper1"/>
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin xyz="-0.0 0.10098 0"/>
|
||||
<!-- rpy="0 -0.3 0" -->
|
||||
<limit effort="40" lower="-6.28318530718" upper="6.28318530718" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Lower leg -->
|
||||
<link name="lower1">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.075"/>
|
||||
<inertia ixx="5e-06" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Knee joint. Joint names are: 1 3 5 7 -->
|
||||
<joint name="3" type="revolute">
|
||||
<parent link="upper1"/>
|
||||
<child link="lower1"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<origin xyz="-0.206 0 0"/>
|
||||
<!--rpy="0 0.5 0"-->
|
||||
<limit effort="40" lower="0" upper="3.14159265359" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Toe -->
|
||||
<link name="toe1">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.015"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
<!-- <inertia ixx="2/5*${toeMass}*${toeRadius}*${toeRadius}" ixy="0" ixz="0" iyy="2/5*${toeMass}*${toeRadius}*${toeRadius}" iyz="0" izz="2/5*${toeMass}*${toeRadius}*${toeRadius}" /> -->
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoe1" type="fixed">
|
||||
<parent link="lower1"/>
|
||||
<child link="toe1"/>
|
||||
<origin xyz="0.206 0 -0.0"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Hip motor -->
|
||||
<link name="hip2">
|
||||
<visual>
|
||||
<origin rpy="1.5707963268 0 0" xyz="0.0 -0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963268 0 0" xyz="0 -0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.575"/>
|
||||
<!-- <inertia ixx="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" ixy="0" ixz="0" iyy="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" iyz="0" izz="1/2*${podMass}*${podRadius}*$
|
||||
{podRadius}" /> -->
|
||||
<inertia ixx="0.00066963541" ixy="0" ixz="0" iyy="0.00066963541" iyz="0" izz="0.0008696875"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Abduction joint. Joint names are: 8 9 10 11 -->
|
||||
<joint name="10" type="revolute">
|
||||
<parent link="body"/>
|
||||
<child link="hip2"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin xyz="0.2263 -0.07 0"/>
|
||||
<limit effort="40" lower="-0.707" upper="0.707" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Upper leg -->
|
||||
<link name="upper2">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.103 0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="-0.103 0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.775"/>
|
||||
<inertia ixx="5e-05" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 -->
|
||||
<joint name="4" type="revolute">
|
||||
<parent link="hip2"/>
|
||||
<child link="upper2"/>
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin xyz="0.0 -0.10098 0"/>
|
||||
<!-- rpy="0 -0.3 0" -->
|
||||
<limit effort="40" lower="-6.28318530718" upper="6.28318530718" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Lower leg -->
|
||||
<link name="lower2">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.075"/>
|
||||
<inertia ixx="5e-06" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Knee joint. Joint names are: 1 3 5 7 -->
|
||||
<joint name="5" type="revolute">
|
||||
<parent link="upper2"/>
|
||||
<child link="lower2"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<origin xyz="-0.206 0 0"/>
|
||||
<!--rpy="0 0.5 0"-->
|
||||
<limit effort="40" lower="0" upper="3.14159265359" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Toe -->
|
||||
<link name="toe2">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.015"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
<!-- <inertia ixx="2/5*${toeMass}*${toeRadius}*${toeRadius}" ixy="0" ixz="0" iyy="2/5*${toeMass}*${toeRadius}*${toeRadius}" iyz="0" izz="2/5*${toeMass}*${toeRadius}*${toeRadius}" /> -->
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoe2" type="fixed">
|
||||
<parent link="lower2"/>
|
||||
<child link="toe2"/>
|
||||
<origin xyz="0.206 0 -0.0"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Hip motor -->
|
||||
<link name="hip3">
|
||||
<visual>
|
||||
<origin rpy="1.5707963268 0 0" xyz="-0.0 -0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963268 0 0" xyz="0 -0.028 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.08" radius="0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.575"/>
|
||||
<!-- <inertia ixx="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" ixy="0" ixz="0" iyy="1/12*${podMass}*${podLength}*${podLength} + 1/4*${podMass}*${podRadius}*${podRadius}" iyz="0" izz="1/2*${podMass}*${podRadius}*$
|
||||
{podRadius}" /> -->
|
||||
<inertia ixx="0.00066963541" ixy="0" ixz="0" iyy="0.00066963541" iyz="0" izz="0.0008696875"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Abduction joint. Joint names are: 8 9 10 11 -->
|
||||
<joint name="11" type="revolute">
|
||||
<parent link="body"/>
|
||||
<child link="hip3"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin xyz="-0.2263 -0.07 0"/>
|
||||
<limit effort="40" lower="-0.707" upper="0.707" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Upper leg -->
|
||||
<link name="upper3">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.103 0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="-0.103 0.022 0"/>
|
||||
<geometry>
|
||||
<box size="0.206 0.022 0.055"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.775"/>
|
||||
<inertia ixx="5e-05" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 -->
|
||||
<joint name="6" type="revolute">
|
||||
<parent link="hip3"/>
|
||||
<child link="upper3"/>
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin xyz="-0.0 -0.10098 0"/>
|
||||
<!-- rpy="0 -0.3 0" -->
|
||||
<limit effort="40" lower="-6.28318530718" upper="6.28318530718" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Lower leg -->
|
||||
<link name="lower3">
|
||||
<visual>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963268 0" xyz="0.103 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.206" radius="0.013"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.075"/>
|
||||
<inertia ixx="5e-06" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- Knee joint. Joint names are: 1 3 5 7 -->
|
||||
<joint name="7" type="revolute">
|
||||
<parent link="upper3"/>
|
||||
<child link="lower3"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<origin xyz="-0.206 0 0"/>
|
||||
<!--rpy="0 0.5 0"-->
|
||||
<limit effort="40" lower="0" upper="3.14159265359" velocity="30"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
<!-- Toe -->
|
||||
<link name="toe3">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.015"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
<!-- <inertia ixx="2/5*${toeMass}*${toeRadius}*${toeRadius}" ixy="0" ixz="0" iyy="2/5*${toeMass}*${toeRadius}*${toeRadius}" iyz="0" izz="2/5*${toeMass}*${toeRadius}*${toeRadius}" /> -->
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoe3" type="fixed">
|
||||
<parent link="lower3"/>
|
||||
<child link="toe3"/>
|
||||
<origin xyz="0.206 0 -0.0"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
</robot>
|
||||
|
2
setup.py
2
setup.py
@ -501,7 +501,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
|
||||
|
||||
setup(
|
||||
name='pybullet',
|
||||
version='2.9.0',
|
||||
version='2.9.3',
|
||||
description=
|
||||
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||
long_description=
|
||||
|
@ -239,7 +239,10 @@ void btDeformableBodySolver::reinitialize(const btAlignedObjectArray<btSoftBody*
|
||||
m_residual[i].setZero();
|
||||
}
|
||||
|
||||
m_dt = dt;
|
||||
if (dt > 0)
|
||||
{
|
||||
m_dt = dt;
|
||||
}
|
||||
m_objective->reinitialize(nodeUpdated, dt);
|
||||
updateSoftBodies();
|
||||
}
|
||||
|
@ -718,8 +718,18 @@ void btDeformableMultiBodyDynamicsWorld::removeForce(btSoftBody* psb, btDeformab
|
||||
forces.removeAtIndex(removed_index);
|
||||
}
|
||||
|
||||
void btDeformableMultiBodyDynamicsWorld::removeSoftBodyForce(btSoftBody* psb)
|
||||
{
|
||||
btAlignedObjectArray<btDeformableLagrangianForce*>& forces = m_deformableBodySolver->m_objective->m_lf;
|
||||
for (int i = 0; i < forces.size(); ++i)
|
||||
{
|
||||
forces[i]->removeSoftBody(psb);
|
||||
}
|
||||
}
|
||||
|
||||
void btDeformableMultiBodyDynamicsWorld::removeSoftBody(btSoftBody* body)
|
||||
{
|
||||
removeSoftBodyForce(body);
|
||||
m_softBodies.remove(body);
|
||||
btCollisionWorld::removeCollisionObject(body);
|
||||
// force a reinitialize so that node indices get updated.
|
||||
|
@ -133,6 +133,8 @@ public:
|
||||
|
||||
void removeForce(btSoftBody* psb, btDeformableLagrangianForce* force);
|
||||
|
||||
void removeSoftBodyForce(btSoftBody* psb);
|
||||
|
||||
void removeSoftBody(btSoftBody* body);
|
||||
|
||||
void removeCollisionObject(btCollisionObject* collisionObject);
|
||||
|
@ -222,7 +222,7 @@ void btSoftBody::initDefaults()
|
||||
m_windVelocity = btVector3(0, 0, 0);
|
||||
m_restLengthScale = btScalar(1.0);
|
||||
m_dampingCoefficient = 1.0;
|
||||
m_sleepingThreshold = .4;
|
||||
m_sleepingThreshold = .04;
|
||||
m_useSelfCollision = false;
|
||||
m_collisionFlags = 0;
|
||||
m_softSoftCollision = false;
|
||||
|
Loading…
Reference in New Issue
Block a user