Skip to content
This repository has been archived by the owner on Oct 31, 2023. It is now read-only.

Any support for free floating robot? #26

Open
shikui08 opened this issue Oct 13, 2021 · 10 comments
Open

Any support for free floating robot? #26

shikui08 opened this issue Oct 13, 2021 · 10 comments
Assignees

Comments

@shikui08
Copy link

Function get_body_parameters_from_urdf treats base_link as fixed joint and the dofs are excluded. How to work with free floating robots?

@fmeier
Copy link
Contributor

fmeier commented Oct 15, 2021

Hi!

thanks for reaching out! We're currently not officially supporting floating base systems, however I know of one researcher that has adapted the code-base to work with free floating robots. Let me see how hard it would be to incorporate these changes into our official library! I'll get back to you ASAP.

Best,
Franziska

@fmeier fmeier self-assigned this Oct 15, 2021
@shikui08
Copy link
Author

shikui08 commented Oct 18, 2021

Currently I can get around the free floating robot issue, but encountered other problems.
I experiment using DifferentiableRobotModel.

One is that when calliing compute_forward_kinematics on certain end effector, the resulting position&orientation may turn out zeros&identity quaternion, which is unexpected. Instead if I call the function recursively down the kinematic chain from root to the end effector, I get expected results.

Another is that calling compute_endeffector_jacobian gives jacobian matrices that are different from either rbdl or tiny-differentiable-simulator. I can verify that rbdl&tiny-differentiable-simulator point_jacobian matrices are consistent. But inspecting compute_endeffector_jacobian result I get no clue.

Am I getting something wrong?

@fmeier
Copy link
Contributor

fmeier commented Oct 18, 2021

hi!

would you be able to provide a small script that highlights the issue? which Urdf are you using? and what links are you trying to compute the Jacobians for?

we're automatically testing our forward_kinematics and Jacobian computations against pybullet (and the tests are passing) - so our kinematic computations should be consistent with pybullet at least (see tests).

@fmeier
Copy link
Contributor

fmeier commented Oct 19, 2021

Please note that we just merged a PR that fixed another issue (batched Jacobian computations) that might be related to your kinematic computation issues.

@shikui08
Copy link
Author

shikui08 commented Oct 19, 2021

For the position&orientation issue, here is a sample urdf

