强化学习仿真环境Legged Gym的初步使用——训练一个二阶倒立摆
本篇教程将大致介绍Legged Gym的结构,使用方法,并以一个二阶倒立摆为例来完成一次实际的强化学习训练
回顾强化学习基本概念 —– 五元组
本章节将简要回顾强化学习中五元组的概念,需要读者对强化学习有基本的概念。若对强化学习缺少基本认知,建议先阅读OpenAI推出的Spinning up 系列教程。读者也可先大致阅读后续章节,对Legged Gym训练框架有初步认知。
首先我们回顾一下强化学习基本概念之一的五元组,即$M=<S,A,P,R,\gamma>$, 其中$S$表示状态集;$A$表示动作集 $P$ 表示状态和动作的条件转移概率,$R$ 奖励函数,最后$\gamma$表示回报率。 以下是这五元组的详细解释:
状态集($S$):
定义:状态集S是所有可能的状态的集合。在强化学习中,状态描述了环境当前的情况或配置。
特点:状态用于确定接下来会发生什么(行动、观察、奖励)。状态是关于历史的函数,即($S_t = f(H_t)$),其中($H_t$)是到时间$t$为止的历史信息。
动作集($A$):
定义:动作集$A$是在每个状态下所有可能的动作的集合。这些动作是智能体(Agent)可以选择执行的。
特点:动作是智能体与环境交互的方式,通过执行动作,智能体可以改变环境的状态。
转移概率($P$): 定义:转移概率$P$描述了从一个状态转移到另一个状态的概率分布,具体取决于当前状态和所选择的动作。
公式表示:($P(s’|s, a)$)表示在状态$s$执行动作$a$后转移到状态$s’$的概率。 特点:转移概率定义了环境的动态性,即如何从一个状态转移到另一个状态。
奖励函数($R$): 定义:奖励函数$R$是一个标量函数,用于量化智能体在给定状态下执行某个动作的好坏。
公式表示:($R(s, a)$)或($R(s, a, s’)$)表示在状态s执行动作$a$后(或转移到状态$s’$后)获得的即时奖励。
特点:奖励是强化学习的核心,它指导智能体如何学习以最大化长期累积奖励。
折扣因子($\gamma$):
定义:折扣因子$\gamma$是一个介于0和1之间的数,用于计算累积奖励时的折扣。 公式表示:在计算长期累积奖励时,未来的奖励会被$\gamma$折扣。例如,t时刻的累积奖励可以表示为$(G_t = R_{t+1} + \gamma R_{t+2} + \gamma^2 R_{t+3} + \ldots)$。
特点:折扣因子平衡了即时奖励和未来奖励的重要性。较大的$\gamma$值使智能体更加关注长远的奖励,而较小的$\gamma$值则使其更加关注眼前的奖励。
我们也可以用一个框图的形式来重新表述上述五元组的概念。
如上图所示,我们的智能体(即我们最终训练出的神经网络$P$)在$S_t$状态下执行了$A_t$动作(即神经网络输入为$S_t$输出为$A_t$),此时环境(即我们训练的仿真器)在接收到了$A_t$输入量后状态改变成了$S_{t+1}$,同时环境产生了$R_t$的奖励。最后计算环境产生的总汇报$G_t$时需要考虑折扣因子$\gamma$。
正如上图看到的那样,一个强化学习的训练框架主要可以分为训练智能体和编写环境两个部分 。训练智能体包括搭建神经网络模型如MLP、LSTM、Transformer等,和设计强化学习算法如DQN、PPO、SAC等。而编写环境包括计算$S_{t+1}$状态(调用刚体动力学引擎计算机器人状态),计算环境是否需要复位,以及最重要的编写奖励函数等。
对于初学者或者说对于使用强化学习应用开发来说,现有训练智能体的算法足以覆盖大部分应用场景,因此训练强化学习算法应主要集中在环境的编写上,特别是奖励函数的设计上 。
包括Legged Gym在内的大部分强化学习框架都是将训练智能体的算法(如PPO,SAC算法)等封装起来,同时更多的保留一些方便编写环境的接口供用户使用,用户使用这个框架时更多的是在编写环境,而无需关心训练网络的细节。
Legged Gym(ver. ZZS) 环境安装 从这里 下载最新稳定版Legger Gym(ver. ZZS)。并解压到待安装的位置(注意请妥善选择解压目录,安装后不可更改位置)。
在解压文件夹目录下激活前文所述 安装的python3.8虚拟环境。并执行pip install -e .
命令即可完成安装,无需再安装rsl_rl等。
在文件夹根目录下打开vscode,选择到左侧的扩展
窗口,选择到最下一栏的推荐页面,并安装推荐的拓展,包括如下:
1 2 3 4 5 6 "ms-python.python", "ms-python.vscode-pylance", "ms-python.pylint", "ms-python.debugpy", "ms-python.black-formatter", "gruntfuggly.todo-tree"
到这里我们基本完成了Legged Gym(ver. ZZS)的安装,下面训练测试一下。
选择vscode左侧边栏中的文件浏览界面并随机打开一个以.py
结尾的文件。之后在底部状态栏右侧选择激活前文所创建的虚拟环境,这里我命名为legged-gym
。
选择vscode左侧边栏中的的调试和运行界面,在弹出的界面顶部的下拉框中有配置好的train
和play
两种模式。我们选择train
模式,并单击左侧绿色小三角来开始第一次训练。若一切配置正确,可以看到在弹出的窗口中训练二阶倒立摆的场景。可以使用W
, S
, A
, D
, 和shift
, space
键来水平移动视角,或按住鼠标右键并拖动来旋转视角(类似于MineCraft 的操作键位)。
Legged Gym(ver. ZZS) 环境基本结构介绍 代码文件结构梳理 整个框架的主要文件作用如下表所示。在初步使用过程中我们主要关注./legged_gym/envs/
文件夹下的各种即可,强烈建议入门时详细阅读./legged_gym/envs/base/
文件夹下的legged_robot.py
和legged_robot_config.py
,以及大致阅读./scripts/
文件夹下train.py
,play.py
和./vscode/
文件夹下的launch.json
。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 :. │ ├───.vscode │ extensions.json │ launch.json #启动训练相关配置 │ settings.json #vscode其他相关配置 │ ├───legged_gym │ │ │ ├───algos #ppo算法模块 │ ├───envs │ │ ├── __init__.py #新写的环境需要在里注册 │ │ ├───base │ │ │ base_config.py #基础环境配置 │ │ │ base_task.py #基础环境 │ │ │ IsaacgymAdapter.py # deprecated, no use │ │ │ legged_robot.py # 适用于腿足机器人的通用环境 │ │ │ legged_robot_config.py #适用于腿足机器人的通用配置 │ │ │ │ │ └───cartpole2 │ │ cartpole2.py #二阶倒立摆环境 │ │ cartpole2_config.py #二阶倒立摆配置 │ ├───scripts │ │ play.py #仿真验证训练结果的脚本 │ │ train.py #训练网络模型的脚本 │ │ │ ├───tests │ │ test_env.py #测试新编写的环境是否可用的脚本 │ │ │ └───utils #一些工具集 │ dr_utils.py #deprecated, no use │ ExperimentLogger.py #记录实验参数 │ fast_dbg_viz.py #绘图工具(可用于绘制落脚点等) │ helpers.py #通用的各种帮助函数 │ logger.py #ETH的logger │ math.py #四元数相关的计算函数 │ rsl_utils.py #训练rnn网络的辅助工具 │ RunningMeanStd.py #ppo算法辅助工具 │ task_registry.py #新算法注册工具 │ terrain.py #地形生成工具 │ torch_jit_utils.py #四元数相关的更多函数 │ train_batch.py #deprecated, no use │ Zlog.py #ZZS的logger │ __init__.py │ └───resources #机器人的各种urdf文件和stl文件 └───robots ├───a1 │ ├───meshes │ └───urdf ├───anymal_b │ ├───meshes │ └───urdf ├───anymal_c │ ├───meshes │ └───urdf ├───cartpole │ ├───cartpole2.urdf #二阶倒立摆的urdf文件 │ └───cassie ├───meshes └───urdf
训练与测试 Legged Gym的训练与测试的入口程序分别是./script
文件夹下的train.py
和play.py
,在python环境中运行这两个文件并附带相应参数即可完成训练或测试。为了方便用户使用和调试,这里使用了vscode的launch.json
文件对其额外进行了一层封装来方便以图形化的方式在vscode中使用。用户可以在.vscode/launch.json
中找到相关的定义,关于vscode中更多关于运行和调试的配置可以点击这里 了解详情。
训练和测试支持各种参数,以下是一些常用参数和其含义,全部的参数定义参见./legged_gym/utils/helpers.py
文件中的get_args()
函数:
args
type
default
note
--task
str
anymal_c_flat
指定要训练的环境名称
--resume
bool
False
是否从上次训练的结果中继续训练
--load_run
str
None
上次训练的文件名(在--resume True
时生效)
--checkpoint
int
-1
设置载入训练模型的迭代次数,-1表示载入最后一次迭代
--headless
bool
False
是否弹出渲染界面,默认弹出
--num_envs
int
None
指定并行训练环境的个数,不指定则使用cfg文件中的值
--max_iterations
int
None
训练时最大迭代次数,不指定则使用cfg文件中的值
--seed
int
None
设置随机种子,不指定则使用cfg文件中的值
环境与配置简介 在使用Legged Gym训练框架时我们重点关注的是./env
环境下的内容,./env
文件夹下的各子文件夹表示不同环境和其对应的配置文件,base
文件夹下为最基本的环境配置。这些环境和其配置文件使用面向对象的方式编写,包含环境类如./env/base/legged_robot.py
中的LeggedRobot
类,环境配置类如./env/base/legged_robot_config.py
中的LeggedRobotCfg
类,和算法配置类如./env/base/legged_robot_config.py
中的LeggedRobotCfgPPO
类。其中环境类定义了不同的环境,环境配置类定义了环境中的相关参数,如奖励函数等,而算法配置类定义了强化学习算法相关的参数,如ppo的学习率等。其中所有环境的基类为./env/base/base_task.py
中的BaseTask
类,这个类定义了最基本的输入输出,初始化等。而所有环境配置类和算法配置类主要取决于环境和算法本身,没有太多的继承关系,不过仍需继承./env/base/base_config.py
中的BaseConfig
类来保证一些基本功能。
在Legged Gym中添加我们自己的环境主要包含定义新环境类和配置类,和注册相关类。定义新类基本就是创建一个新文件夹,拷贝legged_robot_config.py
和legged_robot.py
文件,修改以下环境的名称,修改以下输入输出等。下面主要讲一下如何注册相关类。打开./envs/__init__.py
文件,在其中加入我们想要新注册的类,以及取一个我们想要的名字即可,这个名字即--task name
参数中的name
。注意修改算法配置类中的runner的experiment_name 。
关于更多isaacgym仿真器的使用方法,建议大家阅读isaacgym官方tutorial和api参考手册 。
1 2 3 4 5 6 7 8 9 10 from .cartpole2.cartpole2 import Cartpole2Taskfrom .cartpole2.cartpole2_config import Cartpole2Config, Cartpole2ConfigPPOtask_registry.register("cartpole2" , Cartpole2Task, Cartpole2Config(), Cartpole2ConfigPPO())
强化学习实践第一步 —— 二阶倒立摆训练 上文简要介绍了Legged Gym的基本框架和使用方法,下面我将以一个二阶倒立摆为例实际介绍一个环境应该如何搭建。该环境定义在./envs/cartpole2/cartpole2.py
中,环境相关配置文件定义在./envs/cartpole2/cartpole2_config.py
中,所有类均需按照上文所述的方法在./envs/__init__.py
中注册。
环境初始化 环境初始化主要包含创建isaacgym仿真器实例,设置相关缓存,导入智能体模型与配置,创建模型实例与获取相关状态矩阵,创建地面,初始化奖励函数等(略过了一些不太重要的步骤,完整步骤参见代码)。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 def __init__ (self, cfg: Cartpole2Config, sim_params, physics_engine, sim_device, headless ): self.cfg = cfg self.sim_params = sim_params self.init_done = False self._parse_cfg(self.cfg) super ().__init__(self.cfg, sim_params, physics_engine, sim_device, headless) if not self.headless: self.set_camera(self.cfg.viewer.pos, self.cfg.viewer.lookat) self._init_buffers() self._prepare_reward_function() self.init_done = True
在父类构造函数中调用了create_sim()
函数,在其中创建了仿真器实例,地面和创建了智能体。
1 2 3 4 5 6 7 8 9 10 def create_sim (self ): """Creates simulation, terrain and evironments""" self.sim = self.gym.create_sim( self.sim_device_id, self.graphics_device_id, self.physics_engine, self.sim_params, ) self._create_ground_plane() self._create_envs()
我们重点关注一下_create_envs()
这个函数,这个函数首先从cartpole_config.asset.file
中读取了urdf文件并将其导入。导入时配置了一系列选项。
1 2 3 4 5 6 7 8 9 asset_path = self.cfg.asset.file.format (LEGGED_GYM_ROOT_DIR=LEGGED_GYM_ROOT_DIR) asset_root = os.path.dirname(asset_path) asset_file = os.path.basename(asset_path) asset_options = gymapi.AssetOptions() robot_asset = self.gym.load_asset(self.sim, asset_root, asset_file, asset_options)
之后在一个循环中创建了环境实例,并对每个实例修改了关节驱动模式的参数。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 start_pose = gymapi.Transform() start_pose.p = gymapi.Vec3(0.0 , 0.0 , 0.5 ) env_lower = gymapi.Vec3(0.0 , 0.0 , 0.0 ) env_upper = gymapi.Vec3(self.cfg.env.env_spacing, self.cfg.env.env_spacing, 0.0 ) self.actor_handles = [] self.envs = [] for i in range (self.num_envs): env_handle = self.gym.create_env(self.sim, env_lower, env_upper, int (np.sqrt(selfnum_envs))) actor_handle = self.gym.create_actor( env_handle, robot_asset, start_pose, self.cfg.asset.name, i, self.cfg.asset.self_collisions, 0 , ) dof_props = self.gym.get_actor_dof_properties(env_handle, actor_handle) dof_props["driveMode" ][0 ] = gymapi.DOF_MODE_EFFORT dof_props["driveMode" ][1 ] = gymapi.DOF_MODE_NONE dof_props["driveMode" ][2 ] = gymapi.DOF_MODE_NONE dof_props["stiffness" ][:] = 0.0 dof_props["damping" ][:] = 0.0 self.gym.set_actor_dof_properties(env_handle, actor_handle, dof_props) self.envs.append(env_handle) self.actor_handles.append(actor_handle)
此外我们再关注一下_init_buffers()
这个函数,该函数在创建缓存之外还从isaacgym仿真器中获取到了保存倒立摆智能体关节角信息的相关矩阵,并将其转换为了pytorch张量。
1 2 3 4 5 6 dof_state_tensor = self.gym.acquire_dof_state_tensor(self.sim) self.gym.refresh_dof_state_tensor(self.sim) self.dof_state = gymtorch.wrap_tensor(dof_state_tensor) self.dof_pos = self.dof_state.view(self.num_envs, self.num_dof, 2 )[..., 0 ] self.dof_vel = self.dof_state.view(self.num_envs, self.num_dof, 2 )[..., 1 ]
观测与奖励 二阶倒立摆环境的观测包括各个关节角的速度和位置,是一个6维向量。观测时刷新isaacgym仿真器中的关节角状态,之后将其输入到观测矩阵中。其中观测量的维度在cartpole2_config.py
中的Cartpole2Config.env.num_observations
定义。注意计算观测值前需要将关节角状态矩阵刷新,计算观测值最后需要对观测值限幅。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 self.gym.refresh_dof_state_tensor(self.sim) def compute_observations (self ): """Computes observations""" self.obs_buf = torch.cat( ( (self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos, self.dof_vel * self.obs_scales.dof_vel, ), dim=-1 , ) clip_obs = self.cfg.normalization.clip_observations self.obs_buf = torch.clip(self.obs_buf, -clip_obs, clip_obs)
奖励函数是强化学习算法中的核心,在实验中奖励函数定义为如下: $$ r_t=(AngleScale\cdot(PoleAngle^2+PoleAngle2^2)+ VelScale\cdot(|CartVel|+|PoleVel|+|Pole2Vel|)+TerminationReward)\cdot dt $$ 其中 $AngleScale$,$VelScale$定义在cartpole2_config.py
中的Cartpole2Config.rewards.scales
中,均为负值,$dt$为仿真的最小时间片长度在这里定义为Cartpole2Config.sim.dt
*Cartpole2Config.control.decimation
。该函数的含义为关节角速度越小,关节角越接近0点(即竖直状态),那么奖励越大,且倒立摆倒下时还需要被惩罚。
奖励函数的定义如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 def _reward_joint_angle (self ): pole_angle = self.dof_pos[:, 1 ] pole_angle2 = self.dof_pos[:, 2 ] reward = pole_angle * pole_angle + pole_angle2 * pole_angle2 * 2 return reward def _reward_joint_velocity (self ): cart_vel = self.dof_vel[:, 0 ] pole_vel = self.dof_vel[:, 1 ] pole_vel2 = self.dof_vel[:, 2 ] reward = torch.abs (cart_vel) + torch.abs (pole_vel) + torch.abs (pole_vel2) return reward def _reward_termination (self ): cart_pos = self.dof_pos[:, 0 ] pole_angle = self.dof_pos[:, 1 ] pole_angle2 = self.dof_pos[:, 2 ] reward = torch.zeros(self.num_envs, dtype=torch.float , device=self.device) reward = torch.where(torch.abs (cart_pos) > 3 , torch.ones_like(reward) * -2.0 , reward) reward = torch.where(torch.abs (pole_angle) > torch.pi / 2 , torch.ones_like(reward) * -2.0 , reward) reward = torch.where(torch.abs (pole_angle2) > torch.pi / 2 , torch.ones_like(reward) * -2.0 , reward) return reward
这些奖励函数由_prepare_reward_function()
函数在环境初始化时初始化,和由self.compute_reward()
函数在每个step中调用并计算奖励。这两个函数在本入门教程中就不细讲了,建议读者自行阅读源代码理解。
编写复位函数 复位函数的作用在于单个环境中的智能体训练超过一定时间后或当其陷入不可挽回的状态后及时复位防止收集到过多无效状态影响训练效果。复位函数主要包括根据条件找出需要复位的智能体以及复位该智能体对应的环境。
找出待复位的环境定义在check_termination()
函数中,主要根据关节角度和训练时间来判断是否需要复位,并将结果记录在```reset_buf``变量中。
1 2 3 4 5 6 7 8 9 10 11 12 def check_termination (self ): """Check if environments need to be reset""" self.reset_buf = torch.zeros_like(self.episode_length_buf) self.time_out_buf = self.episode_length_buf > self.max_episode_length self.reset_buf |= self.time_out_buf cart_pos = self.dof_pos[:, 0 ] pole_angle = self.dof_pos[:, 1 ] pole_angle2 = self.dof_pos[:, 2 ] self.reset_buf |= torch.abs (cart_pos) > 3.0 self.reset_buf |= torch.abs (pole_angle) > torch.pi / 2 self.reset_buf |= torch.abs (pole_angle2) > torch.pi / 2
实际执行复位的函数为reset_idx()
,该函数将重置关节角,重置训练时长,以及记录一下当前训练片段的累计奖励等。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 def reset_idx (self, env_ids ): if len (env_ids) == 0 : return self._reset_dofs(env_ids) self.episode_length_buf[env_ids] = 0 self.reset_buf[env_ids] = 1 self.extras["episode" ] = {} for key in self.episode_sums.keys(): self.extras["episode" ]["rew_" + key] = ( torch.mean(self.episode_sums[key][env_ids]) / self.max_episode_length_s ) self.episode_sums[key][env_ids] = 0.0 if self.cfg.env.send_timeouts: self.extras["time_outs" ] = self.time_out_buf def _reset_dofs (self, env_ids ): positions = 0.2 * (torch.rand((len (env_ids), self.num_dof), device=self.device) - 0.5 ) velocities = 0.5 * (torch.rand((len (env_ids), self.num_dof), device=self.device) - 0.5 ) self.dof_pos[env_ids, :] = positions[:] self.dof_vel[env_ids, :] = velocities[:] env_ids_int32 = env_ids.to(dtype=torch.int32) self.gym.set_dof_state_tensor_indexed( self.sim, gymtorch.unwrap_tensor(self.dof_state), gymtorch.unwrap_tensor(env_ids_int32), len (env_ids_int32), )
编写step函数 step函数是强化学习环境中的核心函数,在每一步迭代中都会调用。如前文的基本概念所述,环境需要做的就是接收动作策略的输入,并提供相应的下一时刻的输出,和这一步策略所获得的奖励。由此可以得出step函数的编写主要流程。 (1) 该函数首先接受由策略提供的action,并计算出对应的torque; (2) 然后将torque应用到仿真中,进行一次仿真; (3) 仿真完成后,调用post_physics_step()函数,检查终止条件,计算奖励,更新观测等。 (4) 最后返回观测,奖励,终止标志等信息。强化学习仿真环境的编写主要过程包括:应用action,仿真,计算奖励,检查终止条件,更新观测,返回信息。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 def step (self, actions ): clip_actions = self.cfg.normalization.clip_actions self.actions = torch.clip(actions, -clip_actions, clip_actions).to(self.device) self.render() for _ in range (self.cfg.control.decimation): self.torques = self._compute_torques(self.actions).view(self.torques.shape) self.gym.set_dof_actuation_force_tensor( self.sim, gymtorch.unwrap_tensor(self.torques) ) self.gym.simulate(self.sim) if self.device == "cpu" : self.gym.fetch_results(self.sim, True ) self.gym.refresh_dof_state_tensor(self.sim) self.post_physics_step() clip_obs = self.cfg.normalization.clip_observations self.obs_buf = torch.clip(self.obs_buf, -clip_obs, clip_obs) if self.privileged_obs_buf is not None : self.privileged_obs_buf = torch.clip(self.privileged_obs_buf, -clip_obs, clip_obs) return ( self.obs_buf, self.privileged_obs_buf, self.rew_buf, self.reset_buf, self.extras, ) def post_physics_step (self ): """check terminations, compute observations and rewards calls self._post_physics_step_callback() for common computations calls self._draw_debug_vis() if needed """ self.gym.refresh_dof_state_tensor(self.sim) self.episode_length_buf += 1 self.common_step_counter += 1 self.check_termination() self.compute_reward() env_ids = self.reset_buf.nonzero(as_tuple=False ).flatten() self.reset_idx(env_ids) self.compute_observations()
以上就是二阶倒立摆环境的大致内容,值得注意的是该环境的奖励函数编写的并不够充分,并不能实现完美的平衡效果 ,各位读者可以自行尝试更改奖励函数的形式或者权重参数来获得更好的效果。
EOF