legged_gym代码阅读及解释

提示:文章写完后,目录可以自动生成,如何生成可参考右边的帮助文档


前言(持续更新)

legged_gym是苏黎世联邦理工大学(ETH)机器人系统实验室开源的基于英伟达推出的仿真平台Issac gym(目前该平台已不再更新维护)的足式机器人仿真框架。

注意:该框架完全运行起来依赖强化学习框架rsl_rl和Issac gym,本文不对强化学习框架rsl_rl和仿真平台脚本进行描述解释。

该文章为本人阅读legged_gym过程中的个人理解,其中包含了本人在阅读理解过程中各种不懂的问题。对于读者可能显得有些冗余,望理解。有些问题本人目前也解释不清,在网络上已经存在很多对于该代码讲解与解释的视频,可搜索查阅。

一、legged_gym代码框架

legged_gym
       ├──envs 存放训练机器人环境的设置脚本,设置包括强化学习算法PPO参数、奖励函数定义、机器人URDF读取等
                ├──__init__.py机器人、环境注册脚本
                └──机器人文件夹
                       ├──机器人.py机器人、环境注册脚本
                       └──机器人_config.py环境、地形、指令、奖励函数设置
       ├──scripts存放训练和查看训练结果的脚本
                ├──train.py训练脚本
                └──play.py查看训练效果脚本
       ├──tests
                └──test_env.py测试训练环境搭建情况的脚本
       ├──utils包含了各种类型转化,姿态向量、范数计算的脚本
                ├──__init__.py初始化脚本,明确训练对象
                ├──task_register.py任务注册脚本,主要是对于参数的读取(参数来自于envs下的脚本),设置等
                ├──helper.py参数的初始化,训练环境的设置等
                ├──logger.pylog文件读取,储存等
                ├──math.py类型转化、范数计算
                └──terrain.py设置训练地形
       ├──licenses
       ├──logs储存log日志文件,训练模型文件
       ├──resources储存机器人URDF和mesh文件
       └──__init__.py初始化脚本,指定了当前的根目录LEGGED_GYM_ROOT_DIR以及环境设置目录LEGGED_GYM_ROOT_DIR

如下图为脚本代码调用的基本逻辑,实际代码中存在交叉调用,这里只展示主要流程,不包括Issac gym和rsl_rl。以anymal_c_rough为例,第一张图为大流程,第二张图展示了参数的来源。

调用
调用
调用
参数
调用
实际参数
实际参数
task_registry.py
train.py
helper.py
envs/__init__.py
anymal.py
anymal_c_rough_config.py
调用
调用
调用
参数
调用
类继承
继承修改参数
实际参数
参数结构
实际参数
类继承
类继承
调用
调用
task_registry.py
train.py
helper.py
envs/__init__.py
anymal.py
legged_robot.py
legged_robot_config.py
anymal_c_rough_config.py
base_task.py
base_config.py
terrain.py
math.py

二、脚本代码阅读

1.scripts/train.py

train.py是强化学习训练代码运行的入口,代码如下:

def train(args):
    ## 接收终端启动程序时给定的参数args,返回环境env以及环境初始化参数env_cfg,见2.1节
    env, env_cfg = task_registry.make_env(name=args.task, args=args)
    ## 进行算法相关设置,见2.2节
    ppo_runner, train_cfg = task_registry.make_alg_runner(env=env, name=args.task, args=args)
    ppo_runner.learn(num_learning_iterations=train_cfg.runner.max_iterations, init_at_random_ep_len=True)
## 该框架的入口
if __name__ == '__main__':
    ## 首先执行获取参数的函数,该函数的定义在utils/helper.py里
    args = get_args()
    train(args)

2.utils/task_registry.py

2.1 make_env函数

该函数在train.py中被调用,主要功能是接收终端启动程序时给定的参数args,返回环境env以及环境初始化参数env_cfg,代码如下:

## 该函数中名称后的->代表该函数返回的是VecEnv, LeggedRobotCfg类型的两个参数,也就是对于函数返回值类型的一个声明,类似于C++中的指定。
def make_env(self, name, args=None, env_cfg=None) -> Tuple[VecEnv, LeggedRobotCfg]:    
    ## 如果用户没有指定参数,那么调用helper.py中的get_args()函数
    if args is None:
        args = get_args()
    ## 检查指定训练的机器人模型,环境是否注册存在,这里的注册,我认为就是是否声明以及初始化
    if name in self.task_classes:
        task_class = self.get_task_class(name)
    else:
    	## 如果没有注册,通过raise关键字将异常抛出
        raise ValueError(f"Task with name: {name} was not registered")
    if env_cfg is None:
        ## 如果环境参数没有,调用helper.py中的get_args()函数获取环境参数。env_cfg中包含的参数见6节
        env_cfg, _ = self.get_cfgs(name)
    ## 用终端读入的参数覆盖默认参数
    env_cfg, _ = update_cfg_from_args(env_cfg, None, args)
    ## 设置种子
    ## seed 是指随机数生成器的种子(seed value)。它用于控制随机过程的初始化,确保实验的可重复性。
    set_seed(env_cfg.seed)
    ## 仿真参数解析
    ## 将普通参数转化为字典值
    sim_params = {"sim": class_to_dict(env_cfg.sim)}
    sim_params = parse_sim_params(args, sim_params)
    env = task_class(   cfg=env_cfg,
                        sim_params=sim_params,
                        physics_engine=args.physics_engine,
                        sim_device=args.sim_device,
                        headless=args.headless)
    return env, env_cfg

2.2 make_alg_runner函数

该函数在train.py中被调用,主要功能是接收终端启动程序时给定的参数args,创建强化学习训练算法,代码如下:

def make_alg_runner(self, env, name=None, args=None, train_cfg=None, log_root="default") -> Tuple[OnPolicyRunner, LeggedRobotCfgPPO]:
    ## 如果用户没有指定参数,那么调用helper.py中的get_args()函数
    if args is None:
        args = get_args()
    ## 如果训练参数从终端读取后有值的话就使用,否则调用helper.py中的get_args()函数
    if train_cfg is None:
        if name is None:
            raise ValueError("Either 'name' or 'train_cfg' must be not None")
        ## 这里的下划线_代表第一个参数在此处不需要使用和考虑
        _, train_cfg = self.get_cfgs(name)
    else:
        if name is not None:
            print(f"'train_cfg' provided -> Ignoring 'name={name}'")
    ## 将指定的参数覆盖掉默认的参数
    _, train_cfg = update_cfg_from_args(None, train_cfg, args)
	## 设置log文件储存的名称以及位置
    if log_root=="default":
    	## LEGGED_GYM_ROOT_DIR在legged_gym里的初始化脚本里定义,就是legged_gym的根目录
    	## log_root最终为logs文件夹下用户指定的试验名称的文件名字,试验名称可在终端启动时指定,默认值在legged_robot_config.py下的
    	runner结构体中给定
    	## log_dir在此基础上设定系统当前时间,以月日_时_分_秒_运行名称创建目录,如:Jan20_17_02_51_test,代表120170251秒
        log_root = os.path.join(LEGGED_GYM_ROOT_DIR, 'logs', train_cfg.runner.experiment_name)
        log_dir = os.path.join(log_root, datetime.now().strftime('%b%d_%H-%M-%S') + '_' + train_cfg.runner.run_name)
    elif log_root is None:
        log_dir = None
    else:
        log_dir = os.path.join(log_root, datetime.now().strftime('%b%d_%H-%M-%S') + '_' + train_cfg.runner.run_name)
    ## 创建训练参数字典变量
    train_cfg_dict = class_to_dict(train_cfg)
    ## 调用rsl_rl下的函数,设置PPO强化学习算法相关参数
    runner = OnPolicyRunner(env, train_cfg_dict, log_dir, device=args.rl_device)
    ## 在创建新的log_dir时保存之前模型储存路径
    resume = train_cfg.runner.resume
    if resume:
        ## 加载之前训练的模型
        resume_path = get_load_path(log_root, load_run=train_cfg.runner.load_run, checkpoint=train_cfg.runner.checkpoint)
        print(f"Loading model from: {resume_path}")
        runner.load(resume_path)
    return runner, train_cfg

2.3 register函数

在envs文件夹下的__init__.py中调用了register函数,代码如下:

## 根据指定的任务类型,将训练的地形环境、机器人类型、强化学习算法参数进行读取
def register(self, name: str, task_class: VecEnv, env_cfg: LeggedRobotCfg, train_cfg: LeggedRobotCfgPPO):
    self.task_classes[name] = task_class
    self.env_cfgs[name] = env_cfg
    self.train_cfgs[name] = train_cfg

3.utils/helper.py

def get_args():
    custom_parameters = [
        ## --task参数是指定训练任务的,比如 --task=anymal_c_rough,一般会将任务的配置文件放在envs文件夹下
        {"name": "--task", "type": str, "default": "anymal_c_flat", "help": "Resume training or start testing from a checkpoint. Overrides config file if provided."},
        ## --resume参数
        {"name": "--resume", "action": "store_true", "default": False,  "help": "Resume training from a checkpoint"},
        {"name": "--experiment_name", "type": str,  "help": "Name of the experiment to run or load. Overrides config file if provided."},
        {"name": "--run_name", "type": str,  "help": "Name of the run. Overrides config file if provided."},
        {"name": "--load_run", "type": str,  "help": "Name of the run to load when resume=True. If -1: will load the last run. Overrides config file if provided."},
        ## --checkpoint参数是使用哪个训练好的模型,比如训练500次的还是1000次的模型
        {"name": "--checkpoint", "type": int,  "help": "Saved model checkpoint number. If -1: will load the last checkpoint. Overrides config file if provided."},
        ## --headless参数是在训练过程中是否开启issac gym可视化界面,若纯训练可关闭--headless=ture,否则会影响训练速度
        {"name": "--headless", "action": "store_true", "default": False, "help": "Force display off at all times"},
        ## --horovod参数是训练是否采用多卡同时训练,本人未使用过,不知道还需要怎样设置
        {"name": "--horovod", "action": "store_true", "default": False, "help": "Use horovod for multi-gpu training"},
        ## --rl_device参数是指定训练的GPU卡
        {"name": "--rl_device", "type": str, "default": "cuda:0", "help": 'Device used by the RL algorithm, (cpu, gpu, cuda:0, cuda:1 etc..)'},
        ## --num_envs参数是指定一次训练中有多少个智能体,智能体越多训练效率高,但是对GPU显存的要求也高。
        {"name": "--num_envs", "type": int, "help": "Number of environments to create. Overrides config file if provided."},
        {"name": "--seed", "type": int, "help": "Random seed. Overrides config file if provided."},
        ## --max_iterations参数是指定训练的最多迭代次数
        {"name": "--max_iterations", "type": int, "help": "Maximum number of training iterations. Overrides config file if provided."},
    ]
    ## issac gym中解析参数的函数。该函数的作用就是将上述参数导入到issac gym中
    args = gymutil.parse_arguments(
        description="RL Policy",
        custom_parameters=custom_parameters)

    ## 参数的赋值
    args.sim_device_id = args.compute_device_id
    args.sim_device = args.sim_device_type
    if args.sim_device=='cuda':
        args.sim_device += f":{args.sim_device_id}"
    return args

4.utils/terrain.py

4.1 __init__函数

该函数在legged_robot.py被调用,主要功能是对设置地形的一些参数进行初始化,代码如下:

def __init__(self, cfg: LeggedRobotCfg.terrain, num_robots) -> None:

    self.cfg = cfg
    ## 智能体的个数,获取来源是LeggedRobotCfg类下边的env结构体下边的num_envs
    self.num_robots = num_robots
    ## 赋值地形表示形式
    self.type = cfg.mesh_type
    ## 如果地形无指定或者指定为平面则无需进行之后的赋值
    if self.type in ["none", 'plane']:
        return
    ## 整个环境由一个又一个局部地形构成,局部地形的长宽进行赋值
    self.env_length = cfg.terrain_length
    self.env_width = cfg.terrain_width
    ## 地形的累加比例,对于默认参数terrain_proportions = [0.1, 0.1, 0.35, 0.25, 0.2]
    ## self.proportions = [0.1, 0.2, 0.55, 0.8, 1.0]
    self.proportions = [np.sum(cfg.terrain_proportions[:i+1]) for i in range(len(cfg.terrain_proportions))]
    ## 生成的地形块个数
    self.cfg.num_sub_terrains = cfg.num_rows * cfg.num_cols
    ## 创建一个描述环境的三维数组,数组的大小与地形块的行、列数相关
    self.env_origins = np.zeros((cfg.num_rows, cfg.num_cols, 3))
	## 根据水平方向的分辨率得到地形长宽方向上有多少个像素(相当于是栅格化了)
    self.width_per_env_pixels = int(self.env_width / cfg.horizontal_scale)
    self.length_per_env_pixels = int(self.env_length / cfg.horizontal_scale)
	## 地形边界的像素个数
    self.border = int(cfg.border_size/self.cfg.horizontal_scale)
    ## 最终的综合大环境行像素个数,两侧都有边界
    self.tot_cols = int(cfg.num_cols * self.width_per_env_pixels) + 2 * self.border
    ## 最终的综合大环境列像素个数,两侧都有边界
    self.tot_rows = int(cfg.num_rows * self.length_per_env_pixels) + 2 * self.border
	## 初始化高度阈二维数组,数组的维度与行列大小有关
    self.height_field_raw = np.zeros((self.tot_rows , self.tot_cols), dtype=np.int16)
    ## 如果课程变量是true则执行4.2节curiculum函数
    if cfg.curriculum:
        self.curiculum()
    elif cfg.selected:
    	## 该函数基于terrain_kwargs地形类型字典值生成单一地形,函数的具体定义不展开了 
    	## 感兴趣的人可以看一下该函数的倒数第二句,真的很神
        self.selected_terrain()
    else:   
    	## 难度和选择完全随机生成地形,函数的具体定义不展开了 
        self.randomized_terrain()   
    
    self.heightsamples = self.height_field_raw
    if self.type=="trimesh":
        self.vertices, self.triangles = terrain_utils.convert_heightfield_to_trimesh(   self.height_field_raw,
                                                                                        self.cfg.horizontal_scale,
                                                                                        self.cfg.vertical_scale,
                                                                                        self.cfg.slope_treshold)

4.2 curiculum函数

该函数在utils/terrain.py中__init__函数(4.1节)被调用,主要功能是按照初始化参数要求生成不同需求的地形。

def curiculum(self):
    for j in range(self.cfg.num_cols):
        for i in range(self.cfg.num_rows):
        	## 行序号越大difficulty难度越高,难度顾名思义就是地形通行度变差
            difficulty = i / self.cfg.num_rows
            ## 列序号越大choice选择越大,choice结合累加比例选择地形类型。
            choice = j / self.cfg.num_cols + 0.001
            terrain = self.make_terrain(choice, difficulty)
            ## 将生成的地形加入至大环境中,最终储存在self.env_origins数组中,该函数不展开解释
            self.add_terrain_to_map(terrain, i, j)

4.3 make_terrain函数

该函数在utils/terrain.py中curiculum函数(4.2节)被调用,主要功能是在issac gym生成地形,其中的terrain_utilsissac gym提供的api。

def make_terrain(self, choice, difficulty):
	## 创建一个局部地形,参数包括地形的名字,地形的像素长宽以及分辨率
    terrain = terrain_utils.SubTerrain(   "terrain",
                            width=self.width_per_env_pixels,
                            length=self.width_per_env_pixels,
                            vertical_scale=self.cfg.vertical_scale,
                            horizontal_scale=self.cfg.horizontal_scale)
    ## slope坡度与难度正相关
    slope = difficulty * 0.4
    ## 台阶高度也与难度正相关
    step_height = 0.05 + 0.18 * difficulty
    ## 离散障碍物的高度也也与难度正相关
    discrete_obstacles_height = 0.05 + difficulty * 0.2
    ## 石头的大小和难度正相关,为什么这么设计目前未知,得继续学习
    stepping_stones_size = 1.5 * (1.05 - difficulty)
    ## 设定石头之间的距离
    stone_distance = 0.05 if difficulty==0 else 0.1
    ## 沟的尺寸和难度正相关
    gap_size = 1. * difficulty
    ## 坑的尺寸和难度正相关
    pit_depth = 1. * difficulty
    ## 如果落在第一区间则生成平坦坡
    if choice < self.proportions[0]:
    	## 在第一区间的前一半生成下坡
        if choice < self.proportions[0]/ 2:
            slope *= -1
        ## issacgym提供的api就不展开了,其中第一个参数是地形的名称,第二个参数是坡度,第三个参数是在地形的中间生成一个平台,
        ## 让机器人初始化的时候落在上边的,这里设置为3m
        terrain_utils.pyramid_sloped_terrain(terrain, slope=slope, platform_size=3.)
    ## 如果落在第二区间则生成崎岖坡,相较于第一区间是在坡道基础上叠加了随机地形,后续均为生成各类典型地形,不再赘述
    elif choice < self.proportions[1]:
        terrain_utils.pyramid_sloped_terrain(terrain, slope=slope, platform_size=3.)
        terrain_utils.random_uniform_terrain(terrain, min_height=-0.05, max_height=0.05, step=0.005, downsampled_scale=0.2)
    elif choice < self.proportions[3]:
        if choice<self.proportions[2]:
            step_height *= -1
        terrain_utils.pyramid_stairs_terrain(terrain, step_width=0.31, step_height=step_height, platform_size=3.)
    elif choice < self.proportions[4]:
        num_rectangles = 20
        rectangle_min_size = 1.
        rectangle_max_size = 2.
        terrain_utils.discrete_obstacles_terrain(terrain, discrete_obstacles_height, rectangle_min_size, rectangle_max_size, num_rectangles, platform_size=3.)
    elif choice < self.proportions[5]:
        terrain_utils.stepping_stones_terrain(terrain, stone_size=stepping_stones_size, stone_distance=stone_distance, max_height=0., platform_size=4.)
    elif choice < self.proportions[6]:
        gap_terrain(terrain, gap_size=gap_size, platform_size=3.)
    else:
        pit_terrain(terrain, depth=pit_depth, platform_size=4.)
    
    return terrain

4. utils/math.py

该脚本主要做数据类型转换,向量投影计算。

4.1 quat_apply_yaw函数

该函数将vec向量沿quat中的z轴旋转量旋转,代码如下:

def quat_apply_yaw(quat, vec):
	## 首先将quat进行副本制作并转化为一个二维向量,其中每个元素有四个分量(四元数)
    quat_yaw = quat.clone().view(-1, 4)
    ## 将该四元数的前两个元素都置为0,四元数为[x,y,z,w]其中x,y元素代表了绕x轴和y轴的旋转分量
    ## 所以将这两个量置0目的就是只保留z轴方向上的旋转分量
    quat_yaw[:, :2] = 0.
    ## 将新的四元数进行归一化
    quat_yaw = normalize(quat_yaw)
    ## 旋转,quat_applys是在torch_utils.py中实现的
    return quat_apply(quat_yaw, vec)

5.envs/   init.py  

该脚本中对于机器人的训练名称、训练环境搭建(与第7节相关),训练参数(与第6.1节相关),算法参数(与第6.2节相关)进行注册,代码如下:

## 第一个参数为name与终端输入的--task=xxx中的xxx进行匹配,第二个参数为LeggedRobot类型参考x.x节
## 第三个参数为LeggedRobotCfg类型参考x.x节,第四个参数为LeggedRobotCfgPPO类型参考x.x节
task_registry.register( "anymal_c_rough", Anymal, AnymalCRoughCfg(), AnymalCRoughCfgPPO() )
task_registry.register( "anymal_c_flat", Anymal, AnymalCFlatCfg(), AnymalCFlatCfgPPO() )
task_registry.register( "anymal_b", Anymal, AnymalBRoughCfg(), AnymalBRoughCfgPPO() )
task_registry.register( "a1", LeggedRobot, A1RoughCfg(), A1RoughCfgPPO() )
task_registry.register( "cassie", Cassie, CassieRoughCfg(), CassieRoughCfgPPO() )

6.envs/base/legged_robot_config.py

该脚本中包含了两个类,一是LeggedRobotCfg,二是LeggedRobotCfgPPO,代码如下:
下边列出的参数的值为默认参数,并非最终实际运行的值,因为用户定义的具体的类会继承上述类,然后针对性地修改初始参数。
比如本文介绍的anymal_c_rough_config.py会针对ANYmal_c在崎岖地形上的训练有一些参数的修改。

6.1 LeggedRobotCfg类

## LeggedRobotCfg继承BaseConfig类
class LeggedRobotCfg(BaseConfig):
	## 训练环境类,包含训练机器人数量、观测量等参数。
	class env:
		## 强化学习环境中同时训练智能体的数量,这里把智能体称为env  	
		num_envs = 4096
		## 强化学习观测值的数量
		num_observations = 235
		## 是否有特权观测值,所谓特权观测值就是实际机器人观测不到但仿真环境可以观测到的量,比如地面刚度,摩擦系数等
		## 如果该值不是None的话priviledge_obs_buf会通过step()函数返回,否则step()函数返回None
		num_privileged_obs = None
		## 可操控的动作数量
		num_actions = 12
		## not used with heightfields/trimeshes
		env_spacing = 3. 
		## 向算法发送超时信息(具体功能目前不清楚)
		send_timeouts = True
		## 机器人存活的时间
		episode_length_s = 20 # episode length in seconds
	    
	## 地形类,包含地形类型、大小等初始化参数,用于terrain.py
	class terrain:
		## 地形的表示形式:‘trimesh’是用三角网格,‘heightfield’是二维网格,有点类似与栅格的形式
		mesh_type = 'trimesh' # "heightfield" # none, plane, heightfield or trimesh
		## 水平方向的分辨率
		horizontal_scale = 0.1 # [m]
		## 垂直方向的分辨率
		vertical_scale = 0.005 # [m]
		## 生成局部地形边界的大小
		border_size = 25 # [m]
		## 是否使用课程,课程的含义就是当机器人在当前环境下运行情况较好后,增加地形的难度,指令的难度(比如速度更高等)
		curriculum = True
		## 静摩擦
		static_friction = 1.0
		## 滑动摩擦
		dynamic_friction = 1.0
		## 误差补偿
		restitution = 0.
		## 以下参数仅使用与粗糙地形
		measure_heights = True
		## 量测一个1.6*1m的矩形
		measured_points_x = [-0.8, -0.7, -0.6, -0.5, -0.4, -0.3, -0.2, -0.1, 0., 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7,0.8] 
		measured_points_y = [-0.5, -0.4, -0.3, -0.2, -0.1, 0., 0.1, 0.2, 0.3, 0.4, 0.5]
		## 是否选择一个单一的独特的地形
		selected = False
		## 选择地形的字典值,即名称
		terrain_kwargs = None 
		## 初始化地形的状态等级
		max_init_terrain_level = 5
		terrain_length = 8.
		terrain_width = 8.
		## 生成的各种地形块,有几行
		num_rows= 10 # number of terrain rows (levels)
		## 生成的各种地形块,有几列
		num_cols = 20 # number of terrain cols (types)
		## 地形类别包含:平坦坡,崎岖坡,正台阶,负台阶,离散地形
		## 各种地形类型所占比例
		terrain_proportions = [0.1, 0.1, 0.35, 0.25, 0.2]
		## 当地形表示形式选择为三角网格后独有的属性
		## 当坡度大于该阈值后直接修正成垂直墙
		slope_treshold = 0.75

	## 指令类,机器人指令的设置参数
    class commands:
   		## 是否使用课程,课程的含义就是当机器人在当前环境下运行情况较好后,增加地形的难度,指令的难度(比如速度更高等)
		curriculum = False
		## 课程难度最高级
		max_curriculum = 1.
		## 指令的个数
		## 默认是4个,包括x轴方向线速度,y轴方向线速度,角速度以及航向
		num_commands = 4 
		## 指令更改的时间
		resampling_time = 10.
		## 是否为航向控制模式,航向模式下航向角速度基于航向偏差进行计算
		heading_command = True
		## 指令的范围
		class ranges:
		    lin_vel_x = [-1.0, 1.0] # min max [m/s]
		    lin_vel_y = [-1.0, 1.0]   # min max [m/s]
		    ang_vel_yaw = [-1, 1]    # min max [rad/s]
		    heading = [-3.14, 3.14]
	
	## 机器人初始状态类
    class init_state:
    	## 初始位置
		pos = [0.0, 0.0, 1.] # x,y,z [m]
		## 初始姿态,利用四元数表示,目前设定的四元数计算的欧拉角都为0
		rot = [0.0, 0.0, 0.0, 1.0] # x,y,z,w [quat]
		## 初始线速度,各方向都为0
		lin_vel = [0.0, 0.0, 0.0]  # x,y,z [m/s]
		## 初始角速度,各方向都为0
		ang_vel = [0.0, 0.0, 0.0]  # x,y,z [rad/s]
		## 初始关节位置都是0
		default_joint_angles = { # target angles when action = 0.0
		   "joint_a": 0., 
		   "joint_b": 0.}
	
	## 机器人关节电机控制模式及参数
	class control:
		## 控制类型:位置控制、速度控制、扭矩控制
	    control_type = 'P' # P: position, V: velocity, T: torques
	    ## PD驱动的参数
	    ## stiffness代表刚度系数k_p damping代表阻尼系数k_d
	    stiffness = {'joint_a': 10.0, 'joint_b': 15.}  # [N*m/rad]
	    damping = {'joint_a': 1.0, 'joint_b': 1.5}     # [N*m*s/rad]
	    ## 公式如下,与action的转化为什么要有这样的比例因子暂未明白
	    # action scale: target angle = actionScale * action + defaultAngle
	    action_scale = 0.5
	    ## decimation: Number of control action updates @ sim DT per policy DT
	    ## 仿真环境的控制频率/decimation=实际环境中的控制频率
	    decimation = 4
	    
	## 与机器人模型URDF相关参数
	class asset:
		## 存放URDF的位置,此处为空,之后具体的机器人.py继承此类然后赋值具体的URDF位置
	    file = ""
	    name = "legged_robot"  # actor name
	    foot_name = "None" # name of the feet bodies, used to index body state and contact force tensors
	    ## 惩罚接触
	    penalize_contacts_on = []
	    ## 单个机器人终止的条件
	    terminate_after_contacts_on = []
	    ## 取消重力
	    disable_gravity = False
	    collapse_fixed_joints = True # merge bodies connected by fixed joints. Specific fixed joints can be kept by adding " <... dont_collapse="true">
	    ## 是否固定机器人本体
	    fix_base_link = False # fixe the base of the robot
	    ## 默认的关节驱动模式:0是无,1是位置控制,2是速度控制,3是扭矩控制
	    default_dof_drive_mode = 3 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 3 effort)
	    ## 是否开启自身碰撞检测,比如本体和腿部碰撞
	    self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
	    ## replace collision cylinders with capsules, leads to faster/more stable simulation
	    replace_cylinder_with_capsule = True 
	    flip_visual_attachments = True # Some .obj meshes must be flipped from y-up to z-up
	    ## 密度
	    density = 0.001
	    ## 角速度阻尼
	    angular_damping = 0.
	    linear_damping = 0.
	    ## 最大角速度
	    max_angular_velocity = 1000.
	    ## 最大线速度
	    max_linear_velocity = 1000.
	    ## 电驱
	    armature = 0.
	    thickness = 0.01

	## 与随机化相关的参数,增强训练出模型的鲁棒性
	class domain_rand:
		## 摩擦力是否有变化
	    randomize_friction = True
	    ## 摩擦系数范围
	    friction_range = [0.5, 1.25]
	    ## 本体质量是否有变化
	    randomize_base_mass = False
	    ## 增加质量的分辨率
	    added_mass_range = [-1., 1.]
	    ## 是否增加推动机器人的力
	    push_robots = True
	    ## 推动机器人力的时间间隔,过15s推一次
	    push_interval_s = 15
	    ## 最大的推动速度
	    max_push_vel_xy = 1.
	
	## 奖励函数类,定义了各个奖励函数,与x.x节奖励函数定义结合看
	class rewards:
	    class scales:
	    	## 任务终止权重
	        termination = -0.0
	        ## 跟踪线速度权重
	        tracking_lin_vel = 1.0
	        ## 跟踪角速度权重
	        tracking_ang_vel = 0.5
	        ## z轴线速度权重
	        lin_vel_z = -2.0
	        ## 姿态方向角速度权重
	        ang_vel_xy = -0.05
	        ## 机器人姿态权重
	        orientation = -0.
	        ## 关节扭矩权重
	        torques = -0.00001
	        ## 关节速度权重
	        dof_vel = -0.
	        ## 关节加速度权重
	        dof_acc = -2.5e-7
	        ## 本体高度权重
	        base_height = -0. 
	        ## 足部悬空时间权重
	        feet_air_time =  1.0
	        ## 本体碰撞权重
	        collision = -1.
	        ## 避免垂直障碍接触权重
	        feet_stumble = -0.0 
	        ## 动作变化率权重
	        action_rate = -0.01
	        ## 无期望命令保持静止权重
	        stand_still = -0.
			## 该项设置为true时,奖励为负值时被置为0,有这一项的原因是避免了过早终止的问题(avoids early termination problems)
		    only_positive_rewards = True
		    tracking_sigma = 0.25 # tracking reward = exp(-error^2/sigma)
		    ## urdf限制区间,如果是1则限制区间就按照urdf的机械限位决定,超出区间就惩罚
		    soft_dof_pos_limit = 1.
		    soft_dof_vel_limit = 1.
		    soft_torque_limit = 1.
		    base_height_target = 1.
		    max_contact_force = 100. # forces above this value are penalized

	class normalization:
	    class obs_scales:
	        lin_vel = 2.0
	        ang_vel = 0.25
	        dof_pos = 1.0
	        dof_vel = 0.05
	        height_measurements = 5.0
	    ## 最多的观测量数
	    clip_observations = 100.
	    ## 最多的动作数 该参数在7.9step()函数中被使用
	    clip_actions = 100.
	
	## 增加噪声的分辨率
	class noise:
	    add_noise = True
	    ## 在legged_robot.py的_get_noise_scale_vec()函数中用到
	    ## 一个观测量(如线性速度)最终的噪声计算如式noise_scales.lin_vel * noise_level * self.obs_scales.lin_vel
	    noise_level = 1.0
	    class noise_scales:
	    	## 关节位置噪声分辨率
	        dof_pos = 0.01
	        ## 关节速度噪声分辨率
	        dof_vel = 1.5
	        ## 线性速度噪声分辨率
	        lin_vel = 0.1
	        ## 角速度噪声分辨率
	        ang_vel = 0.2
	        ## 重力噪声分辨率
	        gravity = 0.05
	        ## 本体高度值噪声分辨率
	        height_measurements = 0.1
	
	## 仿真环境默认视角的参数设置
	class viewer:
	    ref_env = 0
	    pos = [10, 0, 6]  # [m]
	    lookat = [11., 5, 3.]  # [m]
	
	## 仿真环境仿真步长、物理属性设置
	class sim:
	    dt =  0.005
	    substeps = 1
	    gravity = [0., 0. ,-9.81]  # [m/s^2]
	    up_axis = 1  # 0 is y, 1 is z
	
	    class physx:
	        num_threads = 10
	        solver_type = 1  

6.2 LeggedRobotCfgPPO类

class LeggedRobotCfgPPO(BaseConfig):
	## 种子的设置,种子的作用在2.1节中有提到
    seed = 1
    ## 运行类的名称
    runner_class_name = 'OnPolicyRunner'
    
    ## 策略类参数
    class policy:
        init_noise_std = 1.0
        ## 演员隐藏层维度
        actor_hidden_dims = [512, 256, 128]
        ## 评论家隐藏层维度
        critic_hidden_dims = [512, 256, 128]
        ## 激活函数类型 见6.3节
        ## 可以是elu, relu, selu, crelu, lrelu, tanh, sigmoid
        activation = 'elu' 
        ## 接下来的参数只有 'ActorCriticRecurrent'算法需要
        # rnn_type = 'lstm'
        # rnn_hidden_size = 512
        # rnn_num_layers = 1
        
    ## 算法类参数
    class algorithm:
        # training params
        value_loss_coef = 1.0
        use_clipped_value_loss = True
        clip_param = 0.2
        entropy_coef = 0.01
        num_learning_epochs = 5
        num_mini_batches = 4 # mini batch size = num_envs*nsteps / nminibatches
        learning_rate = 1.e-3 #5.e-4
        schedule = 'adaptive' # could be adaptive, fixed
        gamma = 0.99
        lam = 0.95
        desired_kl = 0.01
        max_grad_norm = 1.

    class runner:
    	## 策略的类名
        policy_class_name = 'ActorCritic'
        ## 算法的类名
        algorithm_class_name = 'PPO'
        ## 每次迭代单个机器人的步数
        num_steps_per_env = 24
        ## 策略训练次数
        max_iterations = 1500

        ## 储存的参数
        ## 储存训练模型的间隔,目前会存迭代50次的模型,100次的模型,150次的模型,以此类推
        save_interval = 50
        ## 试验的名称,影响储存模型的路径
        experiment_name = 'test'
        run_name = ''
        ## 是否接着上次训练
        resume = False
        ## 读入上次的训练情况
        load_run = -1 # -1 = last run
        ## 读入上次训练储存的模型
        checkpoint = -1 # -1 = last saved model
        resume_path = None # updated from load_run and chkpt

6.3 激活函数类型

6.3.1 ELU (Exponential Linear Unit)

特点: 负值区域平滑,缓解梯度消失,计算成本较高。
f ( x ) = { x if  x > 0 α ( e x − 1 ) if  x ≤ 0 f(x) = \begin{cases} x & \text{if } x > 0 \\ \alpha (e^x - 1) & \text{if } x \leq 0 \end{cases} f(x)={xα(ex1)if x>0if x0
函数图像如图:
在这里插入图片描述

6.3.2 ReLU (Rectified Linear Unit)

特点: 计算简单,能缓解梯度消失,但可能导致神经元死亡。
f ( x ) = max ⁡ ( 0 , x ) f(x) = \max(0, x) f(x)=max(0,x)
函数图像如图:
RELU

6.3.3 SELU (Scaled Exponential Linear Unit)

特点: 自归一化,适合深层网络,需配合特定初始化。
f ( x ) = λ { x if  x > 0 α ( e x − 1 ) if  x ≤ 0 f(x) = \lambda \begin{cases} x & \text{if } x > 0 \\ \alpha (e^x - 1) & \text{if } x \leq 0 \end{cases} f(x)=λ{xα(ex1)if x>0if x0
函数形状走势与6.3.1小节相同,根据不同的 λ \lambda λ图像具体形状有所不同。

6.3.4 CReLU (Concatenated ReLU)

特点: 输出正负两部分,增加特征表达,但计算量翻倍。
f ( x ) = [ max ⁡ ( 0 , x ) , max ⁡ ( 0 , − x ) ] f(x) = [\max(0, x), \max(0, -x)] f(x)=[max(0,x),max(0,x)]
函数图像如图:
CRELU

6.3.5 LReLU (Leaky ReLU)

特点: 解决ReLU的神经元死亡问题,允许负值通过。
f ( x ) = max ⁡ ( α x , x ) 通常  α = 0.01 f(x) = \max(\alpha x, x) \quad \text{通常 } \alpha = 0.01 f(x)=max(αx,x)通常 α=0.01
函数图像如图:
在这里插入图片描述

6.3.6 Tanh (Hyperbolic Tangent)

特点: 输出在 [−1,1]之间,适合需要负输出的场景,但梯度消失问题依然存在。
f ( x ) = tanh ⁡ ( x ) = e x − e − x e x + e − x f(x) = \tanh(x) = \frac{e^x - e^{-x}}{e^x + e^{-x}} f(x)=tanh(x)=ex+exexex
函数图像如图:
Tanh

6.3.7 Sigmoid

特点: 输出在 [0,1] 之间,适合二分类,但梯度消失问题严重。
f ( x ) = 1 1 + e − x f(x) = \frac{1}{1 + e^{-x}} f(x)=1+ex1
函数图像如图:
Sigmoid

7.envs/base/legged_robot.py

该脚本中定义了LeggedRobot类,该类继承于BaseTask类。实现与issac gym的交互,奖励函数定义。

7.1 __init__函数

该函数主要实现LeggedRobotCfg参数导入,仿真参数、仿真设置、仿真设备的初始化,代码如下:

## 输入参数cfg(6.1节)、sim_params(仿真的参数,在utils/task_registry.py中的parse_sim_params()中完成初始化)、
## physics_engine(物理引擎在utils/task_registry.py中的parse_sim_params()中完成初始化))
## sim_device(仿真的设备,cuda还是cpu)、headless
def __init__(self, cfg: LeggedRobotCfg, sim_params, physics_engine, sim_device, headless):
	self.cfg = cfg
	self.sim_params = sim_params
	self.height_samples = None
	self.debug_viz = False
	self.init_done = False
	self._parse_cfg(self.cfg)
	## 利用super().__init__()调用父类BaseTask的初始化函数,调用creat_sim()创建仿真环境?
	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)
	## 初始化pytorch的缓存区,见7.3节
	self._init_buffers()
	## 汇总奖励函数
	self._prepare_reward_function()
	self.init_done = True

7.2 _parse_cfg函数

该函数的主要功能是将初始化参数类型进行赋值,转化,代码如下:

def _parse_cfg(self, cfg):
	## 结合6.1节的control类self.dt = 4 * 0.005 = 0.02
    self.dt = self.cfg.control.decimation * self.sim_params.dt
    ## 观测值的分辨率?
    self.obs_scales = self.cfg.normalization.obs_scales
    ## 奖励权重、指令范围全部变为字典
    self.reward_scales = class_to_dict(self.cfg.rewards.scales)
    self.command_ranges = class_to_dict(self.cfg.commands.ranges)
    if self.cfg.terrain.mesh_type not in ['heightfield', 'trimesh']:
        self.cfg.terrain.curriculum = False
    ## 结合6.1节每个机器人训练的时间
    self.max_episode_length_s = self.cfg.env.episode_length_s
    ## 应该是在仿真中每个机器人训练的周期数
    self.max_episode_length = np.ceil(self.max_episode_length_s / self.dt)
    ## 给机器人施加推力的周期数,推测就是到周期数就推一次,而并非是绝对时间
    self.cfg.domain_rand.push_interval = np.ceil(self.cfg.domain_rand.push_interval_s / self.dt)

7.3 _init_buffers函数

该函数的主要作用是利用初始化参数,初始化torch张量,代码如下:

def _init_buffers(self):
    ## 获取GPU张量,通过issac gym的api
    ## GPU张量这种形式应该很适合高性能运算
    ## self.sim是8.1小节base_task.py中利用gymapi.acquire_gym() 函数获得的
    ## 该参数是isaac gym的全局实例,通过该实例,可以创建和管理仿真环境
    ## acquire_actor_root_state_tensor()函数从仿真环境中获取所有机器人的根状态,并将其存储在一个 GPU 张量中
    ## 根状态通常包括位置、姿态、线速度、角速度
    actor_root_state = self.gym.acquire_actor_root_state_tensor(self.sim)
    dof_state_tensor = self.gym.acquire_dof_state_tensor(self.sim)
    ## acquire_net_contact_force_tensor()函数用于获取仿真环境中所有物体的接触力张量,通常包括三个分量(x, y, z)
    net_contact_forces = self.gym.acquire_net_contact_force_tensor(self.sim)
    self.gym.refresh_dof_state_tensor(self.sim)
    self.gym.refresh_actor_root_state_tensor(self.sim)
    self.gym.refresh_net_contact_force_tensor(self.sim)

    ## wrap_tensor() 是isaac gym 库中的一个函数,用于将 isaac gym 的环境数据(通常是GPU张量)
    ## 转换为pytorch张量,以便在pytorch中进行进一步的计算和操作
    self.root_states = gymtorch.wrap_tensor(actor_root_state)
    self.dof_state = gymtorch.wrap_tensor(dof_state_tensor)
    ## dof_state的类型是pytorch中的张量,tensor.view是将张量的维度进行改变
    ## 从代码来看dof_state是一个num_envs*num_dof*2的状态张量
    ## 该代码的作用是将dof_state转换为一个(num_envs,num_dof)的二维张量,该张量的每个元素应该是包含2个值
    ## [...,0]是取该张量中全部元素的第一个值,应该是关节位置
    self.dof_pos = self.dof_state.view(self.num_envs, self.num_dof, 2)[..., 0]
    ## [...,1]是取该张量中全部元素的第二个值,应该是关节速度
    self.dof_vel = self.dof_state.view(self.num_envs, self.num_dof, 2)[..., 1]
    ## root_states通常包含仿真环境中所有机器人的根状态
    ## 根状态包含位置(3),姿态(四元数),线速度(3),角速度(3)
    ## 张量顺序[x, y, z, qx, qy, qz, qw, vx, vy, vz, wx, wy, wz]
    ## 所以该代码是取出第四个到第七个量,即反映仿真环境中全部机器人姿态的四元数组成base_quat张量
    self.base_quat = self.root_states[:, 3:7]
	## 将接触力的张量进行重新整形,主要说一下这里的-1参数,表明新张量的第二维度的大小会根据机器人不同自动计算
	## 这是因为不同机器人的结构不同,比如有的有4部分、头、身、腿、足,有的则分为头、身、大腿、小腿、足部等
	## 参数3则代表有三个方向的力,是三维张量
    self.contact_forces = gymtorch.wrap_tensor(net_contact_forces).view(self.num_envs, -1, 3) 
    
    ## 仿真步数计数器
    self.common_step_counter = 0
    self.extras = {}
    ## 给各个观测量添加的噪声向量
    self.noise_scale_vec = self._get_noise_scale_vec(self.cfg)
    ## get_axis_params()获取z轴向量,.repeat()复制前边的向量num_envs次
    self.gravity_vec = to_torch(get_axis_params(-1., self.up_axis_idx), device=self.device).repeat((self.num_envs, 1))
    self.forward_vec = to_torch([1., 0., 0.], device=self.device).repeat((self.num_envs, 1))
    ## 创立一系列张量
    self.torques = torch.zeros(self.num_envs, self.num_actions, dtype=torch.float, device=self.device, requires_grad=False)
    self.p_gains = torch.zeros(self.num_actions, dtype=torch.float, device=self.device, requires_grad=False)
    self.d_gains = torch.zeros(self.num_actions, dtype=torch.float, device=self.device, requires_grad=False)
    self.actions = torch.zeros(self.num_envs, self.num_actions, dtype=torch.float, device=self.device, requires_grad=False)
    self.last_actions = torch.zeros(self.num_envs, self.num_actions, dtype=torch.float, device=self.device, requires_grad=False)
    self.last_dof_vel = torch.zeros_like(self.dof_vel)
    self.last_root_vel = torch.zeros_like(self.root_states[:, 7:13])
    self.commands = torch.zeros(self.num_envs, self.cfg.commands.num_commands, dtype=torch.float, device=self.device, requires_grad=False) # x vel, y vel, yaw vel, heading
    self.commands_scale = torch.tensor([self.obs_scales.lin_vel, self.obs_scales.lin_vel, self.obs_scales.ang_vel], device=self.device, requires_grad=False,) # TODO change this
    self.feet_air_time = torch.zeros(self.num_envs, self.feet_indices.shape[0], dtype=torch.float, device=self.device, requires_grad=False)
    self.last_contacts = torch.zeros(self.num_envs, len(self.feet_indices), dtype=torch.bool, device=self.device, requires_grad=False)
    ## quat_rotate_inverse()函数是将机器人在仿真环境中的速度转化至机器人本体坐标系上
    ## 该函数的实现在torch_utils.py里,参考的数学原理见这个知乎帖子(https://zhuanlan.zhihu.com/p/135951128)
    self.base_lin_vel = quat_rotate_inverse(self.base_quat, self.root_states[:, 7:10])
    self.base_ang_vel = quat_rotate_inverse(self.base_quat, self.root_states[:, 10:13])
    self.projected_gravity = quat_rotate_inverse(self.base_quat, self.gravity_vec)
    if self.cfg.terrain.measure_heights:
    	## 参考7.5小节
        self.height_points = self._init_height_points()
    self.measured_heights = 0

    ## 关节位置偏移量和PD权重
    self.default_dof_pos = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
    ## 根据各个关节的名字,初始化关节角度,p参,d参,参考6.1节init_state和control
    for i in range(self.num_dofs):
        name = self.dof_names[i]
        angle = self.cfg.init_state.default_joint_angles[name]
        self.default_dof_pos[i] = angle
        found = False
        for dof_name in self.cfg.control.stiffness.keys():
            if dof_name in name:
                self.p_gains[i] = self.cfg.control.stiffness[dof_name]
                self.d_gains[i] = self.cfg.control.damping[dof_name]
                found = True
        if not found:
            self.p_gains[i] = 0.
            self.d_gains[i] = 0.
            if self.cfg.control.control_type in ["P", "V"]:
                print(f"PD gain of joint {name} were not defined, setting them to zero")
    self.default_dof_pos = self.default_dof_pos.unsqueeze(0)

7.4 _prepare_reward_function函数

该函数的功能是根据预先设定好的奖励函数权重(权重不为0)准备需要计算的奖励函数,代码如下:

def _prepare_reward_function(self):
    for key in list(self.reward_scales.keys()):
        scale = self.reward_scales[key]
        if scale==0:
            self.reward_scales.pop(key) 
        else:
            self.reward_scales[key] *= self.dt
    ## 准备奖励函数列表,奖励函数的权重和函数名称差一个'_reward_',可以对比6.1节中的reward和legged_robot.py后边的奖励函数定
    self.reward_functions = []
    self.reward_names = []
    for name, scale in self.reward_scales.items():
        if name=="termination":
            continue
        self.reward_names.append(name)
        name = '_reward_' + name
        self.reward_functions.append(getattr(self, name))

    ## self.episode_sums字典将包含与self.reward_scales字典相同数量的键
    ## 但每个键都将映射到一个大小为 (self.num_envs) 的全零浮点数张量
    ## 张量将用于在训练过程中累积每个环境的奖励。
    self.episode_sums = {name: torch.zeros(self.num_envs, dtype=torch.float, device=self.device, requires_grad=False)
                         for name in self.reward_scales.keys()}

7.5 _init_height_points函数

该函数的主要功能是根据6.1节terrain中参数设定的量测范围measured_points_y、measured_points_x,初始化由机器人周围矩形范围内点在环境坐标系下的张量,代码如下:

def _init_height_points(self):
    y = torch.tensor(self.cfg.terrain.measured_points_y, device=self.device, requires_grad=False)
    x = torch.tensor(self.cfg.terrain.measured_points_x, device=self.device, requires_grad=False)
    grid_x, grid_y = torch.meshgrid(x, y)
	## numel()返回该张量中元素的个数
    self.num_height_points = grid_x.numel()
    points = torch.zeros(self.num_envs, self.num_height_points, 3, device=self.device, requires_grad=False)
    ## flatten()将张量压缩为一维
    ## points张量的第一个维度为grid_x
    ## points张量的第二个维度为grid_y
    points[:, :, 0] = grid_x.flatten()
    points[:, :, 1] = grid_y.flatten()
    return points

7.6 create_sim函数

该函数的主要功能是根据初始化参数,在isaac gym中创建具体的环境、地形等,代码如下:

def create_sim(self):
	## 确认竖直向上的轴是z轴
    self.up_axis_idx = 2 # 2 for z, 1 for y -> adapt gravity accordingly
    self.sim = self.gym.create_sim(self.sim_device_id, self.graphics_device_id, self.physics_engine, self.sim_params)
    mesh_type = self.cfg.terrain.mesh_type
    ## 创建地形的网格类型
    if mesh_type in ['heightfield', 'trimesh']:
    	## 构建Terrain类,调用第4节utils/terrain.py中的函数
        self.terrain = Terrain(self.cfg.terrain, self.num_envs)
    ## 以下三个函数均在legged_robot.py中定义 
    if mesh_type=='plane':
        self._create_ground_plane()
    elif mesh_type=='heightfield':
        self._create_heightfield()
    elif mesh_type=='trimesh':
        self._create_trimesh()
    elif mesh_type is not None:
        raise ValueError("Terrain mesh type not recognised. Allowed types are [None, plane, heightfield, trimesh]")
    ## 见7.7节
    self._create_envs()

7.7 _creat_envs函数

该函数的主要功能是加载URDF文件,创建训练环境,为机器人增加物理属性,增加机器人自由度和形状属性等,代码如下:

def _create_envs(self):
	## 读取6.1节中asset关于URDF的目录
	## 示例当中:file = "{LEGGED_GYM_ROOT_DIR}/resources/robots/anymal_c/urdf/anymal_c.urdf"
	## 通过该代码将代码中的{LEGGED_GYM_ROOT_DIR}替换称为LEGGED_GYM_ROOT_DIR实际代表的路径,该路径变量是从
	## legged_gym/__init.py__中初始化得到的
	## 假如LEGGED_GYM_ROOT_DIR=/home/ten/legged_gym,
	## 那么asset_path=/home/ten/legged_gym/resources/robots/anymal_c/urdf/anymal_c.urdf
    asset_path = self.cfg.asset.file.format(LEGGED_GYM_ROOT_DIR=LEGGED_GYM_ROOT_DIR)
    ## asset_root = /home/ten/legged_gym/resources/robots/anymal_c/urdf
    asset_root = os.path.dirname(asset_path)
    ## asset_file = anymal_c.urdf
    asset_file = os.path.basename(asset_path)

	## 就是对6.1节中的参数赋值
    asset_options = gymapi.AssetOptions()
    asset_options.default_dof_drive_mode = self.cfg.asset.default_dof_drive_mode
    asset_options.collapse_fixed_joints = self.cfg.asset.collapse_fixed_joints
    asset_options.replace_cylinder_with_capsule = self.cfg.asset.replace_cylinder_with_capsule
    asset_options.flip_visual_attachments = self.cfg.asset.flip_visual_attachments
    asset_options.fix_base_link = self.cfg.asset.fix_base_link
    asset_options.density = self.cfg.asset.density
    asset_options.angular_damping = self.cfg.asset.angular_damping
    asset_options.linear_damping = self.cfg.asset.linear_damping
    asset_options.max_angular_velocity = self.cfg.asset.max_angular_velocity
    asset_options.max_linear_velocity = self.cfg.asset.max_linear_velocity
    asset_options.armature = self.cfg.asset.armature
    asset_options.thickness = self.cfg.asset.thickness
    asset_options.disable_gravity = self.cfg.asset.disable_gravity
	
	## 加载urdf至issac gym中
    robot_asset = self.gym.load_asset(self.sim, asset_root, asset_file, asset_options)
    ## 计算关节数量
    self.num_dof = self.gym.get_asset_dof_count(robot_asset)
    ## 计算刚体数量
    self.num_bodies = self.gym.get_asset_rigid_body_count(robot_asset)
    ## 得到关节的属性
    dof_props_asset = self.gym.get_asset_dof_properties(robot_asset)
    ## 得到刚体的属性
    rigid_shape_props_asset = self.gym.get_asset_rigid_shape_properties(robot_asset)

    ## 储存urdf的属性
    body_names = self.gym.get_asset_rigid_body_names(robot_asset)
    self.dof_names = self.gym.get_asset_dof_names(robot_asset)
    self.num_bodies = len(body_names)
    self.num_dofs = len(self.dof_names)
    feet_names = [s for s in body_names if self.cfg.asset.foot_name in s]
    penalized_contact_names = []
    for name in self.cfg.asset.penalize_contacts_on:
        penalized_contact_names.extend([s for s in body_names if name in s])
    termination_contact_names = []
    for name in self.cfg.asset.terminate_after_contacts_on:
        termination_contact_names.extend([s for s in body_names if name in s])

	## 将机器人的初始化状态合并
    base_init_state_list = self.cfg.init_state.pos + self.cfg.init_state.rot + self.cfg.init_state.lin_vel + self.cfg.init_state.ang_vel
    self.base_init_state = to_torch(base_init_state_list, device=self.device, requires_grad=False)
    start_pose = gymapi.Transform()
    start_pose.p = gymapi.Vec3(*self.base_init_state[:3])

    self._get_env_origins()
    env_lower = gymapi.Vec3(0., 0., 0.)
    env_upper = gymapi.Vec3(0., 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(self.num_envs)))
        pos = self.env_origins[i].clone()
        pos[:2] += torch_rand_float(-1., 1., (2,1), device=self.device).squeeze(1)
        start_pose.p = gymapi.Vec3(*pos)
            
        rigid_shape_props = self._process_rigid_shape_props(rigid_shape_props_asset, i)
        self.gym.set_asset_rigid_shape_properties(robot_asset, rigid_shape_props)
        actor_handle = self.gym.create_actor(env_handle, robot_asset, start_pose, self.cfg.asset.name, i, self.cfg.asset.self_collisions, 0)
        ## 见7.8节中函数的定义,主要是对关节的限制进行初始化以及针对性修改
        dof_props = self._process_dof_props(dof_props_asset, i)
        self.gym.set_actor_dof_properties(env_handle, actor_handle, dof_props)
        body_props = self.gym.get_actor_rigid_body_properties(env_handle, actor_handle)
        body_props = self._process_rigid_body_props(body_props, i)
        self.gym.set_actor_rigid_body_properties(env_handle, actor_handle, body_props, recomputeInertia=True)
        self.envs.append(env_handle)
        self.actor_handles.append(actor_handle)
	## 对足部的序号,需要关注碰撞的刚体序号,决定终止行为的刚体序号进行初始化
    self.feet_indices = torch.zeros(len(feet_names), dtype=torch.long, device=self.device, requires_grad=False)
    for i in range(len(feet_names)):
        self.feet_indices[i] = self.gym.find_actor_rigid_body_handle(self.envs[0], self.actor_handles[0], feet_names[i])

    self.penalised_contact_indices = torch.zeros(len(penalized_contact_names), dtype=torch.long, device=self.device, requires_grad=False)
    for i in range(len(penalized_contact_names)):
        self.penalised_contact_indices[i] = self.gym.find_actor_rigid_body_handle(self.envs[0], self.actor_handles[0], penalized_contact_names[i])

    self.termination_contact_indices = torch.zeros(len(termination_contact_names), dtype=torch.long, device=self.device, requires_grad=False)
    for i in range(len(termination_contact_names)):
        self.termination_contact_indices[i] = self.gym.find_actor_rigid_body_handle(self.envs[0], self.actor_handles[0], termination_contact_names[i])

7.8 _process_dof_props函数

该函数在creat_envs函数中调用,主要功能是储存、修改、随机每个环境的自由度属性,输入参数是每个自由度的属性,输出是修改后的自由度属性,代码如下:

def _process_dof_props(self, props, env_id):
    if env_id==0:
    	## 创建关节的位置、速度、力矩限制
        self.dof_pos_limits = torch.zeros(self.num_dof, 2, dtype=torch.float, device=self.device, requires_grad=False)
        self.dof_vel_limits = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
        self.torque_limits = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False)
        for i in range(len(props)):
        	## 拿到关节位置、速度、扭矩的限制
            self.dof_pos_limits[i, 0] = props["lower"][i].item()
            self.dof_pos_limits[i, 1] = props["upper"][i].item()
            self.dof_vel_limits[i] = props["velocity"][i].item()
            self.torque_limits[i] = props["effort"][i].item()
            ## m是关节位置上下界的中值
            m = (self.dof_pos_limits[i, 0] + self.dof_pos_limits[i, 1]) / 2
            ## r是关节位置的范围长度
            r = self.dof_pos_limits[i, 1] - self.dof_pos_limits[i, 0]
            ## 按照self.cfg.rewards.soft_dof_pos_limit对位置上下界进行修改,目前soft_dof_pos_limit=1
            ## 所以计算出来没有变化,设计这个目的是为了将关节限位变小保障安全
            self.dof_pos_limits[i, 0] = m - 0.5 * r * self.cfg.rewards.soft_dof_pos_limit
            self.dof_pos_limits[i, 1] = m + 0.5 * r * self.cfg.rewards.soft_dof_pos_limit
    return props

7.9 step函数

该函数是怎么被调用的没弄清楚,但是该函数在训练过程中应该需要被调用,之后对框架更理解的时候再来更新。主要功能是接受动作、仿真、计算奖励,重置机器人等。

def step(self, actions):
	## 将动作限制在clip_actions参数范围内,该参数在6.1节初始化
    clip_actions = self.cfg.normalization.clip_actions
    self.actions = torch.clip(actions, -clip_actions, clip_actions).to(self.device)
    ## 该函数主要是对可视化渲染相关进行了定义
    self.render()
    ## 循环self.cfg.control.decimation次,降低了运行周期 
    for _ in range(self.cfg.control.decimation):
    	## 计算扭矩,见7.10节
        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)
    ## 见7.11节
    self.post_physics_step()

    ## 将动作限制在clip_obs参数范围内,该参数在6.1节初始化
    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

7.10 _compute_torques函数

该函数将动作action通过PD参数转化为关节扭矩,代码如下:

def _compute_torques(self, actions):
    ## PD控制器
    actions_scaled = actions * self.cfg.control.action_scale
    control_type = self.cfg.control.control_type
    if control_type=="P":
    	## 见公式1
        torques = self.p_gains*(actions_scaled + self.default_dof_pos - self.dof_pos) - self.d_gains*self.dof_vel
    elif control_type=="V":
    	## 见公式2
        torques = self.p_gains*(actions_scaled - self.dof_vel) - self.d_gains*(self.dof_vel - self.last_dof_vel)/self.sim_params.dt
    elif control_type=="T":
    	## 见公式3
        torques = actions_scaled
    else:
        raise NameError(f"Unknown controller type: {control_type}")
    return torch.clip(torques, -self.torque_limits, self.torque_limits)

1、如果是位置控制’P’,则动作为相较于初始位置旋转角度,转化为扭矩的公式为公式1
T = k p ( a s + d p 0 − d p e ) − k d d v T=k_p(a_s+d_{p0}-d_{pe})-k_dd_v T=kp(as+dp0dpe)kddv
其中, T T T为施加至关节的扭矩, a s a_s as为动作, d p 0 d_{p0} dp0为关节的初始位置, d p e d_{pe} dpe为关节的当前位置, k p k_p kp为比例系数, k d k_d kd为微分系数, d v d_v dv为关节速度。

2、如果是速度控制’V’,则动作为期望转速转化为扭矩的公式为公式2
T = k p ( a s − d v ) − k d d v − d v l Δ t T=k_p(a_s-d_v)-k_d\frac{d_v-d_v^l}{\Delta t} T=kp(asdv)kdΔtdvdvl
其中, T T T为施加至关节的扭矩, a s a_s as为动作, d v d_v dv为关节速度, d v l d_v^l dvl为关节上一时刻速度, Δ t \Delta t Δt为周期间隔时间, k p k_p kp为比例系数, k d k_d kd为微分系数。

3、如果是力矩控制’T’,则动作为期望转速转化为扭矩的公式为公式3
T = a s T=a_s T=as
其中, T T T为施加至关节的扭矩, a s a_s as为动作。

7.11 post_physics_step函数

该函数计算奖励函数,观测值,检查单个机器人训练是否终止等,代码如下:

def post_physics_step(self):
	## 更新机器人状态以及接触力
    self.gym.refresh_actor_root_state_tensor(self.sim)
    self.gym.refresh_net_contact_force_tensor(self.sim)

    self.episode_length_buf += 1
    self.common_step_counter += 1

    ## 计算机器人坐标系下的基本状态
    self.base_quat[:] = self.root_states[:, 3:7]
    self.base_lin_vel[:] = quat_rotate_inverse(self.base_quat, self.root_states[:, 7:10])
    self.base_ang_vel[:] = quat_rotate_inverse(self.base_quat, self.root_states[:, 10:13])
    self.projected_gravity[:] = quat_rotate_inverse(self.base_quat, self.gravity_vec)
	
	## 见7.12节
    self._post_physics_step_callback()

    ## 检查当前机器人是否满足中止条件 目前有两个:1是当前机器人设定不可碰撞的部分是否发生碰撞;2是是否超出最大的训练周期数
    self.check_termination()
    ## 见7.14节
    self.compute_reward()
    env_ids = self.reset_buf.nonzero(as_tuple=False).flatten()
    self.reset_idx(env_ids)
    ## 该函数计算出当前需要的观测值
    self.compute_observations() # in some cases a simulation step might be required to refresh some obs (for example body positions)

    self.last_actions[:] = self.actions[:]
    self.last_dof_vel[:] = self.dof_vel[:]
    self.last_root_vel[:] = self.root_states[:, 7:13]

    if self.viewer and self.enable_viewer_sync and self.debug_viz:
        self._draw_debug_vis()

7.12 _post_physics_step_callback函数

该函数主要对给训练机器人的指令进行设置。

def _post_physics_step_callback(self):
    ## 当前的训练周期初一设置的重采样周期,选出能够整除的机器人序号 
    env_ids = (self.episode_length_buf % int(self.cfg.commands.resampling_time / self.dt)==0).nonzero(as_tuple=False).flatten()
    ## 给训练机器人随机选择一些指令
    self._resample_commands(env_ids)
    ## 如果是给航向角命令,也是通过期望航向角和当前航向角算出期望z轴角速度
    if self.cfg.commands.heading_command:
        forward = quat_apply(self.base_quat, self.forward_vec)
        heading = torch.atan2(forward[:, 1], forward[:, 0])
        self.commands[:, 2] = torch.clip(0.5*wrap_to_pi(self.commands[:, 3] - heading), -1., 1.)

    if self.cfg.terrain.measure_heights:
    	## 见7.13节
        self.measured_heights = self._get_heights()
    if self.cfg.domain_rand.push_robots and  (self.common_step_counter % self.cfg.domain_rand.push_interval == 0):
    	## 随机给机器人施加推力
    	## 实现方式是给机器人的本体x,y速度施加一个随机量
        self._push_robots()

