Robot¶
The Robot Module in myGym takes care of interaction between robot and environment. In this module, actions received from trained model are executed on simulated robot. You can specify name of a robot you would like to train and Robot module will add it to your environment. This module automatically loads robot’s configuration and does the robot control for you. The robots are equiped with various types of grippers as well.
Currently available robots are: kuka, panda, jaco, reachy, leachy, reachy_and_leachy, gummi, ur3, ur5, ur10, yumi. Note that for jaco and gummi with complex grippers there are also versions with fixed gripper joints jaco_fixed and gummi_fixed. See more details in Robots.
-
class
myGym.envs.robot.
Robot
(robot='kuka', position=[- 0.1, 0, 0.07], orientation=[0, 0, 0], end_effector_index=None, gripper_index=6, init_joint_poses=None, robot_action='step', use_fixed_gripper_orn=False, gripper_orn=[0, - 3.141592653589793, 0], dimension_velocity=0.5, max_velocity=1.0, max_force=300.0, pybullet_client=None)[source]¶ Robot class for control of robot environment interaction
- Parameters:
- param robot
(string) Type of robot to train in the environment (kuka, panda, ur3, …)
- param position
(list) Position of the robot’s base link in the coordinate frame of the environment ([x,y,z])
- param orientation
(list) Orientation of the robot’s base link in the coordinate frame of the environment (Euler angles [x,y,z])
- param end_effector_index
(int) Index of the robot’s end-effector link. For myGym prepared robots this is assigned automatically.
- param gripper_index
(int) Index of the robot’s gripper link. For myGym prepared robots this is assigned automatically.
- param init_joint_poses
(list) Configuration in which robot will be initialized in the environment. Specified either in joint space as list of joint poses or in the end-effector space as [x,y,z] coordinates.
- param robot_action
(string) Mechanism of robot control (absolute, step, joints)
- param use_fixed_gripper_orn
(bool) Whether to fix robot’s end-effector orientation or not
- param gripper_orn
(list) Orientation of gripper in Euler angles for the fixed_gripper_orn option
- param dimension_velocity
(float) Maximum allowed velocity for robot movements in individual x,y,z axis
- param max_velocity
(float) Maximum allowed velocity for robot movements. Should be adjusted in case of sim2real scenario.
- param max_force
(float) Maximum allowed force reached by individual joint motor. Should be adjusted in case of sim2real scenario.
- param pybullet_client
Which pybullet client the environment should refere to in case of parallel existence of multiple instances of this environment
-
reset
(random_robot=False)[source]¶ Reset joint motors
- Parameters:
- param random_robot
(bool) Whether the joint positions after reset should be randomized or equal to initial values.
-
reset_joints
(joint_poses)[source]¶ Reset joint motors to requested values
- Parameters:
- param positions
(list) Values for individual joint motors
-
get_joints_limits
()[source]¶ Identify limits, ranges and rest poses of individual robot joints. Uses data from robot model.
- Returns:
- return [joints_limits_l, joints_limits_u]
(list) Lower and upper limits of all joints
- return joints_ranges
(list) Ranges of movement of all joints
- return joints_rest_poses
(list) Rest poses of all joints
-
get_action_dimension
()[source]¶ Get dimension of action data, based on robot control mechanism
- Returns:
- return dimension
(int) The dimension of action data
-
get_observation_dimension
()[source]¶ Get dimension of robot part of observation data, based on robot task and rewatd type
- Returns:
- return dimension
(int) The dimension of observation data
-
get_observation
()[source]¶ Get robot part of observation data
- Returns:
- return observation
(list) Position of end-effector link (center of mass)
-
get_position
()[source]¶ Get position of robot’s end-effector link
- Returns:
- return position
(list) Position of end-effector link (center of mass)
-
apply_action_step
(action)[source]¶ Apply action command to robot using step control mechanism
- Parameters:
- param action
(list) Desired action data
-
apply_action_absolute
(action)[source]¶ Apply action command to robot using absolute control mechanism
- Parameters:
- param action
(list) Desired action data
-
apply_action_joints
(action)[source]¶ Apply action command to robot using joints control mechanism
- Parameters:
- param action
(list) Desired action data
-
apply_action_joints_step
(action)[source]¶ Apply action command to robot using joint-step control mechanism
- Parameters:
- param action
(list) Desired action data