Shadow TC Environment

This simulation was created by Ugo_Cupcic and ShadowHand. It uses apart from ShadowsHand systems, a UR5 robot arm.

UR5 with Shadow Claw

Robot Environment

openai_ros.robot_envs.shadow_tc_env module

class openai_ros.robot_envs.shadow_tc_env.ShadowTcEnv[source]

Bases: openai_ros.robot_gazebo_env.RobotGazeboEnv

Superclass for all ShadowTcEnv environments.

__init__()[source]

Initializes a new ShadowTcEnv environment.

To check any topic we need to have the simulations running, we need to do two things: 1) Unpause the simulation: without that th stream of data doesnt flow. This is for simulations that are pause for whatever the reason 2) If the simulation was running already for some reason, we need to reset the controlers. This has to do with the fact that some plugins with tf, dont understand the reset of the simulation and need to be reseted to work properly.

The Sensors: The sensors accesible are the ones considered usefull for AI learning.

Sensor Topic List: * /imu/data * /joint_states

Actuators Topic List: * As actuator we will use a class SmartGrasper to interface. We use smart_grasping_sandbox smart_grasper.py, to move and get the pose of the ball and the tool tip.

Args:

__module__ = 'openai_ros.robot_envs.shadow_tc_env'
_check_all_sensors_ready()[source]
_check_all_systems_ready()[source]

Checks that all the sensors, publishers and other simulation systems are operational.

_check_imu_ready()[source]
_check_joint_states_ready()[source]
_check_planning_scene_ready()[source]
_compute_reward(observations, done)[source]

Calculates the reward to give based on the observations given.

_get_obs()[source]
_imu_callback(data)[source]
_init_env_variables()[source]

Inits variables needed to be initialised each time we reset at the start of an episode.

_is_done(observations)[source]

Checks if episode done based on observations given.

_joints_state_callback(data)[source]
_planning_scene_callback(data)[source]
_set_action(action)[source]

Applies the given action to the simulation.

_set_init_pose()[source]

Sets the Robot in its init pose

_setup_smart_grasper()[source]

Setup of the movement system. :return:

_setup_tf_listener()[source]

Set ups the TF listener for getting the transforms you ask for.

close_hand()[source]

When called it closes robots hand

get_ball_pose()[source]

Get Ball Pose return: Ball Pose in the World frame We unpause and pause the simulation because this calss is a service call. This means that if the simulation is NOT running it wont get the Ball information of position.

get_fingers_colision(object_collision_name)[source]

Returns the collision of the three fingers object_collision_name: Here yo ustate the name of the model to check collision with fingers. Objects in sim: cricket_ball__link, drill__link

get_imu()[source]
get_joint_states()[source]
get_tip_pose()[source]

Returns the pose of the tip of the TCP We unpause and pause the simulation because this calss is a service call. This means that if the simulation is NOT running it wont get the TCP information of position.

move_tcp_world_frame(desired_pose)[source]

Moves the Tool tip TCP to the pose given Its relative pose to world frame :param: desired_pose: Pose where you want the TCP to move next

move_tip(x=0.0, y=0.0, z=0.0, roll=0.0, pitch=0.0, yaw=0.0)[source]

Moves that increment of XYZ RPY in the world frame Only state the increment of the variable you want, the rest will not increment due to the default values

open_hand()[source]

When called it opens robots hand

reset_scene()[source]

Restarts the simulation and world objects

send_movement_command(command, duration=0.2)[source]

Send a dictionnary of joint targets to the arm and hand directly. To get the available joints names: rostopic echo /joint_states/name -n1 [H1_F1J1, H1_F1J2, H1_F1J3, H1_F2J1, H1_F2J2, H1_F2J3, H1_F3J1, H1_F3J2, H1_F3J3, elbow_joint, shoulder_lift_joint, shoulder_pan_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint]

Parameters:
  • command – a dictionnary of joint names associated with a target: {“H1_F1J1”: -1.0, “shoulder_pan_joint”: 1.0}
  • duration – the amount of time it will take to get there in seconds. Needs to be bigger than 0.0
set_fingers_colision(activate=False)[source]

It activates or deactivates the finger collisions. It also will triguer the publish into the planning_scene the collisions. We puase and unpause for the smae exact reason as the get TCP and get ball pos. Being a service, untill the simulation is unpaused it wont get response.