-1: numpy必须为1.20.0,否则会报错,版本冲突 0.rl value-based: 如q-learning(走迷宫),对当前状态下作出的动作进行价值计算,通过贪婪策略穷尽所有可能选择最佳state-action,但是对于连续的动作空间,动作的值是无穷的,把他们离散化,会维度爆炸,MSE policy-based: 比如移动机器人在一个室内环境中导航,策略网络以机器人当前的传感器信息(如激光雷达数据、摄像头图像)作为输入,输出动作的概率分布(对于连续动作)。 通过策略梯度算法,根据机器人是否成功到达目标位置以及所花费的时间等奖励信号来更新策略网络的参数。训练过程可能会受到局部最优解的影响,并且策略梯度的估计可能存在较大方差,导致训练不稳定 LOSS:负号是因为我们要使用梯度下降优化器,而策略梯度的目标是进行梯度上升。 --PPO 是一种改进的策略梯度算法,旨在提高训练的稳定性和样本效率。它通过限制策略更新的步长,避免更新幅度过大导致性能下降。 1.代码解析 1.0 on_policy_runner.py: class OnPolicyRunner.learn tot_iter = self.current_learning_iteration + num_learning_iterations for it in range(self.current_learning_iteration, tot_iter): start = time.time() with torch.inference_mode(): for i in range(self.num_steps_per_env): actions = self.alg.act(obs, critic_obs) # 2048,8,84(64+19)-->transformer 预测动作分布,再采样出2048*19个关节的动作, 84是观测值:观测值的计算综合了机器人的多种状态信息,如姿态、角速度、指令、关节位置和速度、动作等,并且可以根据配置添加感知输入和噪声。 obs, privileged_obs, rewards, dones, infos = self.env.step(actions) #仿真环境中执行上面的动作,action--》compute_torques;compute observations,rewards, resets critic_obs = privileged_obs if privileged_obs is not None else obs obs, critic_obs, rewards, dones = obs.to(self.device), critic_obs.to(self.device), rewards.to(self.device), dones.to(self.device) self.alg.process_env_step(rewards, dones, infos) # 对环境交互一个时间步结果的处理,包括奖励和终止信号的保存、超时情况的处理、转换信息的记录以及智能体的重置,为后续的学习和决策提供了基础。 1.1 HST --class H1(): legged_gym/env/h1/h1.py ----init: self._super_init-->self.create_sim-->self._create_envs ----step ----post_physics_step ----reset ----compute_reward ----compute_observations ----create_sim ----_compute_torques ----_create_envs ----render --class H1RoughCfg( BaseConfig ): legged_gym/env/h1/h1_config.py ----class human: ----class env: ----class terrain: ----class commands: ----class init_state: ----class control: ----class asset: ----class domain_rand: ----class rewards: ----class noise: ----class sim: --class H1RoughCfgPPO(BaseConfig): ----class policy: ----class algorithm: ----class runner: 2.网络结构 1.ActorNET = Transformer + mlp Actor MLP: Transformer( (input_layer): Sequential( (0): Linear(in_features=84, out_features=128, bias=True) (1): Dropout(p=0.1, inplace=False) ) (weight_pos_embed): Embedding(8, 128) (attention_blocks): Sequential( (0): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) (1): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) (2): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) (3): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) ) (output_layer): Sequential( (0): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (1): Linear(in_features=128, out_features=19, bias=True) ) ) ================================================================================================================== 2.CriticNet = MLP + Transformer Critic MLP: Transformer( (input_layer): Sequential( (0): Linear(in_features=84, out_features=128, bias=True) (1): Dropout(p=0.1, inplace=False) ) (weight_pos_embed): Embedding(8, 128) (attention_blocks): Sequential( (0): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) (1): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) (2): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) (3): Transformer_Block( (ln_1): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (attn): MultiheadAttention( (out_proj): NonDynamicallyQuantizableLinear(in_features=128, out_features=128, bias=True) ) (ln_2): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (mlp): Sequential( (0): Linear(in_features=128, out_features=512, bias=True) (1): GELU() (2): Linear(in_features=512, out_features=128, bias=True) (3): Dropout(p=0.1, inplace=False) ) ) ) (output_layer): Sequential( (0): LayerNorm((128,), eps=1e-05, elementwise_affine=True) (1): Linear(in_features=128, out_features=1, bias=True) ) )
可视化:
import argparse import numpy as np import pinocchio as pin import rerun as rr import trimesh class RerunURDF(): def __init__(self, robot_type): self.name = robot_type match robot_type: case 'g1': self.robot = pin.RobotWrapper.BuildFromURDF('robot_description/g1/g1_29dof_rev_1_0.urdf', 'robot_description/g1', pin.JointModelFreeFlyer()) self.Tpose = np.array([0,0,0.785,0,0,0,1, -0.15,0,0,0.3,-0.15,0, -0.15,0,0,0.3,-0.15,0, 0,0,0, 0, 1.57,0,1.57,0,0,0, 0,-1.57,0,1.57,0,0,0]).astype(np.float32) case 'h1_2': self.robot = pin.RobotWrapper.BuildFromURDF('robot_description/h1_2/h1_2_wo_hand.urdf', 'robot_description/h1_2', pin.JointModelFreeFlyer()) assert self.robot.model.nq == 7 + 12+1+14 self.Tpose = np.array([0,0,1.02,0,0,0,1, 0,-0.15,0,0.3,-0.15,0, 0,-0.15,0,0.3,-0.15,0, 0, 0, 1.57,0,1.57,0,0,0, 0,-1.57,0,1.57,0,0,0]).astype(np.float32) case 'h1': self.robot = pin.RobotWrapper.BuildFromURDF('robot_description/h1/h1.urdf', 'robot_description/h1', pin.JointModelFreeFlyer()) assert self.robot.model.nq == 7 + 10+1+8 self.Tpose = np.array([0,0,1.03,0,0,0,1, 0,0,-0.15,0.3,-0.15, 0,0,-0.15,0.3,-0.15, 0, 0, 1.57,0,1.57, 0,-1.57,0,1.57]).astype(np.float32) case _: print(robot_type) raise ValueError('Invalid robot type') # print all joints names # for i in range(self.robot.model.njoints): # print(self.robot.model.names[i]) self.link2mesh = self.get_link2mesh() self.load_visual_mesh() self.update() def get_link2mesh(self): link2mesh = {} for visual in self.robot.visual_model.geometryObjects: mesh = trimesh.load_mesh(visual.meshPath) name = visual.name[:-2] mesh.visual = trimesh.visual.ColorVisuals() mesh.visual.vertex_colors = visual.meshColor link2mesh[name] = mesh return link2mesh def load_visual_mesh(self): self.robot.framesForwardKinematics(pin.neutral(self.robot.model)) for visual in self.robot.visual_model.geometryObjects: frame_name = visual.name[:-2] mesh = self.link2mesh[frame_name] frame_id = self.robot.model.getFrameId(frame_name) parent_joint_id = self.robot.model.frames[frame_id].parentJoint parent_joint_name = self.robot.model.names[parent_joint_id] frame_tf = self.robot.data.oMf[frame_id] joint_tf = self.robot.data.oMi[parent_joint_id] rr.log(f'urdf_{self.name}/{parent_joint_name}', rr.Transform3D(translation=joint_tf.translation, mat3x3=joint_tf.rotation, axis_length=0.01)) relative_tf = frame_tf * joint_tf.inverse() mesh.apply_transform(relative_tf.homogeneous) rr.log(f'urdf_{self.name}/{parent_joint_name}/{frame_name}', rr.Mesh3D( vertex_positions=mesh.vertices, triangle_indices=mesh.faces, vertex_normals=mesh.vertex_normals, vertex_colors=mesh.visual.vertex_colors, albedo_texture=None, vertex_texcoords=None, ), timeless=True) def update(self, configuration = None): self.robot.framesForwardKinematics(self.Tpose if configuration is None else configuration) for visual in self.robot.visual_model.geometryObjects: frame_name = visual.name[:-2] frame_id = self.robot.model.getFrameId(frame_name) parent_joint_id = self.robot.model.frames[frame_id].parentJoint parent_joint_name = self.robot.model.names[parent_joint_id] joint_tf = self.robot.data.oMi[parent_joint_id] rr.log(f'urdf_{self.name}/{parent_joint_name}', rr.Transform3D(translation=joint_tf.translation, mat3x3=joint_tf.rotation, axis_length=0.01)) if __name__ == "__main__": parser = argparse.ArgumentParser() parser.add_argument('--file_name', type=str, help="File name", default='dance1_subject2') parser.add_argument('--robot_type', type=str, help="Robot type", default='g1') args = parser.parse_args() rr.init('Reviz', spawn=True) rr.log('', rr.ViewCoordinates.RIGHT_HAND_Z_UP, timeless=True) rr.set_time_sequence('frame_nr', 0) file_name = args.file_name robot_type = args.robot_type csv_files = robot_type + '/' + file_name + '.csv' data = np.genfromtxt(csv_files, delimiter=',') rerun_urdf = RerunURDF(robot_type) for frame_nr in range(data.shape[0]): rr.set_time_sequence('frame_nr', frame_nr) configuration = data[frame_nr, :] rerun_urdf.update(configuration)