Object

class myGym.envs.env_object.EnvObject(urdf_path, position=[0, 0, 0], orientation=[0, 0, 0, 0], fixed=False, pybullet_client=None)[source]

Env object class for dynamic object in PyBullet environment

Parameters:
param urdf_path

(string) Path to model of object

param position

(list) Position of object in the coordinate frame of the environment ([x,y,z])

param orientation

(list) Orientation of object in the coordinate frame of the environment (quaternion [x,y,z,w])

param fixed

(bool) Whether the object should have fixed position and orientation

param pybullet_client

Which pybullet client the environment should refere to in case of parallel existence of multiple instances of this environment

set_color(color)[source]

Set desired color of object

Parameters:
param color

(list) RGB color to set

set_random_color()[source]

Set random color of object

get_color_rgba()[source]

Get object’s color

Returns:
return self.color_rgba

(list) RGB color of object

set_random_texture(obj_id, patternPath='dtd/images')[source]

Apply texture to object

Parameters:
param obj_id

(int) ID of object

param patternPath

(string) relative path to *.jpg (recursive) with textures

set_init_position(position)[source]

Set object’s initial position in world coordinates

Parameters:
param position

(list) Desired initial position ([x,y,z])

set_init_orientation(orientation)[source]

Set object’s initial orientation in world coordinates

Parameters:
param orientation

(list) Desired initial orientation (quaternion [x,y,z,w])

get_position()[source]

Get object’s position in world coordinates

Returns:
return position

(array) Position ([x,y,z]) of object

get_orientation()[source]

Get object’s orientation in quaterion in world coordinates

Returns:
return orientation

(array) Orientation of object (quaternion [x,y,z,w])

get_orientation_euler()[source]

Get object’s orientation in Euler angles in world coordinates

Returns:
return orientation

(array) Orientation of object in Euler angles (degrees)

get_position_and_orientation()[source]

Get object’s position and orientation in quaterion in world coordinates

Returns:
return orientation

(array) Position ([x,y,z]) Orientation of object (quaternion [x,y,z,w])

set_position(position)[source]

Set object’s position in world coordinates

Parameters:
param position

(array) Position ([x,y,z]) of object

set_orientation(orientation)[source]

Set object’s orientation in quaterion in world coordinates

Parameters:
param orientation

(array) Orientation of object in quaternion ([x,y,z,w])

move(movement)[source]

Move object to new position relative to current position

Parameters:
param movement

(array) By how much to move from current position ([x,y,z])

rotate_euler(rotation)[source]

Rotate object to new orientation relative to current orientation in Euler angles

Parameters:
param rotation

(array) By how much to rotate from current rotation (degrees)

get_file_path()[source]

Get path to object’s model

Returns:
return self.file_path

(string) Path to object’s model

load()[source]

Load object from it’s model to the scene

Returns:
return self.uid

(int) ID of loaded object

get_bounding_box()[source]

Get 3D axis-aligned bounding box of object

Returns:
return bounding_box

(list) Center and 8 coordinates of vertices of the bounding box

get_centroid()[source]

Get position of object’s centroid

Returns:
return centeroid

(array) Position of object’s centroid (center of mass) ([x,y,z])

draw_bounding_box()[source]

Draw object’s 3D bounding box in the scene GUI

get_lines(diag)[source]

Get lines connecting vertices of 3D bounding box

Parameters:
param diag

(list) Diagonal points of 3D bounding box

Returns:
return lines

(list) List of lines connecting vertices of 3D bounding box

get_cuboid_dimensions()[source]

Get dimensions of cuboid defined by object’s 3D bounding box

Returns:
return self.cuboid_dimension

(list) Dimensions of cuboid

get_name()[source]

Get object’s name. Uses data from URDF.

Returns:
return self.name

(string) Object’s name

get_uid()[source]

Get object’s unique ID

Returns:
return self.uid

Object’s unique ID

static get_random_object_position(boarders)[source]

Generate random position in defined volume

Parameters:
param boarders

(list) Volume, where position may be generated ([x,x,y,y,z,z])

Returns:
return pos

(list) Position in specified volume ([x,y,z])

static get_random_object_orientation()[source]

Generate random orientation

Returns:
return orientation

(array) Orientation (quaternion [x,y,z,w])

static get_random_color()[source]

Get random color

Returns:
return color

(list) RGB color