Merge pull request #1482 from erwincoumans/master

expose local inertia diagonal in PyBullet/C-API, render inertia boxes, updated minitaur with flex brackets
This commit is contained in:
erwincoumans
2017-12-20 16:09:01 -08:00
committed by GitHub
9 changed files with 1131 additions and 21 deletions

View File

@@ -0,0 +1,980 @@
<?xml version="1.0"?>
<robot name="quadruped">
<link name="base_chassis_link">
<visual>
<geometry>
<box size=".3 .13 .087"/>
</geometry>
<material name="black">
<color rgba=".3 .3 .3 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".3 .13 .087"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz=".05 0 0"/>
<mass value="3.353"/>
<inertia ixx=".006837" ixy=".0" ixz=".0" iyy=".027262" iyz=".0" izz=".029870"/>
</inertial>
</link>
<link name="chassis_right">
<visual>
<origin rpy="0 0 0" xyz=".2375 .054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-.2375 .054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz=".2375 .054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-.2375 .054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<inertial>
<mass value="0.322"/>
<inertia ixx=".004147" ixy=".0" ixz=".0" iyy=".040913" iyz=".0" izz=".041840"/>
</inertial>
</link>
<joint name="chassis_right_center" type="fixed">
<axis xyz="0 0 1"/>
<parent link="base_chassis_link"/>
<child link="chassis_right"/>
<origin rpy="0 0 0" xyz="0 -.1265 -.0185"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="chassis_left">
<visual>
<origin rpy="0 0 0" xyz=".2375 -.054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-.2375 -.054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz=".2375 -.054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-.2375 -.054 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<inertial>
<mass value="0.322"/>
<inertia ixx=".004147" ixy=".0" ixz=".0" iyy=".040913" iyz=".0" izz=".041840"/>
</inertial>
</link>
<joint name="chassis_left_center" type="fixed">
<axis xyz="0 0 1"/>
<parent link="base_chassis_link"/>
<child link="chassis_left"/>
<origin rpy="0 0 0" xyz="0 .1265 -.0185"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_front_rightR_bracket_link">
<visual>
<origin rpy="0 0 0" xyz="0 -0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 -0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 -0.03 0"/>
<mass value=".16"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_front_rightR_bracket_joint" type="prismatic">
<axis xyz="0 0 1"/>
<parent link="base_chassis_link"/>
<child link="motor_front_rightR_bracket_link"/>
<origin rpy="0 0 0" xyz=".2375 -0.154 -.0185"/>
<limit effort="100" lower="-0.02" upper="0.02" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_front_rightR_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_front_rightR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="motor_front_rightR_bracket_link"/>
<child link="motor_front_rightR_link"/>
<origin rpy="1.57075 0 0" xyz="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_front_rightL_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_front_rightL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_right"/>
<child link="motor_front_rightL_link"/>
<origin rpy="1.57075 0 3.141592" xyz=".2375 .0275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_front_leftL_bracket_link">
<visual>
<origin rpy="0 0 0" xyz="0 0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0.02 0"/>
<mass value=".16"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_front_leftL_bracket_joint" type="prismatic">
<axis xyz="0 0 1"/>
<parent link="base_chassis_link"/>
<child link="motor_front_leftL_bracket_link"/>
<origin rpy="0 0 0" xyz=".2375 0.154 -.0185"/>
<limit effort="100" lower="-0.02" upper="0.02" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_front_leftL_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_front_leftL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="motor_front_leftL_bracket_link"/>
<child link="motor_front_leftL_link"/>
<origin rpy="1.57075 0 3.141592" xyz="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_front_leftR_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_front_leftR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_left"/>
<child link="motor_front_leftR_link"/>
<origin rpy="1.57075 0 0" xyz=".2375 -.0275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_back_rightR_bracket_link">
<visual>
<origin rpy="0 0 0" xyz="0 -0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 -0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 -0.03 0"/>
<mass value=".16"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_back_rightR_bracket_joint" type="prismatic">
<axis xyz="0 0 1"/>
<parent link="base_chassis_link"/>
<child link="motor_back_rightR_bracket_link"/>
<origin rpy="0 0 0" xyz="-.2375 -0.154 -.0185"/>
<limit effort="100" lower="-0.02" upper="0.02" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_back_rightR_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white1">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_back_rightR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="motor_back_rightR_bracket_link"/>
<child link="motor_back_rightR_link"/>
<origin rpy="1.57075 0 0" xyz="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_back_rightL_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_back_rightL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_right"/>
<child link="motor_back_rightL_link"/>
<origin rpy="1.57075 0 3.141592" xyz="-.2375 .0275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_back_leftL_bracket_link">
<visual>
<origin rpy="0 0 0" xyz="0 0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0.02 0"/>
<geometry>
<box size=".068 .032 .050"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0.02 0"/>
<mass value=".16"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_back_leftL_bracket_joint" type="prismatic">
<axis xyz="0 0 1"/>
<parent link="base_chassis_link"/>
<child link="motor_back_leftL_bracket_link"/>
<origin rpy="0 0 0" xyz="-.2375 0.154 -.0185"/>
<limit effort="100" lower="-0.02" upper="0.02" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_back_leftL_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_back_leftL_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="motor_back_leftL_bracket_link"/>
<child link="motor_back_leftL_link"/>
<origin rpy="1.57075 0 3.141592" xyz="0 0 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="motor_back_leftR_link">
<visual>
<geometry>
<mesh filename="tmotor3.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length=".021" radius=".0425"/>
</geometry>
</collision>
<inertial>
<mass value=".241"/>
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
</inertial>
</link>
<joint name="motor_back_leftR_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="chassis_left"/>
<child link="motor_back_leftR_link"/>
<origin rpy="1.57075 0 0" xyz="-.2375 -.0275 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_front_rightR_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_front_rightR_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_front_rightR_link"/>
<child link="upper_leg_front_rightR_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_front_rightR_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<mass value=".086"/>
<inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
</inertial>
</link>
<joint name="knee_front_rightR_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_front_rightR_link"/>
<child link="lower_leg_front_rightR_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_front_rightL_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_front_rightL_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_front_rightL_link"/>
<child link="upper_leg_front_rightL_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_front_rightL_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .1"/>
<mass value=".072"/>
<inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
</inertial>
</link>
<joint name="knee_front_rightL_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_front_rightL_link"/>
<child link="lower_leg_front_rightL_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_front_leftR_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_front_leftR_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_front_leftR_link"/>
<child link="upper_leg_front_leftR_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_front_leftR_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .1"/>
<mass value=".072"/>
<inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
</inertial>
</link>
<joint name="knee_front_leftR_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_front_leftR_link"/>
<child link="lower_leg_front_leftR_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_front_leftL_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_front_leftL_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_front_leftL_link"/>
<child link="upper_leg_front_leftL_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_front_leftL_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<mass value=".086"/>
<inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
</inertial>
</link>
<joint name="knee_front_leftL_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_front_leftL_link"/>
<child link="lower_leg_front_leftL_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_back_rightR_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_back_rightR_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_back_rightR_link"/>
<child link="upper_leg_back_rightR_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_back_rightR_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<mass value=".086"/>
<inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
</inertial>
</link>
<joint name="knee_back_rightR_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_back_rightR_link"/>
<child link="lower_leg_back_rightR_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_back_rightL_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_back_rightL_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_back_rightL_link"/>
<child link="upper_leg_back_rightL_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_back_rightL_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .1"/>
<mass value=".072"/>
<inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
</inertial>
</link>
<joint name="knee_back_rightL_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_back_rightL_link"/>
<child link="lower_leg_back_rightL_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_back_leftR_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_back_leftR_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_back_leftR_link"/>
<child link="upper_leg_back_leftR_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_back_leftR_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .108"/>
<geometry>
<box size=".017 .009 .216"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .1"/>
<mass value=".072"/>
<inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
</inertial>
</link>
<joint name="knee_back_leftR_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_back_leftR_link"/>
<child link="lower_leg_back_leftR_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="upper_leg_back_leftL_link">
<visual>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<geometry>
<box size=".039 .008 .129"/>
</geometry>
</collision>
<inertial>
<mass value=".034"/>
<inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
</inertial>
</link>
<joint name="hip_back_leftL_joint" type="fixed">
<axis xyz="0 0 1"/>
<parent link="motor_back_leftL_link"/>
<child link="upper_leg_back_leftL_link"/>
<origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
<link name="lower_leg_back_leftL_link">
<contact>
<friction_anchor/>
<stiffness value="3000.0"/>
<damping value="100.0"/>
<spinning_friction value=".05"/>
<lateral_friction value="1"/>
</contact>
<visual>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
<material name="grey">
<color rgba=".65 .65 .75 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<geometry>
<box size=".017 .009 .240"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 .120"/>
<mass value=".086"/>
<inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
</inertial>
</link>
<joint name="knee_back_leftL_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_leg_back_leftL_link"/>
<child link="lower_leg_back_leftL_link"/>
<origin rpy="0 0 0" xyz="0 .0085 .056"/>
<limit effort="100" velocity="100"/>
<joint_properties damping=".0" friction=".0"/>
</joint>
</robot>