<?xml version="1.0"?> <robot name="4_sim_lipm"> <link name="LINK_World" /> <link name="LINK_ball_l"> <inertial> <mass value="0.2955128140901495" /> <origin xyz="0.0039986963383853436 0.038636524230241776 -0.0005474126664921641" /> <inertia ixx="0.000172215799314257" ixy="-2.7822674348879834e-06" ixz="7.254566851183765e-06" iyy="0.0002933435276595457" iyz="-6.081162250865166e-06" izz="0.0002581013910651983" /> </inertial> <visual> <origin rpy="1.5707963705062866 -2.7013689063437596e-08 -3.141592502593994" xyz="0.0039986963383853436 0.038636524230241776 -0.0005474126664921641" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.5707963705062866 -2.7013689063437596e-08 -3.141592502593994" xyz="0.0039986963383853436 0.038636524230241776 -0.0005474126664921641" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_ball_r"> <inertial> <mass value="0.29551255288159567" /> <origin xyz="-0.003998711705207825 0.03863653168082237 -0.0005474422941915691" /> <inertia ixx="0.00017221552637115343" ixy="2.782249611730089e-06" ixz="-7.254458338441265e-06" iyy="0.00029334313511919106" iyz="-6.081157508475223e-06" izz="0.00025810111385687516" /> </inertial> <visual> <origin rpy="1.5707963705062866 -5.4982123742775e-08 -3.141592502593994" xyz="-0.003998711705207825 0.03863653168082237 -0.0005474422941915691" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.5707963705062866 -5.4982123742775e-08 -3.141592502593994" xyz="-0.003998711705207825 0.03863653168082237 -0.0005474422941915691" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_calf_l"> <inertial> <mass value="6.412605675304451" /> <origin xyz="-0.010149852372705936 0.247135728597641 -0.006469465792179108" /> <inertia ixx="0.11669883061867126" ixy="0.0024212222125494912" ixz="0.0011147873582243147" iyy="0.015607179106209056" iyz="-0.009448589932025851" izz="0.11267265122697534" /> </inertial> <visual> <origin rpy="-0.11321306228637695 2.4294984086736804e-06 3.1197099685668945" xyz="-0.010149852372705936 0.247135728597641 -0.006469465792179108" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="-0.11321306228637695 2.4294984086736804e-06 3.1197099685668945" xyz="-0.010149852372705936 0.247135728597641 -0.006469465792179108" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_calf_r"> <inertial> <mass value="6.917640118822182" /> <origin xyz="0.007234317250549793 0.25078654289245605 -0.005356085952371359" /> <inertia ixx="0.12607076231563924" ixy="-0.0024257670809426177" ixz="-0.0015498021296475447" iyy="0.018112964818990135" iyz="-0.01012122530619801" izz="0.12161084380606177" /> </inertial> <visual> <origin rpy="-0.11321508884429932 8.229486425648247e-09 -3.119715452194214" xyz="0.007234317250549793 0.25078654289245605 -0.005356085952371359" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="-0.11321508884429932 8.229486425648247e-09 -3.119715452194214" xyz="0.007234317250549793 0.25078654289245605 -0.005356085952371359" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_foot_l"> <inertial> <mass value="1.3397568942243037" /> <origin xyz="0.00028446814394555986 0.05372985452413559 -0.03145608678460121" /> <inertia ixx="0.003902366170718377" ixy="-8.517878366165514e-06" ixz="-0.00013582031278423036" iyy="0.004316296225836691" iyz="0.00020063973319915532" izz="0.0017635398270636783" /> </inertial> <visual> <origin rpy="1.1049138307571411 7.68371748449681e-08 3.1228129863739014" xyz="0.00028446814394555986 0.05372985452413559 -0.03145608678460121" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.1049138307571411 7.68371748449681e-08 3.1228129863739014" xyz="0.00028446814394555986 0.05372985452413559 -0.03145608678460121" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_foot_r"> <inertial> <mass value="1.3395980851226803" /> <origin xyz="-0.00028304013540036976 0.05372866988182068 -0.0314563512802124" /> <inertia ixx="0.003901174913070836" ixy="8.208249428302479e-06" ixz="0.00013650682973817698" iyy="0.0043148748263546225" iyz="0.00020017179514546167" izz="0.0017628697683145366" /> </inertial> <visual> <origin rpy="1.1049139499664307 5.340243447449211e-08 -3.1228129863739014" xyz="-0.00028304013540036976 0.05372866988182068 -0.0314563512802124" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.1049139499664307 5.340243447449211e-08 -3.1228129863739014" xyz="-0.00028304013540036976 0.05372866988182068 -0.0314563512802124" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_lowerarm_l"> <inertial> <mass value="1.1212187936116227" /> <origin xyz="0.00664106197655201 0.12044784426689148 -0.0004038595943711698" /> <inertia ixx="0.0008858144513998454" ixy="-0.0001243740725126935" ixz="-0.0001953057627156736" iyy="0.005430609253270456" iyz="-2.9882874703829776e-05" izz="0.005323166134983879" /> </inertial> <visual> <origin rpy="1.570796251296997 0.029617944732308388 1.6443431377410889" xyz="0.00664106197655201 0.12044784426689148 -0.0004038595943711698" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.570796251296997 0.029617944732308388 1.6443431377410889" xyz="0.00664106197655201 0.12044784426689148 -0.0004038595943711698" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_lowerarm_r"> <inertial> <mass value="1.1171922451278757" /> <origin xyz="-0.0067726909182965755 0.12066613137722015 -0.00030598242301493883" /> <inertia ixx="0.0008778787510175203" ixy="0.00011827234051488484" ixz="0.00018581906033725276" iyy="0.005400022511853482" iyz="-2.6808414092217423e-05" izz="0.005294977298778246" /> </inertial> <visual> <origin rpy="1.5707963705062866 -0.029617881402373314 -1.6443431377410889" xyz="-0.0067726909182965755 0.12066613137722015 -0.00030598242301493883" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.5707963705062866 -0.029617881402373314 -1.6443431377410889" xyz="-0.0067726909182965755 0.12066613137722015 -0.00030598242301493883" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_neck_01"> <inertial> <mass value="5.607288777641918" /> <origin xyz="-8.483028501871104e-09 0.13390107452869415 0.0053551942110061646" /> <inertia ixx="0.03701160272668338" ixy="2.0496673994201477e-08" ixz="-7.559235924152575e-09" iyy="0.023536065948619938" iyz="-0.0018912253047577382" izz="0.029634380455757177" /> </inertial> <visual> <origin rpy="-0.3020614981651306 -3.141592502593994 2.563265693992546e-14" xyz="-8.483028501871104e-09 0.13390107452869415 0.0053551942110061646" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="-0.3020614981651306 -3.141592502593994 2.563265693992546e-14" xyz="-8.483028501871104e-09 0.13390107452869415 0.0053551942110061646" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_hand_l"> <inertial> <mass value="0.0001" /> <origin xyz="0.00784336868673563 0.07277116924524307 -0.007723701186478138" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> <visual> <origin rpy="1.5707963705062866 0.029611706733703613 1.6443430185317993" xyz="0.00784336868673563 0.07277116924524307 -0.007723701186478138" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> </link> <link name="LINK_hand_r"> <inertial> <mass value="0.0001" /> <origin xyz="-0.012764434330165386 0.10407515615224838 -0.010402247309684753" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> <visual> <origin rpy="1.570796251296997 -0.029611555859446526 -1.6443431377410889" xyz="-0.012764434330165386 0.10407515615224838 -0.010402247309684753" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> </link> <link name="LINK_Root"> <inertial> <mass value="14.753640348475889" /> <origin xyz="-0.000585267145652324 0.020340695977211 0.1179814338684082" /> <inertia ixx="0.11370771378278732" ixy="0.00014011103485245258" ixz="0.0002541676221881062" iyy="0.16765446960926056" iyz="-0.0019391612149775028" izz="0.16728077828884125" /> </inertial> <visual> <origin rpy="1.5707963705062866 -0.0 -3.141592502593994" xyz="-0.000585267145652324 0.020340695977211 0.1179814338684082" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.5707963705062866 -0.0 -3.141592502593994" xyz="-0.000585267145652324 0.020340695977211 0.1179814338684082" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_spine_03"> <inertial> <mass value="21.500350428865275" /> <origin xyz="3.3564199384272797e-06 0.16169624030590057 -0.025016900151968002" /> <inertia ixx="0.25347239965535323" ixy="3.002778000100033e-06" ixz="3.957268744829594e-06" iyy="0.25567958662783297" iyz="0.023970245984271842" izz="0.31088321536602587" /> </inertial> <visual> <origin rpy="-0.06777708232402802 -3.141592502593994 1.539036842304435e-14" xyz="3.3564199384272797e-06 0.16169624030590057 -0.025016900151968002" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="-0.06777708232402802 -3.141592502593994 1.539036842304435e-14" xyz="3.3564199384272797e-06 0.16169624030590057 -0.025016900151968002" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_thigh_l"> <inertial> <mass value="11.410618766493268" /> <origin xyz="0.012672637589275837 0.2009904980659485 0.004310078453272581" /> <inertia ixx="0.19604591482856323" ixy="0.014472864097093828" ixz="-0.00022600582502466758" iyy="0.05442592368243429" iyz="0.007104760531279687" izz="0.18470631061769652" /> </inertial> <visual> <origin rpy="0.07165336608886719 1.2211364719405537e-07 3.1279239654541016" xyz="0.012672637589275837 0.2009904980659485 0.004310078453272581" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="0.07165336608886719 1.2211364719405537e-07 3.1279239654541016" xyz="0.012672637589275837 0.2009904980659485 0.004310078453272581" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_thigh_r"> <inertial> <mass value="11.20676283640715" /> <origin xyz="-0.01585758477449417 0.2023342102766037 0.005646978504955769" /> <inertia ixx="0.19380166959324155" ixy="-0.012934155961407331" ixz="0.0007959547867777545" iyy="0.052255415493527885" iyz="0.007309766833658921" izz="0.18243769040234814" /> </inertial> <visual> <origin rpy="0.07165348529815674 1.740331896371572e-07 -3.1279239654541016" xyz="-0.01585758477449417 0.2023342102766037 0.005646978504955769" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="0.07165348529815674 1.740331896371572e-07 -3.1279239654541016" xyz="-0.01585758477449417 0.2023342102766037 0.005646978504955769" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_upperarm_l"> <inertial> <mass value="3.0647975217901102" /> <origin xyz="0.0015305164270102978 0.12498530000448227 -0.014185071922838688" /> <inertia ixx="0.006135492007835584" ixy="-0.0009647230217278372" ixz="-0.0009569350939062984" iyy="0.020168973195080122" iyz="-0.000432781724970006" izz="0.019949156099616564" /> </inertial> <visual> <origin rpy="1.5707963705062866 -0.026344897225499153 1.5729475021362305" xyz="0.0015305164270102978 0.12498530000448227 -0.014185071922838688" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.5707963705062866 -0.026344897225499153 1.5729475021362305" xyz="0.0015305164270102978 0.12498530000448227 -0.014185071922838688" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_upperarm_r"> <inertial> <mass value="3.0647243183979365" /> <origin xyz="-0.0015360863180831075 0.12496005743741989 -0.01417225319892168" /> <inertia ixx="0.006136169831976023" ixy="0.000967079054111819" ixz="0.0009512992872572462" iyy="0.020165120692912885" iyz="-0.00043296209336769173" izz="0.019943718018775453" /> </inertial> <visual> <origin rpy="1.5707967281341553 0.02634504623711109 -1.57294762134552" xyz="-0.0015360863180831075 0.12496005743741989 -0.01417225319892168" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </visual> <collision> <origin rpy="1.5707967281341553 0.02634504623711109 -1.57294762134552" xyz="-0.0015360863180831075 0.12496005743741989 -0.01417225319892168" /> <geometry> <cylinder length="0.25" radius="0.15" /> </geometry> </collision> </link> <link name="LINK_rfoot_surface_3"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_lfoot_surface_0"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_lfoot_surface_2"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_lfoot_surface"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_rfoot_surface_1"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_rfoot_surface_0"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_lfoot_surface_1"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_rfoot_surface"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_lfoot_surface_3"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_head"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <link name="LINK_rfoot_surface_2"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="9.999999747378752e-05" ixy="0.0" ixz="0.0" iyy="9.999999747378752e-05" iyz="0.0" izz="9.999999747378752e-05" /> </inertial> </link> <joint name="thigh_r_z" type="revolute"> <parent link="LINK_Root" /> <child link="LINK_thigh_r_z" /> <origin rpy="-1.499136209487915 -0.013633678667247295 -0.0009786542505025864" xyz="0.11052830517292023 1.4901161193847656e-08 0.0" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <link name="LINK_thigh_r_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_thigh_r_z" type="SimpleTransmission"> <actuator name="ACTU_h_r_z" /> <joint name="thigh_r_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="thigh_r_y" type="revolute"> <parent link="LINK_thigh_r_z" /> <child link="LINK_thigh_r_y" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_thigh_r_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_thigh_r_y" type="SimpleTransmission"> <actuator name="ACTU_h_r_y" /> <joint name="thigh_r_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="thigh_r_x" type="revolute"> <parent link="LINK_thigh_r_y" /> <child link="LINK_thigh_r" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="2.0943951023931953" velocity="1000" /> </joint> <transmission name="TRAN_thigh_r_x" type="SimpleTransmission"> <actuator name="ACTU_h_r_x" /> <joint name="thigh_r_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="calf_r" type="revolute"> <parent link="LINK_thigh_r" /> <child link="LINK_calf_r" /> <origin rpy="-0.18482057750225067 -0.00402161106467247 -0.00783928669989109" xyz="-2.1187588572502136e-08 0.4666747450828552 -1.043081283569336e-07" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-2.0943951023931953" upper="0.0" velocity="1000" /> </joint> <transmission name="TRAN_calf_r" type="SimpleTransmission"> <actuator name="ACTU__r" /> <joint name="calf_r" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="foot_r_y" type="revolute"> <parent link="LINK_calf_r" /> <child link="LINK_foot_r_y" /> <origin rpy="1.2180670499801636 0.01762360893189907 0.01539343036711216" xyz="-2.7008354663848877e-08 0.49490243196487427 4.470348358154297e-08" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.5235987755982988" upper="1.0471975511965976" velocity="1000" /> </joint> <link name="LINK_foot_r_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_foot_r_y" type="SimpleTransmission"> <actuator name="ACTU__r_y" /> <joint name="foot_r_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="foot_r_x" type="revolute"> <parent link="LINK_foot_r_y" /> <child link="LINK_foot_r" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <transmission name="TRAN_foot_r_x" type="SimpleTransmission"> <actuator name="ACTU__r_x" /> <joint name="foot_r_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="ball_r" type="revolute"> <parent link="LINK_foot_r" /> <child link="LINK_ball_r" /> <origin rpy="0.46588248014450073 4.5413801608162885e-09 0.018779557198286057" xyz="-5.289621185511351e-09 0.14233510196208954 -5.21540641784668e-08" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="0.0" upper="0.7853981633974483" velocity="1000" /> </joint> <transmission name="TRAN_ball_r" type="SimpleTransmission"> <actuator name="ACTU__r" /> <joint name="ball_r" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="thigh_l_z" type="revolute"> <parent link="LINK_Root" /> <child link="LINK_thigh_l_z" /> <origin rpy="-1.4991365671157837 0.013633674941956997 0.000978656462393701" xyz="-0.11052830517292023 -1.4901161193847656e-08 0.0" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <link name="LINK_thigh_l_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_thigh_l_z" type="SimpleTransmission"> <actuator name="ACTU_h_l_z" /> <joint name="thigh_l_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="thigh_l_y" type="revolute"> <parent link="LINK_thigh_l_z" /> <child link="LINK_thigh_l_y" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_thigh_l_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_thigh_l_y" type="SimpleTransmission"> <actuator name="ACTU_h_l_y" /> <joint name="thigh_l_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="thigh_l_x" type="revolute"> <parent link="LINK_thigh_l_y" /> <child link="LINK_thigh_l" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="2.0943951023931953" velocity="1000" /> </joint> <transmission name="TRAN_thigh_l_x" type="SimpleTransmission"> <actuator name="ACTU_h_l_x" /> <joint name="thigh_l_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="calf_l" type="revolute"> <parent link="LINK_thigh_l" /> <child link="LINK_calf_l" /> <origin rpy="-0.18482039868831635 0.004021633416414261 0.007839244790375233" xyz="2.0372681319713593e-08 0.46667471528053284 5.960464477539063e-08" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-2.0943951023931953" upper="0.0" velocity="1000" /> </joint> <transmission name="TRAN_calf_l" type="SimpleTransmission"> <actuator name="ACTU__l" /> <joint name="calf_l" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="foot_l_y" type="revolute"> <parent link="LINK_calf_l" /> <child link="LINK_foot_l_y" /> <origin rpy="1.218066930770874 -0.017623817548155785 -0.01539333164691925" xyz="1.7229467630386353e-08 0.4949023723602295 7.450580596923828e-08" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.5235987755982988" upper="1.0471975511965976" velocity="1000" /> </joint> <link name="LINK_foot_l_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_foot_l_y" type="SimpleTransmission"> <actuator name="ACTU__l_y" /> <joint name="foot_l_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="foot_l_x" type="revolute"> <parent link="LINK_foot_l_y" /> <child link="LINK_foot_l" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <transmission name="TRAN_foot_l_x" type="SimpleTransmission"> <actuator name="ACTU__l_x" /> <joint name="foot_l_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="ball_l" type="revolute"> <parent link="LINK_foot_l" /> <child link="LINK_ball_l" /> <origin rpy="0.46588262915611267 -3.5463565417614973e-10 -0.018779773265123367" xyz="2.5756889954209328e-09 0.14233511686325073 -3.3527612686157227e-08" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="0.0" upper="0.7853981633974483" velocity="1000" /> </joint> <transmission name="TRAN_ball_l" type="SimpleTransmission"> <actuator name="ACTU__l" /> <joint name="ball_l" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="spine_03_z" type="revolute"> <parent link="LINK_Root" /> <child link="LINK_spine_03_z" /> <origin rpy="1.5030192136764526 -1.5307817236021037e-08 -7.451365036104107e-08" xyz="6.5635408219577585e-09 -0.03128525987267494 0.24065923690795898" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_spine_03_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_spine_03_z" type="SimpleTransmission"> <actuator name="ACTU_e_03_z" /> <joint name="spine_03_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="spine_03_y" type="revolute"> <parent link="LINK_spine_03_z" /> <child link="LINK_spine_03_y" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_spine_03_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_spine_03_y" type="SimpleTransmission"> <actuator name="ACTU_e_03_y" /> <joint name="spine_03_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="spine_03_x" type="revolute"> <parent link="LINK_spine_03_y" /> <child link="LINK_spine_03" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <transmission name="TRAN_spine_03_x" type="SimpleTransmission"> <actuator name="ACTU_e_03_x" /> <joint name="spine_03_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="neck_01_z" type="revolute"> <parent link="LINK_spine_03" /> <child link="LINK_neck_01_z" /> <origin rpy="-0.2342844158411026 8.580718713346869e-08 3.34661969247918e-08" xyz="2.220446049250313e-15 0.33789360523223877 4.470348358154297e-08" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_neck_01_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_neck_01_z" type="SimpleTransmission"> <actuator name="ACTU__01_z" /> <joint name="neck_01_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="neck_01_y" type="revolute"> <parent link="LINK_neck_01_z" /> <child link="LINK_neck_01_y" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_neck_01_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_neck_01_y" type="SimpleTransmission"> <actuator name="ACTU__01_y" /> <joint name="neck_01_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="neck_01_x" type="revolute"> <parent link="LINK_neck_01_y" /> <child link="LINK_neck_01" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <transmission name="TRAN_neck_01_x" type="SimpleTransmission"> <actuator name="ACTU__01_x" /> <joint name="neck_01_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="head" type="fixed"> <parent link="LINK_neck_01" /> <child link="LINK_head" /> <origin rpy="1.6987323760986328e-06 -6.191091205236948e-14 -2.2271079294991503e-13" xyz="-1.1102230246251565e-16 0.12063366174697876 7.450580596923828e-09" /> </joint> <joint name="upperarm_l_z" type="revolute"> <parent link="LINK_spine_03" /> <child link="LINK_upperarm_l_z" /> <origin rpy="-0.057985275983810425 1.5029284954071045 1.5390818119049072" xyz="-0.17121928930282593 0.2663302421569824 -0.010236039757728577" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-2.6179938779914944" upper="1.0471975511965976" velocity="1000" /> </joint> <link name="LINK_upperarm_l_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_upperarm_l_z" type="SimpleTransmission"> <actuator name="ACTU_rarm_l_z" /> <joint name="upperarm_l_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="upperarm_l_y" type="revolute"> <parent link="LINK_upperarm_l_z" /> <child link="LINK_upperarm_l_y" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_upperarm_l_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_upperarm_l_y" type="SimpleTransmission"> <actuator name="ACTU_rarm_l_y" /> <joint name="upperarm_l_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="upperarm_l_x" type="revolute"> <parent link="LINK_upperarm_l_y" /> <child link="LINK_upperarm_l" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-2.0943951023931953" upper="1.0471975511965976" velocity="1000" /> </joint> <transmission name="TRAN_upperarm_l_x" type="SimpleTransmission"> <actuator name="ACTU_rarm_l_x" /> <joint name="upperarm_l_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="lowerarm_l" type="revolute"> <parent link="LINK_upperarm_l" /> <child link="LINK_lowerarm_l" /> <origin rpy="0.05581187456846237 0.0041102273389697075 -0.07128098607063293" xyz="5.8682417147792876e-08 0.29596537351608276 -4.0978193283081055e-08" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-2.0943951023931953" upper="0.0" velocity="1000" /> </joint> <transmission name="TRAN_lowerarm_l" type="SimpleTransmission"> <actuator name="ACTU_rarm_l" /> <joint name="lowerarm_l" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="hand_l_z" type="revolute"> <parent link="LINK_lowerarm_l" /> <child link="LINK_hand_l_z" /> <origin rpy="-6.254151685425313e-06 -4.509371649419336e-07 1.563690119610328e-07" xyz="1.507578417658806e-08 0.2597350478172302 -3.1082890927791595e-08" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <link name="LINK_hand_l_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_hand_l_z" type="SimpleTransmission"> <actuator name="ACTU__l_z" /> <joint name="hand_l_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="hand_l_x" type="revolute"> <parent link="LINK_hand_l_z" /> <child link="LINK_hand_l" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <transmission name="TRAN_hand_l_x" type="SimpleTransmission"> <actuator name="ACTU__l_x" /> <joint name="hand_l_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="upperarm_r_z" type="revolute"> <parent link="LINK_spine_03" /> <child link="LINK_upperarm_r_z" /> <origin rpy="-0.057994138449430466 -1.502928376197815 -1.5390750169754028" xyz="0.17121928930282593 0.2663302421569824 -0.010236069560050964" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="2.6179938779914944" velocity="1000" /> </joint> <link name="LINK_upperarm_r_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_upperarm_r_z" type="SimpleTransmission"> <actuator name="ACTU_rarm_r_z" /> <joint name="upperarm_r_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="upperarm_r_y" type="revolute"> <parent link="LINK_upperarm_r_z" /> <child link="LINK_upperarm_r_y" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-0.8726646259971648" upper="0.8726646259971648" velocity="1000" /> </joint> <link name="LINK_upperarm_r_y"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_upperarm_r_y" type="SimpleTransmission"> <actuator name="ACTU_rarm_r_y" /> <joint name="upperarm_r_y" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="upperarm_r_x" type="revolute"> <parent link="LINK_upperarm_r_y" /> <child link="LINK_upperarm_r" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-2.0943951023931953" upper="1.0471975511965976" velocity="1000" /> </joint> <transmission name="TRAN_upperarm_r_x" type="SimpleTransmission"> <actuator name="ACTU_rarm_r_x" /> <joint name="upperarm_r_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="lowerarm_r" type="revolute"> <parent link="LINK_upperarm_r" /> <child link="LINK_lowerarm_r" /> <origin rpy="0.05581184849143028 -0.004110404290258884 0.07128093391656876" xyz="-2.8870999813079834e-08 0.29596537351608276 -3.457535058259964e-08" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="0.0" upper="2.0943951023931953" velocity="1000" /> </joint> <transmission name="TRAN_lowerarm_r" type="SimpleTransmission"> <actuator name="ACTU_rarm_r" /> <joint name="lowerarm_r" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="hand_r_z" type="revolute"> <parent link="LINK_lowerarm_r" /> <child link="LINK_hand_r_z" /> <origin rpy="-6.247486908250721e-06 4.551301344690728e-07 7.734677898163511e-10" xyz="-2.997148840222508e-08 0.2597350478172302 -2.2118911147117615e-08" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <link name="LINK_hand_r_z"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <transmission name="TRAN_hand_r_z" type="SimpleTransmission"> <actuator name="ACTU__r_z" /> <joint name="hand_r_z" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="hand_r_x" type="revolute"> <parent link="LINK_hand_r_z" /> <child link="LINK_hand_r" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-1.0471975511965976" upper="1.0471975511965976" velocity="1000" /> </joint> <transmission name="TRAN_hand_r_x" type="SimpleTransmission"> <actuator name="ACTU__r_x" /> <joint name="hand_r_x" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <joint name="lfoot_surface" type="fixed"> <parent link="LINK_ball_l" /> <child link="LINK_lfoot_surface" /> <origin rpy="-1.9086440872229105e-08 -1.0715857534648876e-08 1.5707961320877075" xyz="-0.001955525716766715 -0.10177090018987656 -0.03230590000748634" /> </joint> <joint name="rfoot_surface" type="fixed"> <parent link="LINK_ball_r" /> <child link="LINK_rfoot_surface" /> <origin rpy="-4.235107198269361e-08 -4.705588096953761e-08 1.5707961320877075" xyz="0.0019559389911592007 -0.10177121311426163 -0.03230592980980873" /> </joint> <joint name="lfoot_surface_0" type="fixed"> <parent link="LINK_lfoot_surface" /> <child link="LINK_lfoot_surface_0" /> <origin rpy="0.0 -0.0 0.0" xyz="-0.15000000596046448 0.05000000074505806 0.0" /> </joint> <joint name="rfoot_surface_0" type="fixed"> <parent link="LINK_rfoot_surface" /> <child link="LINK_rfoot_surface_0" /> <origin rpy="0.0 -0.0 0.0" xyz="-0.15000000596046448 0.05000000074505806 0.0" /> </joint> <joint name="lfoot_surface_1" type="fixed"> <parent link="LINK_lfoot_surface" /> <child link="LINK_lfoot_surface_1" /> <origin rpy="0.0 -0.0 0.0" xyz="-0.15000000596046448 -0.05000000074505806 0.0" /> </joint> <joint name="rfoot_surface_1" type="fixed"> <parent link="LINK_rfoot_surface" /> <child link="LINK_rfoot_surface_1" /> <origin rpy="0.0 -0.0 0.0" xyz="-0.15000000596046448 -0.05000000074505806 0.0" /> </joint> <joint name="lfoot_surface_2" type="fixed"> <parent link="LINK_lfoot_surface" /> <child link="LINK_lfoot_surface_2" /> <origin rpy="0.0 -0.0 0.0" xyz="0.15000000596046448 0.05000000074505806 0.0" /> </joint> <joint name="rfoot_surface_2" type="fixed"> <parent link="LINK_rfoot_surface" /> <child link="LINK_rfoot_surface_2" /> <origin rpy="0.0 -0.0 0.0" xyz="0.15000000596046448 0.05000000074505806 0.0" /> </joint> <joint name="lfoot_surface_3" type="fixed"> <parent link="LINK_lfoot_surface" /> <child link="LINK_lfoot_surface_3" /> <origin rpy="0.0 -0.0 0.0" xyz="0.15000000596046448 -0.05000000074505806 0.0" /> </joint> <joint name="rfoot_surface_3" type="fixed"> <parent link="LINK_rfoot_surface" /> <child link="LINK_rfoot_surface_3" /> <origin rpy="0.0 -0.0 0.0" xyz="0.15000000596046448 -0.05000000074505806 0.0" /> </joint> <joint name="Root_Tx" type="prismatic"> <parent link="LINK_World" /> <child link="LINK_Root_Tx" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-1000" upper="1000" velocity="1000" /> </joint> <transmission name="TRAN_Root_Tx" type="SimpleTransmission"> <actuator name="ACTU_Root_Tx" /> <joint name="Root_Tx" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <link name="LINK_Root_Tx"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <joint name="Root_Ty" type="prismatic"> <parent link="LINK_Root_Tx" /> <child link="LINK_Root_Ty" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-1000" upper="1000" velocity="1000" /> </joint> <transmission name="TRAN_Root_Ty" type="SimpleTransmission"> <actuator name="ACTU_Root_Ty" /> <joint name="Root_Ty" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <link name="LINK_Root_Ty"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <joint name="Root_Tz" type="prismatic"> <parent link="LINK_Root_Ty" /> <child link="LINK_Root_Tz" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-1000" upper="1000" velocity="1000" /> </joint> <transmission name="TRAN_Root_Tz" type="SimpleTransmission"> <actuator name="ACTU_Root_Tz" /> <joint name="Root_Tz" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <link name="LINK_Root_Tz"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <joint name="Root_Eulx" type="revolute"> <parent link="LINK_Root_Tz" /> <child link="LINK_Root_Eulx" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="1 0 0" /> <limit effort="1000.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="1000" /> </joint> <transmission name="TRAN_Root_Eulx" type="SimpleTransmission"> <actuator name="ACTU_Root_Eulx" /> <joint name="Root_Eulx" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <link name="LINK_Root_Eulx"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <joint name="Root_Euly" type="revolute"> <parent link="LINK_Root_Eulx" /> <child link="LINK_Root_Euly" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 1 0" /> <limit effort="1000.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="1000" /> </joint> <transmission name="TRAN_Root_Euly" type="SimpleTransmission"> <actuator name="ACTU_Root_Euly" /> <joint name="Root_Euly" /> <mechanicalReduction>1</mechanicalReduction> </transmission> <link name="LINK_Root_Euly"> <inertial> <mass value="0.001" /> <origin xyz="0 0 0" /> <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" /> </inertial> </link> <joint name="Root_Eulz" type="revolute"> <parent link="LINK_Root_Euly" /> <child link="LINK_Root" /> <origin rpy="0 0 0" xyz="0 0 0" /> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="1000" /> </joint> <transmission name="TRAN_Root_Eulz" type="SimpleTransmission"> <actuator name="ACTU_Root_Eulz" /> <joint name="Root_Eulz" /> <mechanicalReduction>1</mechanicalReduction> </transmission> </robot>

Code snippet:

`import torch
import sys

sys.path.append("/home/shikui/dev/differentiable-robot-model/")
import differentiable_robot_model.urdf_utils as u
import differentiable_robot_model.robot_model as m

model = m.DifferentiableRobotModel("/home/shikui/dev/catkin_ws/src/walker_gazebo/4/4_sim_lipm_Trans_EulXYZ_ROOT.urdf")
print(model._n_dofs)

tt= torch.zeros((1,38))

a,b = model.compute_forward_kinematics(tt, "LINK_thigh_r")
print(a,b)

a,b = model.compute_forward_kinematics(tt, "LINK_thigh_r_y")
print(a,b)

a,b = model.compute_forward_kinematics(tt, "LINK_thigh_r")
print(a,b) `

Sample output
tensor([[0., 0., 0.]]) tensor([[0., 0., 0., 1.]])
tensor([[1.1053e-01, 1.4901e-08, 0.0000e+00]]) tensor([[-0.6813, -0.0047, -0.0050, 0.7320]])
tensor([[1.1053e-01, 1.4901e-08, 0.0000e+00]]) tensor([[-0.6813, -0.0047, -0.0050, 0.7320]])
Notice LINK_thigh_r position&orientation differs.

@Tengoles
Copy link

Tengoles commented Aug 1, 2022

@shikui08
So is free floating currently supported?

@shikui08
Copy link
Author

shikui08 commented Aug 2, 2022

@shikui08 So is free floating currently supported?

Hi~ Hasn't been following the updates of this repository closely. It's very possible free floating robots are still not supported, but I can't tell for sure.

@Tengoles
Copy link

Tengoles commented Aug 2, 2022

@shikui08
You said in another comment that you found a way to get around the free floating robot issue. Would really appreciate some guidance on how you did it.

@shikui08
Copy link
Author

shikui08 commented Aug 2, 2022

@shikui08 You said in another comment that you found a way to get around the free floating robot issue. Would really appreciate some guidance on how you did it.

Basically I replaced the free floating base with 3 slide joints and 3 hinge joints. This allows actuation on the free floating base, which changes the behavior of the robot and might not be expected.

@ortegatron
Copy link

Hi @fmeier , I wonder which are the changes need to support free base? If you help me laying them down, we could have that as a roadmap and work it on a PR

Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants