def __init__(self, config): self.config = config self.velocity = config.get("velocity", 1.0) LocomotorRobot.__init__(self, "turtlebot/turtlebot.urdf", action_dim=2, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", False), control="velocity")
def __init__(self, config): self.config = config self.velocity = config.get('velocity', 1.0) LocomotorRobot.__init__(self, "jr2_urdf/jr2.urdf", action_dim=4, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", True), control='velocity')
def __init__(self, config): self.config = config self.torque = config.get("torque", 0.03) LocomotorRobot.__init__(self, "husky/husky.urdf", action_dim=4, torque_coef=2.5, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", False), control="torque")
def __init__(self, config): self.config = config self.torque = config.get("torque", 1.0) LocomotorRobot.__init__( self, "ant/ant.xml", action_dim=8, torque_coef=2.5, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", False), control="torque", )
def __init__(self, config): self.config = config self.wheel_velocity = config.get('wheel_velocity', 0.3) self.wheel_dim = 2 self.arm_velocity = config.get('arm_velocity', 1.0) self.arm_dim = 5 LocomotorRobot.__init__(self, "jr2_urdf/jr2_kinova.urdf", action_dim=self.wheel_dim + self.arm_dim, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", False), control='velocity', self_collision=True)
def __init__(self, config): self.config = config self.torque = config.get("torque", 0.1) self.glass_id = None self.glass_offset = 0.3 LocomotorRobot.__init__( self, "humanoid/humanoid.xml", action_dim=17, torque_coef=0.41, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", False), control="torque", self_collision=True, )
def __init__(self, config): self.config = config self.wheel_velocity = config.get('wheel_velocity', 1.0) self.torso_lift_velocity = config.get('torso_lift_velocity', 1.0) self.arm_velocity = config.get('arm_velocity', 1.0) self.wheel_dim = 2 self.torso_lift_dim = 1 self.arm_dim = 7 LocomotorRobot.__init__(self, "fetch/fetch.urdf", action_dim=self.wheel_dim + self.torso_lift_dim + self.arm_dim, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", False), control="velocity", self_collision=True)
def __init__(self, config): self.config = config # https://www.trossenrobotics.com/locobot-pyrobot-ros-rover.aspx # Maximum translational velocity: 70 cm/s # Maximum rotational velocity: 180 deg/s (>110 deg/s gyro performance will degrade) self.linear_velocity = config.get('linear_velocity', 0.5) self.angular_velocity = config.get('angular_velocity', np.pi / 2.0) self.wheel_dim = 2 self.wheel_axle_half = 0.115 # half of the distance between the wheels self.wheel_radius = 0.038 # radius of the wheels LocomotorRobot.__init__(self, "locobot/locobot.urdf", base_name="base_link", action_dim=self.wheel_dim, scale=config.get("robot_scale", 1.0), is_discrete=config.get("is_discrete", False), control="differential_drive")
def __init__(self, config, env=None, pd_control_enabled=True, accurate_motor_model_enabled=True): """Constructs a minitaur and reset it to the initial states. Properties: self_collision_enabled: Whether to enable self collision. motor_velocity_limit: The upper limit of the motor velocity. pd_control_enabled: Whether to use PD control for the motors. If true, need smaller time step to stablize (1/500.0 timestep) accurate_motor_model_enabled: Whether to use the accurate DC motor model. motor_kp: proportional gain for the accurate motor model motor_kd: derivative gain for the acurate motor model torque_control_enabled: Whether to use the torque control, if set to False, pose control will be used. motor_overheat_protection: Whether to shutdown the motor that has exerted large torque (OVERHEAT_SHUTDOWN_TORQUE) for an extended amount of time (OVERHEAT_SHUTDOWN_TIME). See apply_action() in minitaur_robot.py for more details. on_rack: Whether to place the minitaur on rack. This is only used to debug the walking gait. In this mode, the minitaur's base is hanged midair so that its walking gait is clearer to visualize. kd_for_pd_controllers: kd value for the pd controllers of the motors. """ self.config = config self.model_type = "URDF" #self.robot_name = "quadruped" self.robot_name = "base_chassis_link" scale = config["robot_scale"] if "robot_scale" in config.keys( ) else self.default_scale LocomotorRobot.__init__(self, "quadruped/minitaur.urdf", self.robot_name, action_dim=8, sensor_dim=self.OBSERVATION_DIM, power=5, scale=scale, initial_pos=config['initial_pos'], target_pos=config["target_pos"], resolution=config["resolution"], env=env) self.r_f = 0.1 self.time_step = config["speed"]["timestep"] self.pd_control_enabled = pd_control_enabled self.minitaur = None # TODO: fix this self.accurate_motor_model_enabled = accurate_motor_model_enabled if self.accurate_motor_model_enabled: self._kp = self.motor_kp self._kd = self.motor_kd self._motor_model = motor.MotorModel(torque_control_enabled=self.torque_control_enabled, kp=self._kp, kd=self._kd) elif self.pd_control_enabled: self._kp = 8 self._kd = self.kd_for_pd_controllers else: self._kp = 1 self._kd = 1 if config["is_discrete"]: self.action_space = gym.spaces.Discrete(17) self.torque = 10 ## Hip_1, Ankle_1, Hip_2, Ankle_2, Hip_3, Ankle_3, Hip_4, Ankle_4 self.action_list = [[self.r_f * self.torque, 0, 0, 0, 0, 0, 0, 0], [0, self.r_f * self.torque, 0, 0, 0, 0, 0, 0], [0, 0, self.r_f * self.torque, 0, 0, 0, 0, 0], [0, 0, 0, self.r_f * self.torque, 0, 0, 0, 0], [0, 0, 0, 0, self.r_f * self.torque, 0, 0, 0], [0, 0, 0, 0, 0, self.r_f * self.torque, 0, 0], [0, 0, 0, 0, 0, 0, self.r_f * self.torque, 0], [0, 0, 0, 0, 0, 0, 0, self.r_f * self.torque], [-self.r_f * self.torque, 0, 0, 0, 0, 0, 0, 0], [0, -self.r_f * self.torque, 0, 0, 0, 0, 0, 0], [0, 0, -self.r_f * self.torque, 0, 0, 0, 0, 0], [0, 0, 0, -self.r_f * self.torque, 0, 0, 0, 0], [0, 0, 0, 0, -self.r_f * self.torque, 0, 0, 0], [0, 0, 0, 0, 0, -self.r_f * self.torque, 0, 0], [0, 0, 0, 0, 0, 0, -self.r_f * self.torque, 0], [0, 0, 0, 0, 0, 0, 0, -self.r_f * self.torque], [0, 0, 0, 0, 0, 0, 0, 0]] self.setup_keys_to_action() self.debug_count = 0 self.qmax = [0] * 8 self.fmax = [0] * 8