OpenRobotLab / HIMLoco

Learning-based locomotion control from OpenRobotLab, including Hybrid Internal Model & H-Infinity Locomotion Control
https://junfeng-long.github.io/HIMLoco/
Other
211 stars 22 forks source link

unexpected output of exported torchscript on real robot #7

Open Pansamic opened 1 month ago

Pansamic commented 1 month ago

policy training

interation 1500

python3 legged_gym/legged_gym/script/train.py --task go1 --headless

play policy in simulation

unitree go1 was walking nicely in environment.

step observation order and information

total 45 numbers

  1. commands (3)(x, y, angular) from unitree_legged_sdk
  2. base_ang_vel (3)(x, y, z) from unitree_legged_sdk
  3. projected_gravity (3)(x, y, z) example:(0,0,9.81)
  4. joint_pos (12)(FL_0, FL_1, FL_2, FR_0, FR_1, FR_2, RL_0, RL_1, RL_2, RR_0, RR_1, RR_2) joint_pos = (joint_pos_real - default_joint_pos) * joint_pos_scale default_joint_pos=[0.1000, 0.8000, -1.5000, -0.1000, 0.8000, -1.5000, 0.1000, 1.0000, -1.5000, -0.1000, 1.0000, -1.5000] joint_pos_scale=1.0
  5. joint_vel (12)(FL_0, FL_1, FL_2, FR_0, FR_1, FR_2, RL_0, RL_1, RL_2, RR_0, RR_1, RR_2) joint_vel = joint_vel_real * joint_vel_scale joint_vel_scale = 0.05
  6. actions (12) : last actions generated by model

model input information

using exported torchscript. model input tensor size : 45 * 6 = 270 6 step observations, from lastest to oldest, the first 45 values is the latest observation.

unexpected policy output

real robot condition: stand on ground and model output was not executed on real robot; velocity commands were all set to 0. actions increased very quickly and became very large the following is the observations.

