Hopper Environment

Its a simulation of a monopod robot. The original 3D model was created by ETH Zurich, HopperPage

The simulation was created by TheConstructSim. Its the perfect system to test locomotion algorithms and AI learning for gait research.

Hopper Red Body Jumping

Hopper Jumps in ROSDS

Robot Environment

openai_ros.robot_envs.hopper_env module

class openai_ros.robot_envs.hopper_env.HopperEnv[source]

Bases: openai_ros.robot_gazebo_env.RobotGazeboEnv

Superclass for all HopperEnv environments.

__init__()[source]

Initializes a new HopperEnv 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: * /drone/down_camera/image_raw: RGB Camera facing down. * /drone/front_camera/image_raw: RGB Camera facing front. * /drone/imu: IMU of the drone giving acceleration and orientation relative to world. * /drone/sonar: Sonar readings facing front * /drone/gt_pose: Get position and orientation in Global space * /drone/gt_vel: Get the linear velocity , the angular doesnt record anything.

Actuators Topic List: * /cmd_vel: Move the Drone Around when you have taken off. * /drone/takeoff: Publish into it to take off * /drone/land: Publish to make ParrotDrone Land

Args:

__module__ = 'openai_ros.robot_envs.hopper_env'
_check_all_publishers_ready()[source]

Checks that all the publishers are working :return:

_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_lowerleg_contactsensor_state_ready()[source]
_check_odom_ready()[source]
_check_pub_connection(publisher_object)[source]
_compute_reward(observations, done)[source]

Calculates the reward to give based on the observations given.

_contact_callback(data)[source]
_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]
_odom_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

check_array_similar(ref_value_array, check_value_array, epsilon)[source]

It checks if the check_value id similar to the ref_value

get_imu()[source]
get_joint_states()[source]
get_lowerleg_contactsensor_state()[source]
get_odom()[source]
move_joints(joints_array, epsilon=0.05, update_rate=10)[source]

It will move the Hopper Joints to the given Joint_Array values

wait_time_for_execute_movement(joints_array, epsilon, update_rate)[source]

We wait until Joints are where we asked them to be based on the joints_states :param joints_array:Joints Values in radians of each of the three joints of hopper leg. :param epsilon: Error acceptable in odometry readings. :param update_rate: Rate at which we check the joint_states. :return: