Comments (5)
For those of you who still struggle with the issue of nan
values, this is my solution.
I tested training the model with one agent only (instead of the 4096 by default) to see what was happening to my biped. After a few iterations it fell on the ground but the simulation did not stop and the robot was basically trying to push itself back on its feet with huge actions on the motors. This made the biped start jumping very high and induced the nan
values.
To test why the simulation did not stop when the robot was on the ground I ran the test_env.py file and realised that I did not specify all of the parts that should stop the simulation when on the ground. I added them and also reduced the max_angular_velocity
and max_linear_velocity
to 10 (instead of 1000.). Basically all the changes are in the class asset of the your_robot_config.py file:
class asset( LeggedRobotCfg.asset ):
file = '{LEGGED_GYM_ROOT_DIR}/resources/robots/your_robot/urdf/your_robot.urdf'
name = "your_robot"
foot_name = 'your_foot'
terminate_after_contacts_on = ['torso','right_arm','etc'] # make sure to specify all the parts terminating the sim
flip_visual_attachments = False
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
max_angular_velocity = 10. # by default set to 1000. in legged_robot_config.py
max_linear_velocity = 10.
Hope this helps!
from legged_gym.
Found out that some of the observation means are nan:
[nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan],
, any hints why this could happen?
from legged_gym.
I had something similar like this once because at some point some rotations became singular and that "injected" NaN values into the system, from then on everything is NaN.
from legged_gym.
Having the Identical issue.
Traceback (most recent call last):
File "legged_gym/scripts/train.py", line 47, in <module>
train(args)
File "legged_gym/scripts/train.py", line 43, in train
ppo_runner.learn(num_learning_iterations=train_cfg.runner.max_iterations, init_at_random_ep_len=True)
File "/home/simon/Downloads/rsl_rl/rsl_rl/runners/on_policy_runner.py", line 132, in learn
mean_value_loss, mean_surrogate_loss = self.alg.update()
File "/home/simon/Downloads/rsl_rl/rsl_rl/algorithms/ppo.py", line 131, in update
self.actor_critic.act(obs_batch, masks=masks_batch, hidden_states=hid_states_batch[0])
File "/home/simon/Downloads/rsl_rl/rsl_rl/modules/actor_critic.py", line 124, in act
self.update_distribution(observations)
File "/home/simon/Downloads/rsl_rl/rsl_rl/modules/actor_critic.py", line 121, in update_distribution
self.distribution = Normal(mean, mean*0. + self.std)
File "/home/simon/miniconda3/envs/rlgpu/lib/python3.8/site-packages/torch/distributions/normal.py", line 50, in __init__
super(Normal, self).__init__(batch_shape, validate_args=validate_args)
File "/home/simon/miniconda3/envs/rlgpu/lib/python3.8/site-packages/torch/distributions/distribution.py", line 55, in __init__
raise ValueError(
ValueError: Expected parameter loc (Tensor of shape (6144, 18)) of distribution Normal(loc: torch.Size([6144, 18]), scale: torch.Size([6144, 18])) to satisfy the constraint Real(), but found invalid values:
tensor([[nan, nan, nan, ..., nan, nan, nan],
[nan, nan, nan, ..., nan, nan, nan],
[nan, nan, nan, ..., nan, nan, nan],
...,
[nan, nan, nan, ..., nan, nan, nan],
[nan, nan, nan, ..., nan, nan, nan],
[nan, nan, nan, ..., nan, nan, nan]], device='cuda:0',
grad_fn=<AddmmBackward0>)
from legged_gym.
I am having the same issue; have you found a way to solve it?
Traceback (most recent call last):
File "train.py", line 47, in <module>
train(args)
File "train.py", line 43, in train
ppo_runner.learn(num_learning_iterations=train_cfg.runner.max_iterations, init_at_random_ep_len=True)
File "/home/robin-lab/rsl_rl/rsl_rl/runners/on_policy_runner.py", line 107, in learn
actions = self.alg.act(obs, critic_obs)
File "/home/robin-lab/rsl_rl/rsl_rl/algorithms/ppo.py", line 94, in act
self.transition.actions = self.actor_critic.act(obs).detach()
File "/home/robin-lab/rsl_rl/rsl_rl/modules/actor_critic.py", line 125, in act
self.update_distribution(observations)
File "/home/robin-lab/rsl_rl/rsl_rl/modules/actor_critic.py", line 122, in update_distribution
self.distribution = Normal(mean, mean*0. + self.std)
File "/home/robin-lab/anaconda3/envs/isaac/lib/python3.8/site-packages/torch/distributions/normal.py", line 50, in __init__
super(Normal, self).__init__(batch_shape, validate_args=validate_args)
File "/home/robin-lab/anaconda3/envs/isaac/lib/python3.8/site-packages/torch/distributions/distribution.py", line 56, in __init__
raise ValueError(
ValueError: Expected parameter loc (Tensor of shape (4096, 10)) of distribution Normal(loc: torch.Size([4096, 10]), scale: torch.Size([4096, 10])) to satisfy the constraint Real(), but found invalid values:
tensor([[ 0.0094, 0.0462, 0.1332, ..., -0.0147, -0.0388, -0.1170],
[-0.0048, 0.0742, 0.1166, ..., 0.0325, -0.0363, 0.0715],
[ 0.0712, 0.0424, 0.1967, ..., -0.0338, -0.0136, -0.0345],
...,
[-0.0758, 0.1650, 0.0851, ..., -0.0418, 0.0612, 0.1154],
[-0.0100, 0.0359, 0.1483, ..., -0.1286, 0.0016, 0.0814],
[ 0.0160, -0.0444, 0.2055, ..., 0.0365, -0.0442, -0.1798]],
device='cuda:0')
This is always caused by an agent having all observation values being nan: [nan, nan, nan, nan, nan, nan, nan, nan, nan, nan]
Any help would be much appreciated! Thanks!
from legged_gym.
Related Issues (20)
- Self Collisions HOT 2
- Different URDF with Official Unitree A1 HOT 1
- Failed to train unitree aliengo robot using legged_gym HOT 2
- How to train the actuator network? HOT 2
- How to get the coordinates of the robot's toe end position? HOT 1
- RuntimeError: Error building extension 'gymtorch' HOT 1
- how does the privileged observation work? HOT 1
- Segmentation fault (core dumped) while running legged_gym/scripts/train HOT 2
- Using trained weights on real-robot: Minimal Example
- Why up_axis=gymapi.UP_AXIS_Z is not set?
- in `legged_gym/legged_gym/utils/terrain.py`, there is a little bug HOT 1
- [Question] How to obtain the position of AnyMal HOT 4
- [Question] Troubles with play.py script after training HOT 1
- How to add more assets in the envs? HOT 2
- Adding Observation History to Policy
- [Error] [carb.gym.plugin] Gym cuda error: invalid resource handle: ../../../source/plugins/carb/gym/impl/Gym/GymPhysX.cpp: 6137 HOT 1
- RuntimeError: Failed to acquire interface: carb::gym::Gym (pluginName: nullptr)
- A question about the parameter(num_observations)
- Unexpected low performance
- Fail to support different envs HOT 2
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from legged_gym.