1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[-0.0013732003280892968, -0.022861016914248466, 0.0020176672842353582]
3. projected_gravity:[-0.48675355315208435, 0.5906697511672974, -9.69249153137207]
4. joint_pos:[0.007182457949966192, -0.0007943391683511436, -0.3220614194869995, -0.0009452864760532975, 0.00883395690470934, -0.268369197845459, 0.008090781047940254, -0.08386248350143433, -0.43170642852783203, -0.02516731061041355, -0.05903494358062744, -0.3634810447692871]
5. joint_vel:[0.001372489263303578, -0.005249354522675276, 0.037090133875608444, -0.0001728608476696536, -0.006720082368701696, 0.03345485404133797, 0.0019887860398739576, 1.2262590644240845e-05, 0.024888401851058006, -0.0009515363490208983, 0.00013333007518667728, 0.030622486025094986]
6. actions:[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.011676287278532982, 0.018950607627630234, -0.004107602406293154]
3. projected_gravity:[-0.5217332243919373, 0.4896288514137268, -9.69630241394043]
4. joint_pos:[0.0070613413117825985, -0.011815357021987438, -0.22569811344146729, -0.0030041574500501156, -0.004730391316115856, -0.18217921257019043, 0.009725766256451607, -0.08168250322341919, -0.34390151500701904, -0.02625730074942112, -0.05951935052871704, -0.2900075912475586]
5. joint_vel:[0.0005337085458450019, 0.002751686843112111, -0.000312761461827904, -0.0014136681566014886, 0.0004291650839149952, -0.0005088179605081677, 0.001512599759735167, 0.00017541683337185532, 0.007920004427433014, 4.129163789912127e-05, 0.00010800767631735653, 0.004399401135742664]
6. actions:[6.928949356079102, -5.831372261047363, 4.250898838043213, 2.4623684883117676, -8.273643493652344, 10.48815631866455, -2.3887853622436523, -6.589196681976318, 5.876589298248291, -2.0439605712890625, 1.1672039031982422, 1.97944176197052]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.01061102282255888, 0.0048358547501266, 0.00814293697476387]
3. projected_gravity:[-0.5027029514312744, 0.4675188958644867, -9.69839859008789]
4. joint_pos:[0.007121899630874395, -0.009150910191237926, -0.22476959228515625, -0.0037913708947598934, -0.0029743195045739412, -0.18242144584655762, 0.010815756395459175, -0.08059251308441162, -0.33578717708587646, -0.025833407416939735, -0.05643105506896973, -0.28742384910583496]
5. joint_vel:[-0.0007422288181260228, 0.002196601126343012, 0.002516841981559992, -0.00040650530718266964, 0.004519312176853418, -5.738079380535055e-06, 0.0015583119820803404, 0.001330773113295436, 0.007788810878992081, 0.000874053337611258, 0.0032286036293953657, 0.002803420415148139]
6. actions:[10.088006973266602, -8.929499626159668, 7.603238582611084, 2.9546124935150146, -13.165000915527344, 16.146728515625, -3.1777000427246094, -9.536442756652832, 10.299056053161621, -2.927490472793579, 2.5608081817626953, 4.609965801239014]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.00022469612304121256, 0.006433751434087753, -0.006238131318241358]
3. projected_gravity:[-0.4745935797691345, 0.4423074722290039, -9.700997352600098]
4. joint_pos:[0.0070613413117825985, -0.008666503243148327, -0.21927928924560547, -0.004215256776660681, -0.0002493142965249717, -0.1823406219482422, 0.011421309784054756, -0.08119809627532959, -0.3248872756958008, -0.025591189041733742, -0.055219948291778564, -0.27987468242645264]
5. joint_vel:[-2.182964863095549e-06, 0.0008200380834750831, 0.0017973721260204911, 0.000280976586509496, 0.0006765943253412843, 0.00040259090019389987, 7.578006625408307e-05, 0.00042468408355489373, 0.004164538811892271, -0.000241755013121292, -0.0009721937822178006, 0.0046769604086875916]
6. actions:[10.55610466003418, -10.29757022857666, 8.746318817138672, 3.5950098037719727, -14.369781494140625, 17.94518280029297, -3.383251428604126, -10.195027351379395, 12.229521751403809, -3.221985101699829, 2.7596006393432617, 5.870493412017822]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.0010236443486064672, 0.003770590526983142, 0.0012187190586701035]
3. projected_gravity:[-0.4505600929260254, 0.44192245602607727, -9.702160835266113]
4. joint_pos:[0.007121899630874395, -0.007334279827773571, -0.21887552738189697, -0.004275815095752478, 0.000659000885207206, -0.1823406219482422, 0.011542418971657753, -0.0810164213180542, -0.31883180141448975, -0.025893965736031532, -0.057157695293426514, -0.2732943296432495]
5. joint_vel:[-6.967798253754154e-05, 0.0005331868887878954, -0.0003386172465980053, -0.00013091551954858005, 0.0010285641765221953, 0.0001135422135121189, -0.0002829436562024057, -0.0007715927786193788, 0.0033176024444401264, 0.00010313916573068127, -0.000553783611394465, 0.0019497914472594857]
6. actions:[12.49686050415039, -13.064316749572754, 11.406435012817383, 4.4220499992370605, -17.45119285583496, 22.602340698242188, -3.6138875484466553, -12.661463737487793, 14.93321418762207, -4.5642991065979, 3.483067512512207, 7.8643670082092285]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.001822592574171722, 0.003237958298996091, 0.0025502995122224092]
3. projected_gravity:[-0.4415949285030365, 0.44340378046035767, -9.702505111694336]
4. joint_pos:[0.007121899630874395, -0.007273721508681774, -0.21887552738189697, -0.005244696047157049, 0.0016278743278235197, -0.1823406219482422, 0.011784637346863747, -0.0809558629989624, -0.31705546379089355, -0.026075640693306923, -0.057036638259887695, -0.2713969945907593]
5. joint_vel:[-1.9270042685093358e-05, -0.00029218755662441254, -5.8212394833390135e-06, -0.0010926518589258194, 0.0007692882209084928, 5.6050223065540195e-05, -0.0004175931680947542, -0.00021231858409009874, 0.0007633155328221619, 0.00015441370487678796, 0.00015283508400898427, 0.0010156917851418257]
6. actions:[16.713092803955078, -19.475141525268555, 16.93473243713379, 5.902242183685303, -24.044116973876953, 32.52742385864258, -4.1791582107543945, -17.71593475341797, 20.09693717956543, -6.8972859382629395, 5.210487365722656, 11.014888763427734]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.0026215407997369766, -0.0026209955103695393, -0.0011781256180256605]
3. projected_gravity:[-0.4355737864971161, 0.4386352002620697, -9.702994346618652]
4. joint_pos:[0.0070613413117825985, -0.007515954785048962, -0.2188352346420288, -0.006213576998561621, 0.0021728991996496916, -0.1823406219482422, 0.01372239924967289, -0.0809558629989624, -0.31471407413482666, -0.026075640693306923, -0.056854963302612305, -0.2709529399871826]
5. joint_vel:[-0.0003094486892223358, -0.0001390860415995121, -0.00013787393982056528, 0.0005077939131297171, 0.0008050521137192845, -0.00027121114544570446, 0.0015229611890390515, 0.0005963622825220227, 0.0009828588226810098, 0.000278064253507182, -2.744298626566888e-06, 3.3997079299297184e-05]
6. actions:[20.617643356323242, -26.19365882873535, 22.3947696685791, 7.1527886390686035, -30.844730377197266, 42.56159591674805, -4.901954650878906, -22.28337287902832, 25.909605026245117, -8.926140785217285, 7.086697578430176, 14.781933784484863]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.001822592574171722, -0.001023098942823708, -0.002243389841169119]
3. projected_gravity:[-0.43514397740364075, 0.43256258964538574, -9.703286170959473]
4. joint_pos:[0.0070613413117825985, -0.007939803414046764, -0.21822965145111084, -0.006213576998561621, 0.002051782561466098, -0.1823406219482422, 0.014872947707772255, -0.08113753795623779, -0.3128166198730469, -0.026075640693306923, -0.0569760799407959, -0.2709529399871826]
5. joint_vel:[-0.00037652687751688063, -0.0007130668964236975, 0.0006724459817633033, 0.0003494581033010036, -4.786930367117748e-05, -0.00021618639584630728, 0.0003611071442719549, -0.0003425601462367922, 0.0013972794404253364, 0.0002016305224969983, -0.0007315383991226554, -0.0001271205983357504]
6. actions:[23.241621017456055, -31.826608657836914, 26.67198944091797, 8.008234024047852, -36.02915573120117, 50.546287536621094, -5.502819538116455, -25.393056869506836, 30.680517196655273, -10.260581016540527, 8.537100791931152, 18.331703186035156]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.0004910121788270772, 0.0029716421850025654, -0.004107602406293154]
3. projected_gravity:[-0.43430280685424805, 0.43105000257492065, -9.703391075134277]
4. joint_pos:[0.0070613413117825985, -0.007939803414046764, -0.21814894676208496, -0.006274127867072821, 0.002051782561466098, -0.1823406219482422, 0.015296833589673042, -0.081076979637146, -0.31241297721862793, -0.026075640693306923, -0.056854963302612305, -0.2709529399871826]
5. joint_vel:[-0.0006432170048356056, 8.670214447192848e-05, 0.00012783663987647742, 5.6327746278839186e-05, 0.00016934778250288218, -5.839273944729939e-05, 0.00035378788015805185, -5.779949788120575e-05, 0.00043830019421875477, 8.947400056058541e-05, 0.00010710385686252266, -1.4449149603024125e-05]
6. actions:[26.82671546936035, -37.92388916015625, 31.580907821655273, 9.097639083862305, -41.75901412963867, 59.52756118774414, -6.220808982849121, -29.29197120666504, 35.95832824707031, -11.975293159484863, 9.9877290725708, 22.120561599731445]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[-0.0019058325560763478, 0.0016400618478655815, 0.0001534547918708995]
3. projected_gravity:[-0.43060094118118286, 0.4314161241054535, -9.703539848327637]
4. joint_pos:[0.007121899630874395, -0.007758128456771374, -0.21810853481292725, -0.0063952370546758175, 0.0021123408805578947, -0.1823406219482422, 0.015417942777276039, -0.08077418804168701, -0.31180739402770996, -0.026136184111237526, -0.056854963302612305, -0.2706298828125]
5. joint_vel:[0.00027062243316322565, 0.000660703401081264, 2.2037552298570517e-06, -0.0006993875140324235, -0.0005917589878663421, -0.00043015708797611296, 5.326433893060312e-05, -0.00018817544332705438, 0.0005511617055162787, -0.00010001878399634734, -2.934649273811374e-05, 0.0004300281289033592]
6. actions:[31.21095848083496, -44.51274108886719, 37.25325393676758, 10.377047538757324, -48.567386627197266, 69.51942443847656, -6.973023414611816, -33.753902435302734, 41.983116149902344, -14.024188041687012, 11.343810081481934, 26.605497360229492]
------------------------------------------------------------
1. commands:[0.0, -0.0, -0.0]
2. base_ang_vel:[0.0020889085717499256, -0.0007567828288301826, 0.0004197708622086793]
3. projected_gravity:[-0.4290333390235901, 0.43306154012680054, -9.703536033630371]
4. joint_pos:[0.007121899630874395, -0.007697629742324352, -0.21814894676208496, -0.006637462880462408, 0.0025361895095556974, -0.18230032920837402, 0.015539051964879036, -0.08035033941268921, -0.3116055727005005, -0.02625730074942112, -0.056673288345336914, -0.2701455354690552]
5. joint_vel:[-0.00013794549158774316, 3.5359207686269656e-05, -0.0005031601176597178, -0.00014782571815885603, 0.0013007100205868483, 0.00023133963986765593, 0.0005254722782410681, 0.00018189483671449125, 6.352984200930223e-05, 0.0007128644501790404, 0.00046459148870781064, -6.30738795734942e-05]
6. actions:[36.6580810546875, -52.517059326171875, 44.17629623413086, 11.961630821228027, -56.81327819824219, 81.67680358886719, -7.855365753173828, -39.30169677734375, 49.31625747680664, -16.531007766723633, 13.063660621643066, 31.865007400512695]
Junfeng-Long commented 1 month ago

Sorry for the late reply. There is something wrong with the export script, we already fixed it. Please try again. And please notice that in this implementation, projected_gravity is a unit vector only indicates direction, not similar to (0,0,-9.81). Please also make sure that you do all the pre-process of observations exactly the same as _computeobservations.

Pansamic commented 1 month ago

Thanks for your fix. My deployment works, but there are still some little problems.

  1. legs will oscillate when robot stops running.
  2. hip angle is too large, the left and right legs will move closer to the middle during walking. sometimes falls even hip_reduction is set to 0.1.
  3. the knee joint will hit the ground when walking. Actaully hit ground in simulation. image

I tried python deployment but it's too slow and only 20Hz control frequency (actually I don't know how to optimize python code). So I export ONNX model as torchcript export

Junfeng-Long commented 1 month ago
  1. Try a lower target height, for example, 0.25m for go1.
  2. The ‘hip_reduction’ is useless since Unitree already considered the reduction of hip joints, setting it to 1.0 is just fine.
  3. This gait is related to reward functions and robots, we did not do much work on editing reward functions to find a good gait, our work focuses on state estimation and sim2real. Please try to find a good gait by yourself.