7.13 _get_heights函数

该函数在post_physics_step_callback函数中被调用,主要功能是将机器人周围矩形范围内的点转化至机器人坐标系后,代码如下:

def _get_heights(self, env_ids=None):
	## 如果地形形式选的是平面,则高度都为0
    if self.cfg.terrain.mesh_type == 'plane':
        return torch.zeros(self.num_envs, self.num_height_points, device=self.device, requires_grad=False)
    elif self.cfg.terrain.mesh_type == 'none':
        raise NameError("Can't measure height with terrain mesh type 'none'")
	## 判断env_ids这个张量是否非空
	## 如果不为空则对指定env_ids的机器人进行操作,如果是空则对整个机器人队列进行操作
    if env_ids:
    	## 把点转化到机器人坐标系下,quat_apply_yaw是旋转至机器人坐标系下,+ (self.root_states[env_ids, :3])是平移至机器人坐标系下
        points = quat_apply_yaw(self.base_quat[env_ids].repeat(1, self.num_height_points), self.height_points[env_ids]) + (self.root_states[env_ids, :3]).unsqueeze(1)
    else:
        points = quat_apply_yaw(self.base_quat.repeat(1, self.num_height_points), self.height_points) + (self.root_states[:, :3]).unsqueeze(1)

    points += self.terrain.cfg.border_size
    ## 转化至像素级索引而非实际值
    points = (points/self.terrain.cfg.horizontal_scale).long()
    px = points[:, :, 0].view(-1)
    py = points[:, :, 1].view(-1)
    px = torch.clip(px, 0, self.height_samples.shape[0]-2)
    py = torch.clip(py, 0, self.height_samples.shape[1]-2)
	
	## 选出机器人最小的高度值
    heights1 = self.height_samples[px, py]
    heights2 = self.height_samples[px+1, py]
    heights3 = self.height_samples[px, py+1]
    heights = torch.min(heights1, heights2)
    heights = torch.min(heights, heights3)

    return heights.view(self.num_envs, -1) * self.terrain.cfg.vertical_scale

7.14 compute_reward函数

该函数在post_physics_step函数中被调用,主要功能是计算奖励函数值,代码如下:

def compute_reward(self):
	## 初始化总奖励值为0
    self.rew_buf[:] = 0.
    ## 循环在_prepare_reward_function初始化的奖励函数字典
    for i in range(len(self.reward_functions)):
        name = self.reward_names[i]
        ## 运行对应函数并乘上权重因子
        rew = self.reward_functions[i]() * self.reward_scales[name]
        ## 之后进行加和
        self.rew_buf += rew
        self.episode_sums[name] += rew
    ## 如果设定只增加正向奖励,则总奖励小于0则置为0
    if self.cfg.rewards.only_positive_rewards:
        self.rew_buf[:] = torch.clip(self.rew_buf[:], min=0.)
    ## 增加终止奖励
    if "termination" in self.reward_scales:
        rew = self._reward_termination() * self.reward_scales["termination"]
        self.rew_buf += rew
        self.episode_sums["termination"] += rew

7.15 compute_observations函数

该函数在post_physics_step函数中被调用,主要功能是计算网络观测值,代码如下:

def compute_observations(self):
	## torch.cat将多个张量沿指定维度拼接在一起。
	## 观测量是:
	## base_lin_vel机器人本体坐标系下的线性速度(x,y,z)
	## base_ang_vel机器人本体坐标系下的角速度(w_x,w_y,w_z)
	## projected_gravity机器人坐标系下的重力分量(g_x, g_y, g_z)
	## commands机器人前三项命令,机器人坐标系x方向,y方向上的线速度,机器人z轴角速度
	## 各关节位置
	## 各关节速度
	## 动作(各个关节的角度,角速度,力矩,与选择的控制模式有关)
	self.obs_buf = torch.cat((  self.base_lin_vel * self.obs_scales.lin_vel,
	                                self.base_ang_vel  * self.obs_scales.ang_vel,
	                                self.projected_gravity,
	                                self.commands[:, :3] * self.commands_scale,
	                                (self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
	                                self.dof_vel * self.obs_scales.dof_vel,
	                                self.actions
	                                ),dim=-1)
	## 如果不是盲走则增加对于环境的量测
	if self.cfg.terrain.measure_heights:
	    heights = torch.clip(self.root_states[:, 2].unsqueeze(1) - 0.5 - self.measured_heights, -1, 1.) * self.obs_scales.height_measurements
	    self.obs_buf = torch.cat((self.obs_buf, heights), dim=-1)
	## 给全部的观测量增加噪声
	if self.add_noise:
	    self.obs_buf += (2 * torch.rand_like(self.obs_buf) - 1) * self.noise_scale_vec

7.16 _resample_commands函数

该函数在post_physics_step_callback函数中调用,计算了外部指令的内容,代码如下:

## command顺序在机器人坐标系x方向,y方向上的线速度,机器人z轴角速度,期望航向角四个命令
## 在命令的上下限中随机生成一个值
def _resample_commands(self, env_ids):
    self.commands[env_ids, 0] = torch_rand_float(self.command_ranges["lin_vel_x"][0], self.command_ranges["lin_vel_x"][1], (len(env_ids), 1), device=self.device).squeeze(1)
    self.commands[env_ids, 1] = torch_rand_float(self.command_ranges["lin_vel_y"][0], self.command_ranges["lin_vel_y"][1], (len(env_ids), 1), device=self.device).squeeze(1)
    if self.cfg.commands.heading_command:
        self.commands[env_ids, 3] = torch_rand_float(self.command_ranges["heading"][0], self.command_ranges["heading"][1], (len(env_ids), 1), device=self.device).squeeze(1)
    else:
        self.commands[env_ids, 2] = torch_rand_float(self.command_ranges["ang_vel_yaw"][0], self.command_ranges["ang_vel_yaw"][1], (len(env_ids), 1), device=self.device).squeeze(1)

    ## 在机器人坐标系x方向,y方向上的线速度命令过小则置为0,目前的比较值是0.2
    self.commands[env_ids, :2] *= (torch.norm(self.commands[env_ids, :2], dim=1) > 0.2).unsqueeze(1)

8.envs/base/base_task.py

8.1__init__函数

def __init__(self, cfg, sim_params, physics_engine, sim_device, headless):
	## 返回一个 gymapi.Gym 对象,用于访问isaac gym的所有功能。
    self.gym = gymapi.acquire_gym()
	
	## 仿真参数的赋值
    self.sim_params = sim_params
    self.physics_engine = physics_engine
    self.sim_device = sim_device
    sim_device_type, self.sim_device_id = gymutil.parse_device_str(self.sim_device)
    self.headless = headless

    ## 强化学习的设备
    if sim_device_type=='cuda' and sim_params.use_gpu_pipeline:
        self.device = self.sim_device
    else:
        self.device = 'cpu'

    ## 是否实时可视化渲染
    self.graphics_device_id = self.sim_device_id
    if self.headless == True:
        self.graphics_device_id = -1
	
	## 初始化参数赋值
    self.num_envs = cfg.env.num_envs
    self.num_obs = cfg.env.num_observations
    self.num_privileged_obs = cfg.env.num_privileged_obs
    self.num_actions = cfg.env.num_actions

    # optimization flags for pytorch JIT
    torch._C._jit_set_profiling_mode(False)
    torch._C._jit_set_profiling_executor(False)

    # 按照训练的机器人个数初始化张量
    self.obs_buf = torch.zeros(self.num_envs, self.num_obs, device=self.device, dtype=torch.float)
    self.rew_buf = torch.zeros(self.num_envs, device=self.device, dtype=torch.float)
    self.reset_buf = torch.ones(self.num_envs, device=self.device, dtype=torch.long)
    self.episode_length_buf = torch.zeros(self.num_envs, device=self.device, dtype=torch.long)
    self.time_out_buf = torch.zeros(self.num_envs, device=self.device, dtype=torch.bool)
    if self.num_privileged_obs is not None:
        self.privileged_obs_buf = torch.zeros(self.num_envs, self.num_privileged_obs, device=self.device, dtype=torch.float)
    else: 
        self.privileged_obs_buf = None
        # self.num_privileged_obs = self.num_obs

    self.extras = {}

    ## 创建环境、机器人,这里不清楚怎么父类调用子类定义的函数?
    self.create_sim()
    self.gym.prepare_sim(self.sim)

    ## 是否监视
    self.enable_viewer_sync = True
    self.viewer = None

    ## 如果使用查看器运行,需设置键盘快捷键和相机
    if self.headless == False:
        self.viewer = self.gym.create_viewer(
            self.sim, gymapi.CameraProperties())
        ## esc退出
        self.gym.subscribe_viewer_keyboard_event(
            self.viewer, gymapi.KEY_ESCAPE, "QUIT")
        ## v暂停
        self.gym.subscribe_viewer_keyboard_event(
            self.viewer, gymapi.KEY_V, "toggle_viewer_sync")

总结

未完,持续更新。有些概念本人也不是很懂,大家批判性的眼光看,一起学习,一起进步。

评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值