Browse Source

Add piper rerun example

tags/v0.3.7rc1
haixuanTao 1 year ago
parent
commit
3dfcbabf5b
6 changed files with 2523 additions and 0 deletions
  1. +568
    -0
      examples/piper/assets/piper_left.urdf
  2. +568
    -0
      examples/piper/assets/piper_left_pred.urdf
  3. +568
    -0
      examples/piper/assets/piper_right.urdf
  4. +568
    -0
      examples/piper/assets/piper_right_pred.urdf
  5. +229
    -0
      examples/piper/piper_inference.py
  6. +22
    -0
      examples/piper/play_inference.yml

+ 568
- 0
examples/piper/assets/piper_left.urdf View File

@@ -0,0 +1,568 @@
<?xml version="1.0" encoding="utf-8"?>
<robot
name="piper_description">
<link
name="base_link">
<!-- <inertial>
<origin
xyz="-0.00973928490005031 1.8312708928633E-06 0.0410140167677137"
rpy="0 0 0" />
<mass
value="0.162352169522719" />
<inertia
ixx="0.000226592553127906"
ixy="-7.33974356968813E-08"
ixz="2.13221970218123E-06"
iyy="0.000269447877479622"
iyz="8.15167478685076E-09"
izz="0.000222318286704" />
</inertial> -->
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="0.00131676031927021 0.000310288842008364 -0.00922874512303438"
rpy="0 0 0" />
<mass
value="0.0978679932242825" />
<inertia
ixx="7.76684558296781E-05"
ixy="1.09084650459916E-07"
ixz="-1.97480532432411E-06"
iyy="9.24967780161546E-05"
iyz="9.91284646834672E-07"
izz="8.24589062407806E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0 0 0.123"
rpy="0 0 -1.5708" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="0 0 1" />
<limit
lower="-2.618"
upper="2.618"
effort="100"
velocity="0" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.147615838821413 -0.0174259998251393 0.00175952516190707"
rpy="0 0 0" />
<mass
value="0.289571136953082" />
<inertia
ixx="0.000150112628108228"
ixy="8.58974959950769E-05"
ixz="-1.07428153464285E-06"
iyy="0.00172585302855383"
iyz="-9.93704792239686E-07"
izz="0.00177445942914759" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.10095 -1.5708" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="3.14"
effort="100"
velocity="1" />
</joint>
<link
name="link3">
<inertial>
<origin
xyz="0.0156727246030052 0.104466514905741 0.000508486764144372"
rpy="0 0 0" />
<mass
value="0.290583247455324" />
<inertia
ixx="0.000221686352136266"
ixy="-7.57426543992343E-06"
ixz="-6.3700062772173E-07"
iyy="0.000100859162015934"
iyz="-8.16202696860781E-07"
izz="0.000241839316548946" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
</collision>
</link>
<joint
name="joint3"
type="revolute">
<origin
xyz="0.28503 0 0"
rpy="0 0 1.3826" />
<parent
link="link2" />
<child
link="link3" />
<axis
xyz="0 0 1" />
<limit
lower="-2.967"
upper="0"
effort="100"
velocity="1" />
</joint>
<link
name="link4">
<inertial>
<origin
xyz="0.000276464622388145 -0.00102803669324853 -0.00472830700561612"
rpy="0 0 0" />
<mass
value="0.127087348341362" />
<inertia
ixx="3.82011730423098E-05"
ixy="-4.92358351033589E-08"
ixz="4.89589432983109E-08"
iyy="4.87048555222491E-05"
iyz="6.70802942486707E-08"
izz="4.10592077565155E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
</collision>
</link>
<joint
name="joint4"
type="revolute">
<origin
xyz="0.021984 0.25075 0"
rpy="-1.5708 0 0" />
<parent
link="link3" />
<child
link="link4" />
<axis
xyz="0 0 1" />
<limit
lower="-1.832"
upper="1.832"
effort="100"
velocity="1" />
</joint>
<link
name="link5">
<inertial>
<origin
xyz="8.82261259100015E-05 0.056682908434204 -0.00196119077436732"
rpy="0 0 0" />
<mass
value="0.144711209371719" />
<inertia
ixx="4.39644269159173E-05"
ixy="-3.59214840853815E-08"
ixz="-1.89785003257649E-08"
iyy="5.63173857792457E-05"
iyz="-2.15407623722543E-07"
izz="4.88713595021005E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
</collision>
</link>
<joint
name="joint5"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.087266 0" />
<parent
link="link4" />
<child
link="link5" />
<axis
xyz="0 0 1" />
<limit
lower="-1.22"
upper="1.22"
effort="100"
velocity="1" />
</joint>
<link
name="link6">
<inertial>
<origin
xyz="9.41121070072333E-09 0.000341209775988838 0.0342122921883722"
rpy="0 0 0" />
<mass
value="0.150196458571266" />
<inertia
ixx="4.31750564711759E-05"
ixy="-2.21295720427027E-08"
ixz="-3.27825836857102E-12"
iyy="9.99756357365307E-05"
iyz="1.10337380549335E-07"
izz="0.000118282295533688" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
</collision>
</link>
<joint
name="joint6"
type="revolute">
<origin
xyz="0 0.091 0.0014165"
rpy="-1.5708 -1.5708 0" />
<parent
link="link5" />
<child
link="link6" />
<axis
xyz="0 0 1" />
<limit
lower="-3.14"
upper="3.14"
effort="100"
velocity="1" />
</joint>