View File

@@ -613,18 +613,19 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl
vertices.push_back(vert); vertices.push_back(vert);
} }
btConvexHullShape* convexHull = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3));
convexHull->setMargin(gUrdfDefaultCollisionMargin); cylZShape->setMargin(gUrdfDefaultCollisionMargin);
convexHull->initializePolyhedralFeatures(); cylZShape->recalcLocalAabb();
convexHull->optimizeConvexHull(); cylZShape->initializePolyhedralFeatures();
cylZShape->optimizeConvexHull();
//btConvexShape* cylZShape = new btConeShapeZ(cyl->radius,cyl->length);//(vexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); //btConvexShape* cylZShape = new btConeShapeZ(cylRadius,cylLength);//(vexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3));
//btVector3 halfExtents(cyl->radius,cyl->radius,cyl->length/2.); //btVector3 halfExtents(cylRadius,cylRadius,cylLength);
//btCylinderShapeZ* cylZShape = new btCylinderShapeZ(halfExtents); //btCylinderShapeZ* cylZShape = new btCylinderShapeZ(halfExtents);
shape = convexHull; shape = cylZShape;
break; break;
} }
case URDF_GEOM_BOX: case URDF_GEOM_BOX:
@@ -798,6 +799,7 @@ upAxisMat.setIdentity();
convexHull->optimizeConvexHull(); convexHull->optimizeConvexHull();
//convexHull->initializePolyhedralFeatures(); //convexHull->initializePolyhedralFeatures();
convexHull->setMargin(gUrdfDefaultCollisionMargin); convexHull->setMargin(gUrdfDefaultCollisionMargin);
convexHull->recalcLocalAabb();
//convexHull->setLocalScaling(collision->m_geometry.m_meshScale); //convexHull->setLocalScaling(collision->m_geometry.m_meshScale);
shape = convexHull; shape = convexHull;
} }
@@ -845,6 +847,7 @@ void BulletURDFImporter::convertURDFToVisualShapeInternal(const UrdfVisual* visu
btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3));
cylZShape->setMargin(gUrdfDefaultCollisionMargin); cylZShape->setMargin(gUrdfDefaultCollisionMargin);
cylZShape->recalcLocalAabb();
convexColShape = cylZShape; convexColShape = cylZShape;
break; break;
} }

View File

@@ -2052,11 +2052,15 @@ B3_SHARED_API int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, str
{ {
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
const b3DynamicsInfo &dynamicsInfo = status->m_dynamicsInfo; const b3DynamicsInfo &dynamicsInfo = status->m_dynamicsInfo;
btAssert(status->m_type == CMD_GET_DYNAMICS_INFO); btAssert(status->m_type == CMD_GET_DYNAMICS_INFO_COMPLETED);
if (status->m_type != CMD_GET_DYNAMICS_INFO_COMPLETED) if (status->m_type != CMD_GET_DYNAMICS_INFO_COMPLETED)
return false; return false;
info->m_mass = dynamicsInfo.m_mass; info->m_mass = dynamicsInfo.m_mass;
info->m_localInertialDiagonal[0] = dynamicsInfo.m_localInertialDiagonal[0];
info->m_localInertialDiagonal[1] = dynamicsInfo.m_localInertialDiagonal[1];
info->m_localInertialDiagonal[2] = dynamicsInfo.m_localInertialDiagonal[2];
info->m_lateralFrictionCoeff = dynamicsInfo.m_lateralFrictionCoeff; info->m_lateralFrictionCoeff = dynamicsInfo.m_lateralFrictionCoeff;
return true; return true;
} }

View File