<link
name="link7">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
</collision>
</link>
<joint
name="joint7"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link7" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint>

<link
name="link8">
<inertial>
<origin
xyz="0.000277795911672651 0.0467673513153836 -0.00921029799058583"
rpy="0 0 0" />
<mass
value="0.0264822490707451" />
<inertia
ixx="9.99782474142963E-06"
ixy="-1.57547666236405E-07"
ixz="2.71355834243046E-08"
iyy="6.17952362333486E-06"
iyz="1.58939503259658E-06"
izz="1.42102248648757E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="-1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="0.038"
effort="100"
velocity="1" />
</joint>
<!-- <link
name="link8">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="-0.037167 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint> -->
</robot>

+ 568
- 0
examples/piper/assets/piper_left_pred.urdf View File

@@ -0,0 +1,568 @@
<?xml version="1.0" encoding="utf-8"?>
<robot
name="piper_description">
<link
name="base_link">
<!-- <inertial>
<origin
xyz="-0.00973928490005031 1.8312708928633E-06 0.0410140167677137"
rpy="0 0 0" />
<mass
value="0.162352169522719" />
<inertia
ixx="0.000226592553127906"
ixy="-7.33974356968813E-08"
ixz="2.13221970218123E-06"
iyy="0.000269447877479622"
iyz="8.15167478685076E-09"
izz="0.000222318286704" />
</inertial> -->
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="0.00131676031927021 0.000310288842008364 -0.00922874512303438"
rpy="0 0 0" />
<mass
value="0.0978679932242825" />
<inertia
ixx="7.76684558296781E-05"
ixy="1.09084650459916E-07"
ixz="-1.97480532432411E-06"
iyy="9.24967780161546E-05"
iyz="9.91284646834672E-07"
izz="8.24589062407806E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0 0 0.123"
rpy="0 0 -1.5708" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="0 0 1" />
<limit
lower="-2.618"
upper="2.618"
effort="100"
velocity="0" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.147615838821413 -0.0174259998251393 0.00175952516190707"
rpy="0 0 0" />
<mass
value="0.289571136953082" />
<inertia
ixx="0.000150112628108228"
ixy="8.58974959950769E-05"
ixz="-1.07428153464285E-06"
iyy="0.00172585302855383"
iyz="-9.93704792239686E-07"
izz="0.00177445942914759" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.10095 -1.5708" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="3.14"
effort="100"
velocity="1" />
</joint>
<link
name="link3">
<inertial>
<origin
xyz="0.0156727246030052 0.104466514905741 0.000508486764144372"
rpy="0 0 0" />
<mass
value="0.290583247455324" />
<inertia
ixx="0.000221686352136266"
ixy="-7.57426543992343E-06"
ixz="-6.3700062772173E-07"
iyy="0.000100859162015934"
iyz="-8.16202696860781E-07"
izz="0.000241839316548946" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
</collision>
</link>
<joint
name="joint3"
type="revolute">
<origin
xyz="0.28503 0 0"
rpy="0 0 1.3826" />
<parent
link="link2" />
<child
link="link3" />
<axis
xyz="0 0 1" />
<limit
lower="-2.967"
upper="0"
effort="100"
velocity="1" />
</joint>
<link
name="link4">
<inertial>
<origin
xyz="0.000276464622388145 -0.00102803669324853 -0.00472830700561612"
rpy="0 0 0" />
<mass
value="0.127087348341362" />
<inertia
ixx="3.82011730423098E-05"
ixy="-4.92358351033589E-08"
ixz="4.89589432983109E-08"
iyy="4.87048555222491E-05"
iyz="6.70802942486707E-08"
izz="4.10592077565155E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
</collision>
</link>
<joint
name="joint4"
type="revolute">
<origin
xyz="0.021984 0.25075 0"
rpy="-1.5708 0 0" />
<parent
link="link3" />
<child
link="link4" />
<axis
xyz="0 0 1" />
<limit
lower="-1.832"
upper="1.832"
effort="100"
velocity="1" />
</joint>
<link
name="link5">
<inertial>
<origin
xyz="8.82261259100015E-05 0.056682908434204 -0.00196119077436732"
rpy="0 0 0" />
<mass
value="0.144711209371719" />
<inertia
ixx="4.39644269159173E-05"
ixy="-3.59214840853815E-08"
ixz="-1.89785003257649E-08"
iyy="5.63173857792457E-05"
iyz="-2.15407623722543E-07"
izz="4.88713595021005E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
</collision>
</link>
<joint
name="joint5"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.087266 0" />
<parent
link="link4" />
<child
link="link5" />
<axis
xyz="0 0 1" />
<limit
lower="-1.22"
upper="1.22"
effort="100"
velocity="1" />
</joint>
<link
name="link6">
<inertial>
<origin
xyz="9.41121070072333E-09 0.000341209775988838 0.0342122921883722"
rpy="0 0 0" />
<mass
value="0.150196458571266" />
<inertia
ixx="4.31750564711759E-05"
ixy="-2.21295720427027E-08"
ixz="-3.27825836857102E-12"
iyy="9.99756357365307E-05"
iyz="1.10337380549335E-07"
izz="0.000118282295533688" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
</collision>
</link>
<joint
name="joint6"
type="revolute">
<origin
xyz="0 0.091 0.0014165"
rpy="-1.5708 -1.5708 0" />
<parent
link="link5" />
<child
link="link6" />
<axis
xyz="0 0 1" />
<limit
lower="-3.14"
upper="3.14"
effort="100"
velocity="1" />
</joint>

<link
name="link7">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
</collision>
</link>
<joint
name="joint7"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link7" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint>

<link
name="link8">
<inertial>
<origin
xyz="0.000277795911672651 0.0467673513153836 -0.00921029799058583"
rpy="0 0 0" />
<mass
value="0.0264822490707451" />
<inertia
ixx="9.99782474142963E-06"
ixy="-1.57547666236405E-07"
ixz="2.71355834243046E-08"
iyy="6.17952362333486E-06"
iyz="1.58939503259658E-06"
izz="1.42102248648757E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="-1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="0.038"
effort="100"
velocity="1" />
</joint>
<!-- <link
name="link8">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="1 0 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="-0.037167 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint> -->
</robot>

+ 568
- 0
examples/piper/assets/piper_right.urdf View File

@@ -0,0 +1,568 @@
<?xml version="1.0" encoding="utf-8"?>
<robot
name="piper_description">
<link
name="base_link">
<!-- <inertial>
<origin
xyz="-0.00973928490005031 1.8312708928633E-06 0.0410140167677137"
rpy="0 0 0" />
<mass
value="0.162352169522719" />
<inertia
ixx="0.000226592553127906"
ixy="-7.33974356968813E-08"
ixz="2.13221970218123E-06"
iyy="0.000269447877479622"
iyz="8.15167478685076E-09"
izz="0.000222318286704" />
</inertial> -->
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="0.00131676031927021 0.000310288842008364 -0.00922874512303438"
rpy="0 0 0" />
<mass
value="0.0978679932242825" />
<inertia
ixx="7.76684558296781E-05"
ixy="1.09084650459916E-07"
ixz="-1.97480532432411E-06"
iyy="9.24967780161546E-05"
iyz="9.91284646834672E-07"
izz="8.24589062407806E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0 0 0.123"
rpy="0 0 -1.5708" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="0 0 1" />
<limit
lower="-2.618"
upper="2.618"
effort="100"
velocity="0" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.147615838821413 -0.0174259998251393 0.00175952516190707"
rpy="0 0 0" />
<mass
value="0.289571136953082" />
<inertia
ixx="0.000150112628108228"
ixy="8.58974959950769E-05"
ixz="-1.07428153464285E-06"
iyy="0.00172585302855383"
iyz="-9.93704792239686E-07"
izz="0.00177445942914759" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.10095 -1.5708" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="3.14"
effort="100"
velocity="1" />
</joint>
<link
name="link3">
<inertial>
<origin
xyz="0.0156727246030052 0.104466514905741 0.000508486764144372"
rpy="0 0 0" />
<mass
value="0.290583247455324" />
<inertia
ixx="0.000221686352136266"
ixy="-7.57426543992343E-06"
ixz="-6.3700062772173E-07"
iyy="0.000100859162015934"
iyz="-8.16202696860781E-07"
izz="0.000241839316548946" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
</collision>
</link>
<joint
name="joint3"
type="revolute">
<origin
xyz="0.28503 0 0"
rpy="0 0 1.3826" />
<parent
link="link2" />
<child
link="link3" />
<axis
xyz="0 0 1" />
<limit
lower="-2.967"
upper="0"
effort="100"
velocity="1" />
</joint>
<link
name="link4">
<inertial>
<origin
xyz="0.000276464622388145 -0.00102803669324853 -0.00472830700561612"
rpy="0 0 0" />
<mass
value="0.127087348341362" />
<inertia
ixx="3.82011730423098E-05"
ixy="-4.92358351033589E-08"
ixz="4.89589432983109E-08"
iyy="4.87048555222491E-05"
iyz="6.70802942486707E-08"
izz="4.10592077565155E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
</collision>
</link>
<joint
name="joint4"
type="revolute">
<origin
xyz="0.021984 0.25075 0"
rpy="-1.5708 0 0" />
<parent
link="link3" />
<child
link="link4" />
<axis
xyz="0 0 1" />
<limit
lower="-1.832"
upper="1.832"
effort="100"
velocity="1" />
</joint>
<link
name="link5">
<inertial>
<origin
xyz="8.82261259100015E-05 0.056682908434204 -0.00196119077436732"
rpy="0 0 0" />
<mass
value="0.144711209371719" />
<inertia
ixx="4.39644269159173E-05"
ixy="-3.59214840853815E-08"
ixz="-1.89785003257649E-08"
iyy="5.63173857792457E-05"
iyz="-2.15407623722543E-07"
izz="4.88713595021005E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
</collision>
</link>
<joint
name="joint5"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.087266 0" />
<parent
link="link4" />
<child
link="link5" />
<axis
xyz="0 0 1" />
<limit
lower="-1.22"
upper="1.22"
effort="100"
velocity="1" />
</joint>
<link
name="link6">
<inertial>
<origin
xyz="9.41121070072333E-09 0.000341209775988838 0.0342122921883722"
rpy="0 0 0" />
<mass
value="0.150196458571266" />
<inertia
ixx="4.31750564711759E-05"
ixy="-2.21295720427027E-08"
ixz="-3.27825836857102E-12"
iyy="9.99756357365307E-05"
iyz="1.10337380549335E-07"
izz="0.000118282295533688" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
</collision>
</link>
<joint
name="joint6"
type="revolute">
<origin
xyz="0 0.091 0.0014165"
rpy="-1.5708 -1.5708 0" />
<parent
link="link5" />
<child
link="link6" />
<axis
xyz="0 0 1" />
<limit
lower="-3.14"
upper="3.14"
effort="100"
velocity="1" />
</joint>

<link
name="link7">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
</collision>
</link>
<joint
name="joint7"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link7" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint>

<link
name="link8">
<inertial>
<origin
xyz="0.000277795911672651 0.0467673513153836 -0.00921029799058583"
rpy="0 0 0" />
<mass
value="0.0264822490707451" />
<inertia
ixx="9.99782474142963E-06"
ixy="-1.57547666236405E-07"
ixz="2.71355834243046E-08"
iyy="6.17952362333486E-06"
iyz="1.58939503259658E-06"
izz="1.42102248648757E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="-1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="0.038"
effort="100"
velocity="1" />
</joint>
<!-- <link
name="link8">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="-0.037167 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint> -->
</robot>

+ 568
- 0
examples/piper/assets/piper_right_pred.urdf View File

@@ -0,0 +1,568 @@
<?xml version="1.0" encoding="utf-8"?>
<robot
name="piper_description">
<link
name="base_link">
<!-- <inertial>
<origin
xyz="-0.00973928490005031 1.8312708928633E-06 0.0410140167677137"
rpy="0 0 0" />
<mass
value="0.162352169522719" />
<inertia
ixx="0.000226592553127906"
ixy="-7.33974356968813E-08"
ixz="2.13221970218123E-06"
iyy="0.000269447877479622"
iyz="8.15167478685076E-09"
izz="0.000222318286704" />
</inertial> -->
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/base_link.stl" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="0.00131676031927021 0.000310288842008364 -0.00922874512303438"
rpy="0 0 0" />
<mass
value="0.0978679932242825" />
<inertia
ixx="7.76684558296781E-05"
ixy="1.09084650459916E-07"
ixz="-1.97480532432411E-06"
iyy="9.24967780161546E-05"
iyz="9.91284646834672E-07"
izz="8.24589062407806E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link1.stl" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0 0 0.123"
rpy="0 0 -1.5708" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="0 0 1" />
<limit
lower="-2.618"
upper="2.618"
effort="100"
velocity="0" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.147615838821413 -0.0174259998251393 0.00175952516190707"
rpy="0 0 0" />
<mass
value="0.289571136953082" />
<inertia
ixx="0.000150112628108228"
ixy="8.58974959950769E-05"
ixz="-1.07428153464285E-06"
iyy="0.00172585302855383"
iyz="-9.93704792239686E-07"
izz="0.00177445942914759" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link2.stl" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.10095 -1.5708" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="3.14"
effort="100"
velocity="1" />
</joint>
<link
name="link3">
<inertial>
<origin
xyz="0.0156727246030052 0.104466514905741 0.000508486764144372"
rpy="0 0 0" />
<mass
value="0.290583247455324" />
<inertia
ixx="0.000221686352136266"
ixy="-7.57426543992343E-06"
ixz="-6.3700062772173E-07"
iyy="0.000100859162015934"
iyz="-8.16202696860781E-07"
izz="0.000241839316548946" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link3.stl" />
</geometry>
</collision>
</link>
<joint
name="joint3"
type="revolute">
<origin
xyz="0.28503 0 0"
rpy="0 0 1.3826" />
<parent
link="link2" />
<child
link="link3" />
<axis
xyz="0 0 1" />
<limit
lower="-2.967"
upper="0"
effort="100"
velocity="1" />
</joint>
<link
name="link4">
<inertial>
<origin
xyz="0.000276464622388145 -0.00102803669324853 -0.00472830700561612"
rpy="0 0 0" />
<mass
value="0.127087348341362" />
<inertia
ixx="3.82011730423098E-05"
ixy="-4.92358351033589E-08"
ixz="4.89589432983109E-08"
iyy="4.87048555222491E-05"
iyz="6.70802942486707E-08"
izz="4.10592077565155E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link4.stl" />
</geometry>
</collision>
</link>
<joint
name="joint4"
type="revolute">
<origin
xyz="0.021984 0.25075 0"
rpy="-1.5708 0 0" />
<parent
link="link3" />
<child
link="link4" />
<axis
xyz="0 0 1" />
<limit
lower="-1.832"
upper="1.832"
effort="100"
velocity="1" />
</joint>
<link
name="link5">
<inertial>
<origin
xyz="8.82261259100015E-05 0.056682908434204 -0.00196119077436732"
rpy="0 0 0" />
<mass
value="0.144711209371719" />
<inertia
ixx="4.39644269159173E-05"
ixy="-3.59214840853815E-08"
ixz="-1.89785003257649E-08"
iyy="5.63173857792457E-05"
iyz="-2.15407623722543E-07"
izz="4.88713595021005E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link5.stl" />
</geometry>
</collision>
</link>
<joint
name="joint5"
type="revolute">
<origin
xyz="0 0 0"
rpy="1.5708 -0.087266 0" />
<parent
link="link4" />
<child
link="link5" />
<axis
xyz="0 0 1" />
<limit
lower="-1.22"
upper="1.22"
effort="100"
velocity="1" />
</joint>
<link
name="link6">
<inertial>
<origin
xyz="9.41121070072333E-09 0.000341209775988838 0.0342122921883722"
rpy="0 0 0" />
<mass
value="0.150196458571266" />
<inertia
ixx="4.31750564711759E-05"
ixy="-2.21295720427027E-08"
ixz="-3.27825836857102E-12"
iyy="9.99756357365307E-05"
iyz="1.10337380549335E-07"
izz="0.000118282295533688" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link6.stl" />
</geometry>
</collision>
</link>
<joint
name="joint6"
type="revolute">
<origin
xyz="0 0.091 0.0014165"
rpy="-1.5708 -1.5708 0" />
<parent
link="link5" />
<child
link="link6" />
<axis
xyz="0 0 1" />
<limit
lower="-3.14"
upper="3.14"
effort="100"
velocity="1" />
</joint>

<link
name="link7">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link7.stl" />
</geometry>
</collision>
</link>
<joint
name="joint7"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link7" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint>

<link
name="link8">
<inertial>
<origin
xyz="0.000277795911672651 0.0467673513153836 -0.00921029799058583"
rpy="0 0 0" />
<mass
value="0.0264822490707451" />
<inertia
ixx="9.99782474142963E-06"
ixy="-1.57547666236405E-07"
ixz="2.71355834243046E-08"
iyy="6.17952362333486E-06"
iyz="1.58939503259658E-06"
izz="1.42102248648757E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="0 0 0.13503"
rpy="-1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 1" />
<limit
lower="0"
upper="0.038"
effort="100"
velocity="1" />
</joint>
<!-- <link
name="link8">
<inertial>
<origin
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
rpy="0 0 0" />
<mass
value="0.0264822500394006" />
<inertia
ixx="9.99782519244544E-06"
ixy="-1.57547595978589E-07"
ixz="-2.71355785017816E-08"
iyy="6.17952364356547E-06"
iyz="-1.58939504838734E-06"
izz="1.42102253390315E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
<material
name="">
<color
rgba="0 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="assets/link8.stl" />
</geometry>
</collision>
</link>
<joint
name="joint8"
type="prismatic">
<origin
xyz="-0.037167 0 0.13503"
rpy="1.5708 0 1.5708" />
<parent
link="link6" />
<child
link="link8" />
<axis
xyz="0 0 -1" />
<limit
lower="-0.038"
upper="0"
effort="100"
velocity="1" />
</joint> -->
</robot>

+ 229
- 0
examples/piper/piper_inference.py View File

@@ -0,0 +1,229 @@
from dora import Node

node = Node()

import numpy as np

pred = np.array(
[
[
[
-0.0737,
-0.0447,
0.2695,
-0.0054,
-0.0461,
-0.0258,
0.1357,
0.1943,
0.0625,
0.1270,
-0.0259,
-0.0195,
0.0981,
0.1021,
],
[
-0.0757,
-0.0332,
0.2793,
-0.0156,
-0.0374,
-0.0193,
0.1924,
0.2119,
0.0654,
0.1377,
0.0020,
-0.0076,
0.0884,
0.1143,
],
[
-0.0771,
-0.0282,
0.2832,
-0.0225,
-0.0378,
-0.0156,
0.1992,
0.2324,
0.0674,
0.1416,
0.0088,
-0.0056,
0.0918,
0.1191,
],
[
-0.0825,
-0.0325,
0.2832,
-0.0210,
-0.0420,
-0.0204,
0.1904,
0.2256,
0.0610,
0.1475,
0.0068,
-0.0071,
0.0879,
0.1172,
],
[
-0.0825,
-0.0344,
0.2852,
-0.0208,
-0.0405,
-0.0167,
0.1777,
0.2109,
0.0518,
0.1621,
0.0059,
-0.0017,
0.0854,
0.1182,
],
[
-0.0840,
-0.0332,
0.2871,
-0.0226,
-0.0417,
-0.0159,
0.1748,
0.2080,
0.0476,
0.1641,
0.0000,
0.0010,
0.0864,
0.1196,
],
[
-0.0879,
-0.0234,
0.2969,
-0.0305,
-0.0396,
-0.0132,
0.1904,
0.2275,
0.0474,
0.1758,
0.0137,
0.0020,
0.0874,
0.1245,
],
[
-0.0884,
-0.0225,
0.3008,
-0.0339,
-0.0386,
-0.0118,
0.1904,
0.2275,
0.0469,
0.1855,
0.0186,
-0.0017,
0.0879,
0.1270,
],
[
-0.0918,
-0.0081,
0.3066,
-0.0449,
-0.0325,
-0.0074,
0.2021,
0.2363,
0.0454,
0.1953,
0.0332,
0.0015,
0.0942,
0.1348,
],
[
-0.0938,
-0.0249,
0.3027,
-0.0366,
-0.0396,
-0.0125,
0.1777,
0.2207,
0.0376,
0.1953,
0.0146,
-0.0017,
0.0884,
0.1279,
],
[
-0.0938,
-0.0229,
0.3047,
-0.0393,
-0.0386,
-0.0121,
0.1680,
0.2256,
0.0330,
0.2002,
0.0127,
0.0015,
0.0913,
0.1260,
],
[
-0.0977,
-0.0206,
0.3105,
-0.0405,
-0.0359,
-0.0161,
0.1680,
0.2178,
0.0295,
0.2129,
0.0146,
-0.0085,
0.0923,
0.1309,
],
[
-0.0938,
-0.0311,
0.3027,
-0.0334,
-0.0386,
-0.0188,
0.1377,
0.2139,
0.0227,
0.2031,
0.0039,
-0.0020,
0.0913,
0.1221,
],
]
]
)

import time
import pyarrow as pa

data = pred[0]
for joint in data:
node.send_output("jointstate_left", pa.array(joint[:7], type=pa.float32()))
node.send_output("jointstate_right", pa.array(joint[7:], type=pa.float32()))
time.sleep(0.1)

+ 22
- 0
examples/piper/play_inference.yml View File

@@ -0,0 +1,22 @@
nodes:
- id: piper
path: piper_inference.py
inputs:
tick: dora/timer/millis/20
outputs:
- jointstate_left
- jointstate_right
env:
CAN_BUS: can_left

- id: rerun
build: wget
path: dora-rerun
inputs:
jointstate_piper_left: piper/jointstate_left
jointstate_piper_right: piper/jointstate_right
env:
piper_left_urdf: assets/piper_left.urdf # Make sure to download assets/meshes from https://github.com/agilexrobotics/Piper_ros/tree/4f22c61f96b8fb3ef3f937b99b63edb697caadf0/src/piper_description/meshes and put them in the assets folder
piper_right_urdf: assets/piper_right.urdf # Make sure to download assets/meshes from https://github.com/agilexrobotics/Piper_ros/tree/4f22c61f96b8fb3ef3f937b99b63edb697caadf0/src/piper_description/meshes and put them in the assets folder
piper_left_transform: 0 0.2 0
piper_right_transform: 0 -0.2 0

Loading…
Cancel
Save