@@ -6148,11 +6148,18 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S
if (linkIndex == -1) if (linkIndex == -1)
{ {
serverCmd.m_dynamicsInfo.m_mass = mb->getBaseMass(); serverCmd.m_dynamicsInfo.m_mass = mb->getBaseMass();
serverCmd.m_dynamicsInfo.m_localInertialDiagonal[0] = mb->getBaseInertia()[0];
serverCmd.m_dynamicsInfo.m_localInertialDiagonal[1] = mb->getBaseInertia()[1];
serverCmd.m_dynamicsInfo.m_localInertialDiagonal[2] = mb->getBaseInertia()[2];
serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = mb->getBaseCollider()->getFriction(); serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = mb->getBaseCollider()->getFriction();
} }
else else
{ {
serverCmd.m_dynamicsInfo.m_mass = mb->getLinkMass(linkIndex); serverCmd.m_dynamicsInfo.m_mass = mb->getLinkMass(linkIndex);
serverCmd.m_dynamicsInfo.m_localInertialDiagonal[0] = mb->getLinkInertia(linkIndex)[0];
serverCmd.m_dynamicsInfo.m_localInertialDiagonal[1] = mb->getLinkInertia(linkIndex)[1];
serverCmd.m_dynamicsInfo.m_localInertialDiagonal[2] = mb->getLinkInertia(linkIndex)[2];
if (mb->getLinkCollider(linkIndex)) if (mb->getLinkCollider(linkIndex))
{ {
serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = mb->getLinkCollider(linkIndex)->getFriction(); serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = mb->getLinkCollider(linkIndex)->getFriction();

View File

@@ -210,6 +210,10 @@ enum JointType {
eGearType=6 eGearType=6
}; };
enum b3RequestDynamicsInfoFlags
{
eDYNAMICS_INFO_REPORT_INERTIA=1,
};
enum b3JointInfoFlags enum b3JointInfoFlags
{ {
@@ -266,7 +270,7 @@ struct b3BodyInfo
struct b3DynamicsInfo struct b3DynamicsInfo
{ {
double m_mass; double m_mass;
double m_localInertialPosition[3]; double m_localInertialDiagonal[3];
double m_lateralFrictionCoeff; double m_lateralFrictionCoeff;
}; };

View File

@@ -2,6 +2,44 @@ import pybullet as p
import time import time
import math import math
def drawInertiaBox(parentUid, parentLinkIndex, color):
mass,frictionCoeff, inertia =p.getDynamicsInfo(bodyUniqueId=parentUid,linkIndex=parentLinkIndex, flags = p.DYNAMICS_INFO_REPORT_INERTIA)
if (mass>0):
Ixx = inertia[0]
Iyy = inertia[1]
Izz = inertia[2]
boxScaleX = 0.5*math.sqrt(6*(Izz + Iyy - Ixx) / mass);
boxScaleY = 0.5*math.sqrt(6*(Izz + Ixx - Iyy) / mass);
boxScaleZ = 0.5*math.sqrt(6*(Ixx + Iyy - Izz) / mass);
halfExtents = [boxScaleX,boxScaleY,boxScaleZ]
pts = [[halfExtents[0],halfExtents[1],halfExtents[2]],
[-halfExtents[0],halfExtents[1],halfExtents[2]],
[halfExtents[0],-halfExtents[1],halfExtents[2]],
[-halfExtents[0],-halfExtents[1],halfExtents[2]],
[halfExtents[0],halfExtents[1],-halfExtents[2]],
[-halfExtents[0],halfExtents[1],-halfExtents[2]],
[halfExtents[0],-halfExtents[1],-halfExtents[2]],
[-halfExtents[0],-halfExtents[1],-halfExtents[2]]]
p.addUserDebugLine(pts[0],pts[1],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[1],pts[3],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[3],pts[2],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[2],pts[0],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[0],pts[4],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[1],pts[5],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[2],pts[6],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[3],pts[7],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+0],pts[4+1],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+1],pts[4+3],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+3],pts[4+2],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+2],pts[4+0],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
toeConstraint = True toeConstraint = True
useMaximalCoordinates = False useMaximalCoordinates = False
useRealTime = 1 useRealTime = 1
@@ -44,7 +82,6 @@ p.setRealTimeSimulation(0)
quadruped = p.loadURDF("quadruped/minitaur_v1.urdf",[1,-1,.3],orn,useFixedBase=False, useMaximalCoordinates=useMaximalCoordinates) quadruped = p.loadURDF("quadruped/minitaur_v1.urdf",[1,-1,.3],orn,useFixedBase=False, useMaximalCoordinates=useMaximalCoordinates)
nJoints = p.getNumJoints(quadruped) nJoints = p.getNumJoints(quadruped)
jointNameToId = {} jointNameToId = {}
for i in range(nJoints): for i in range(nJoints):
jointInfo = p.getJointInfo(quadruped, i) jointInfo = p.getJointInfo(quadruped, i)
@@ -76,6 +113,14 @@ motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint']
motor_back_leftL_link = jointNameToId['motor_back_leftL_link'] motor_back_leftL_link = jointNameToId['motor_back_leftL_link']
knee_back_leftL_link = jointNameToId['knee_back_leftL_link'] knee_back_leftL_link = jointNameToId['knee_back_leftL_link']
drawInertiaBox(quadruped,-1, [1,0,0])
#drawInertiaBox(quadruped,motor_front_rightR_joint, [1,0,0])
for i in range (nJoints):
drawInertiaBox(quadruped,i, [0,1,0])
#fixtorso = p.createConstraint(-1,-1,quadruped,-1,p.JOINT_FIXED,[0,0,0],[0,0,0],[0,0,0]) #fixtorso = p.createConstraint(-1,-1,quadruped,-1,p.JOINT_FIXED,[0,0,0],[0,0,0],[0,0,0])
motordir=[-1,-1,-1,-1,1,1,1,1] motordir=[-1,-1,-1,-1,1,1,1,1]

View File

@@ -4,20 +4,63 @@ import math
p.connect(p.GUI) p.connect(p.GUI)
planeId = p.loadURDF(fileName="plane.urdf",baseOrientation=[0.25882,0,0,0.96593]) planeId = p.loadURDF(fileName="plane.urdf",baseOrientation=[0.25882,0,0,0.96593])
p.loadURDF(fileName="cube.urdf",baseOrientation=[0.25882,0,0,0.96593],basePosition=[0,0,2]) p.loadURDF(fileName="cube.urdf",basePosition=[0,0,2])
cubeId = p.loadURDF(fileName="cube.urdf",baseOrientation=[0,0,0,1],basePosition=[0,0,4]) cubeId = p.loadURDF(fileName="cube.urdf",baseOrientation=[0,0,0,1],basePosition=[0,0,4])
#p.changeDynamics(bodyUniqueId=2,linkIndex=-1,mass=0.1) #p.changeDynamics(bodyUniqueId=2,linkIndex=-1,mass=0.1)
p.changeDynamics(bodyUniqueId=2,linkIndex=-1,mass=100.0) p.changeDynamics(bodyUniqueId=2,linkIndex=-1,mass=1.0)
p.setGravity(0,0,-10) p.setGravity(0,0,-10)
p.setRealTimeSimulation(0) p.setRealTimeSimulation(0)
def drawInertiaBox(parentUid, parentLinkIndex):
mass,frictionCoeff, inertia =p.getDynamicsInfo(bodyUniqueId=parentUid,linkIndex=parentLinkIndex, flags = p.DYNAMICS_INFO_REPORT_INERTIA)
Ixx = inertia[0]
Iyy = inertia[1]
Izz = inertia[2]
boxScaleX = 0.5*math.sqrt(6*(Izz + Iyy - Ixx) / mass);
boxScaleY = 0.5*math.sqrt(6*(Izz + Ixx - Iyy) / mass);
boxScaleZ = 0.5*math.sqrt(6*(Ixx + Iyy - Izz) / mass);
halfExtents = [boxScaleX,boxScaleY,boxScaleZ]
pts = [[halfExtents[0],halfExtents[1],halfExtents[2]],
[-halfExtents[0],halfExtents[1],halfExtents[2]],
[halfExtents[0],-halfExtents[1],halfExtents[2]],
[-halfExtents[0],-halfExtents[1],halfExtents[2]],
[halfExtents[0],halfExtents[1],-halfExtents[2]],
[-halfExtents[0],halfExtents[1],-halfExtents[2]],
[halfExtents[0],-halfExtents[1],-halfExtents[2]],
[-halfExtents[0],-halfExtents[1],-halfExtents[2]]]
color=[1,0,0]
p.addUserDebugLine(pts[0],pts[1],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[1],pts[3],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[3],pts[2],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[2],pts[0],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[0],pts[4],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[1],pts[5],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[2],pts[6],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[3],pts[7],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+0],pts[4+1],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+1],pts[4+3],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+3],pts[4+2],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
p.addUserDebugLine(pts[4+2],pts[4+0],color,1, parentObjectUniqueId=parentUid, parentLinkIndex = parentLinkIndex)
drawInertiaBox(cubeId,-1)
t=0 t=0
while 1: while 1:
t=t+1 t=t+1
if t > 400: if t > 400:
p.changeDynamics(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01) p.changeDynamics(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
mass1,frictionCoeff1=p.getDynamicsInfo(bodyUniqueId=planeId,linkIndex=-1) mass1,frictionCoeff1 =p.getDynamicsInfo(bodyUniqueId=planeId,linkIndex=-1)
mass2,frictionCoeff2=p.getDynamicsInfo(bodyUniqueId=cubeId,linkIndex=-1) mass2,frictionCoeff2 =p.getDynamicsInfo(bodyUniqueId=cubeId,linkIndex=-1)
print mass1,frictionCoeff1
print mass2,frictionCoeff2
time.sleep(.01) print (mass1,frictionCoeff1)
print (mass2,frictionCoeff2)
time.sleep(1./240.)
p.stepSimulation() p.stepSimulation()

View File

@@ -808,11 +808,13 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje
{ {
int bodyUniqueId = -1; int bodyUniqueId = -1;
int linkIndex = -2; int linkIndex = -2;
int flags = 0;
b3PhysicsClientHandle sm = 0; b3PhysicsClientHandle sm = 0;
int physicsClientId = 0; int physicsClientId = 0;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL}; static char* kwlist[] = {"bodyUniqueId", "linkIndex", "flags", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId)) if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ii", kwlist, &bodyUniqueId, &linkIndex, &flags, &physicsClientId))
{ {
return NULL; return NULL;
} }
@@ -827,6 +829,12 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje
b3SharedMemoryCommandHandle cmd_handle; b3SharedMemoryCommandHandle cmd_handle;
b3SharedMemoryStatusHandle status_handle; b3SharedMemoryStatusHandle status_handle;
struct b3DynamicsInfo info; struct b3DynamicsInfo info;
int numFields = 2;
if (flags & eDYNAMICS_INFO_REPORT_INERTIA)
{
numFields++;
}
if (bodyUniqueId < 0) if (bodyUniqueId < 0)
{ {
PyErr_SetString(SpamError, "getDynamicsInfo failed; invalid bodyUniqueId"); PyErr_SetString(SpamError, "getDynamicsInfo failed; invalid bodyUniqueId");
@@ -846,11 +854,25 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje
return NULL; return NULL;
} }
if (b3GetDynamicsInfo(status_handle, &info)) if (b3GetDynamicsInfo(status_handle, &info))
{ {
PyObject* pyDynamicsInfo = PyTuple_New(2);
PyObject* pyDynamicsInfo = PyTuple_New(numFields);
PyTuple_SetItem(pyDynamicsInfo, 0, PyFloat_FromDouble(info.m_mass)); PyTuple_SetItem(pyDynamicsInfo, 0, PyFloat_FromDouble(info.m_mass));
PyTuple_SetItem(pyDynamicsInfo, 1, PyFloat_FromDouble(info.m_lateralFrictionCoeff)); PyTuple_SetItem(pyDynamicsInfo, 1, PyFloat_FromDouble(info.m_lateralFrictionCoeff));
if (flags & eDYNAMICS_INFO_REPORT_INERTIA)
{
PyObject* pyInertiaDiag = PyTuple_New(3);
PyTuple_SetItem(pyInertiaDiag,0,PyFloat_FromDouble(info.m_localInertialDiagonal[0]));
PyTuple_SetItem(pyInertiaDiag,1,PyFloat_FromDouble(info.m_localInertialDiagonal[1]));
PyTuple_SetItem(pyInertiaDiag,2,PyFloat_FromDouble(info.m_localInertialDiagonal[2]));
PyTuple_SetItem(pyDynamicsInfo, 2, pyInertiaDiag);
}
return pyDynamicsInfo; return pyDynamicsInfo;
} }
} }
@@ -8168,6 +8190,8 @@ initpybullet(void)
PyModule_AddIntConstant(m, "JOINT_FIXED", eFixedType); // user read PyModule_AddIntConstant(m, "JOINT_FIXED", eFixedType); // user read
PyModule_AddIntConstant(m, "JOINT_POINT2POINT", ePoint2PointType); // user read PyModule_AddIntConstant(m, "JOINT_POINT2POINT", ePoint2PointType); // user read
PyModule_AddIntConstant(m, "JOINT_GEAR", eGearType); // user read PyModule_AddIntConstant(m, "JOINT_GEAR", eGearType); // user read
PyModule_AddIntConstant(m, "DYNAMICS_INFO_REPORT_INERTIA", eDYNAMICS_INFO_REPORT_INERTIA); // report local inertia in 'getDynamicsInfo'
PyModule_AddIntConstant(m, "SENSOR_FORCE_TORQUE", eSensorForceTorqueType); // user read PyModule_AddIntConstant(m, "SENSOR_FORCE_TORQUE", eSensorForceTorqueType); // user read

View File

@@ -443,7 +443,7 @@ print("-----")
setup( setup(
name = 'pybullet', name = 'pybullet',
version='1.7.4', version='1.7.5',
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3', url='https://github.com/bulletphysics/bullet3',