symaware.simulators.pybullet package
Submodules
symaware.simulators.pybullet.dynamical_model module
- class symaware.simulators.pybullet.dynamical_model.DroneCf2pModel(ID, debug=False)[source]
Bases:
DroneModel
Dynamical model adapted for the Cf2 drone
- class symaware.simulators.pybullet.dynamical_model.DroneCf2xModel(ID, debug=False)[source]
Bases:
DroneModel
Dynamical model adapted for the Cf2x drone
- class symaware.simulators.pybullet.dynamical_model.DroneModel(ID, urp_path, debug=False)[source]
Bases:
DynamicalModel
Base dynamical model for drones
- __LOGGER = <Logger symaware.simulators.pybullet.DroneModel (WARNING)>
- _downwash()[source]
PyBullet implementation of a ground effect model.
Based on experiments conducted at the Dynamic Systems Lab by SiQi Zhou.
- _drag(rpm)[source]
PyBullet implementation of a drag model.
Based on the the system identification in (Forster, 2015).
- Parameters:
rpm (ndarray) – (4)-shaped array of ints containing the RPMs values of the 4 motors.
- _dynamics(rpm)[source]
Explicit dynamics implementation.
Based on code written at the Dynamic Systems Lab by James Xu.
- Parameters:
rpm (ndarray) – (4)-shaped array of ints containing the RPMs values of the 4 motors.
nth_drone (int) – The ordinal number/position of the desired drone in list self.DRONE_IDS.
- _get_state()[source]
Returns the state vector of the n-th drone.
- Returns:
(16)-shaped array of floats containing the state vector of the n-th drone. Check the only line in this method and _updateAndStoreKinematicInformation() to understand its format.
- _ground_effect(rpm)[source]
PyBullet implementation of a ground effect model.
Inspired by the analytical model used for comparison in (Shi et al., 2019).
- Parameters:
rpm (ndarray) – (4)-shaped array of ints containing the RPMs values of the 4 motors.
- _load_urdf_args()[source]
Loads parameters from an URDF file.
This method is nothing more than a custom XML parser for the .urdf files in folder assets/.
- _update_kinematic_info()[source]
Updates and stores the drones kinematic information.
This method is meant to limit the number of calls to PyBullet in each step and improve performance (at the expense of memory).
- property normalized_control_input
- normalized_control_input_to_rpm(normalized_control_input)[source]
De-normalizes the [-1, 1] range to the [0, max_rpm] range.
- Parameters:
normalized_control_input (
ndarray
) – (4)-shaped array of ints containing an input in the [-1, 1] range.- Returns:
(4)-shaped array of ints containing RPMs for the 4 motors in the [0, max_rpm] range.
- property subinputs_dict: DroneModelSubinputs
The input of a system is the composition of subinputs.
Example
A car input [vx, vy, vz, s] is composed by the velocity and the steering angle.
>>> from symaware.base import DynamicalModel >>> class CarModel(DynamicalModel): ... @property ... def subinputs_dict(self): ... return { ... "velocity": self._control_input[:3], ... "steering_angle": self._control_input[3] ... } ...
Important
The order of the subinputs in the list must be the same as the order of the subinputs in the input vector
- class symaware.simulators.pybullet.dynamical_model.DroneRacerModel(ID, debug=False)[source]
Bases:
DroneModel
Dynamical model adapted for the Racer drone
- class symaware.simulators.pybullet.dynamical_model.DynamicalModel(ID, control_input)[source]
Bases:
DynamicalModel
Abstract class for the dynamical models using the PyBullet physics engine.
- Parameters:
- class symaware.simulators.pybullet.dynamical_model.RacecarModel(ID, max_force=20.0, steering_links=(0, 2), motorized_wheels=(8, 15))[source]
Bases:
DynamicalModel
PyBullet dynamical model for the racecar.
- Parameters:
ID (
int
) – Identifier of the agent this model belongs tocontrol_input – Initial control input of the agent. It also used to validate the size of future control inputs
max_force (
float
, default:20.0
) – Maximum force that can be applied to the wheelssteering_links (
tuple
[int
,int
], default:(0, 2)
) – Tuple of the two links that are used to steer the carmotorized_wheels (
tuple
[int
,int
], default:(8, 15)
) – Tuple of the two links that are used to drive the car
- __LOGGER = <Logger symaware.simulators.pybullet.RacecarModel (WARNING)>
- initialise(entity_id)[source]
Initialise the dynamical model. Called by the associated entity when it is added to the environment.
- Parameters:
args – Additional arguments
kwargs – Additional keyword arguments
- step()[source]
Run a simulation step of the dynamical model. Called by the associated entity at each simulation step.
- Parameters:
args – Additional arguments
kwargs – Additional keyword arguments
- property subinputs_dict: RacecarModelSubinputs
The input of a system is the composition of subinputs.
Example
A car input [vx, vy, vz, s] is composed by the velocity and the steering angle.
>>> from symaware.base import DynamicalModel >>> class CarModel(DynamicalModel): ... @property ... def subinputs_dict(self): ... return { ... "velocity": self._control_input[:3], ... "steering_angle": self._control_input[3] ... } ...
Important
The order of the subinputs in the list must be the same as the order of the subinputs in the input vector
- class symaware.simulators.pybullet.dynamical_model.RawDynamicalModel(agent_id)[source]
Bases:
DynamicalModel
Raw dynamical model for the entity. It allows to set the position and orientation of the entity directly. It takes a control input of six elements:
x: x position
y: y position
z: z position
yaw: yaw orientation
pitch: pitch orientation
roll: roll orientation
- step()[source]
Run a simulation step of the dynamical model. Called by the associated entity at each simulation step.
- Parameters:
args – Additional arguments
kwargs – Additional keyword arguments
- property subinputs_dict: RawModelSubinputs
The input of a system is the composition of subinputs.
Example
A car input [vx, vy, vz, s] is composed by the velocity and the steering angle.
>>> from symaware.base import DynamicalModel >>> class CarModel(DynamicalModel): ... @property ... def subinputs_dict(self): ... return { ... "velocity": self._control_input[:3], ... "steering_angle": self._control_input[3] ... } ...
Important
The order of the subinputs in the list must be the same as the order of the subinputs in the input vector
- class symaware.simulators.pybullet.dynamical_model.Velocity2DModel(agent_id, z=2, pitch=0, roll=0, time_step=-1.0)[source]
Bases:
DynamicalModel
A simple model that moves the entity in the x-y plane. The entity can move forward and rotate around the z-axis. It takes a control input of two elements:
v: linear velocity (scalar)
w: angular velocity (scalar)
From the control input, the model computes the new position and orientation of the entity based on the following kinematic equations:
x’ = x + t_e * v * cos(yaw) y’ = y + t_e * v * sin(yaw) yaw’ = yaw + t_e * w
where t_e is the time elapsed since the last step and x, y, yaw are the current x-y position and orientation of the entity.
- Parameters:
agent_id (
int
) – Identifier of the agent this model belongs toz (
float
, default:2
) – Fixed height of the entitypitch (
float
, default:0
) – Fixed pitch of the entityroll (
float
, default:0
) – Fixed roll of the entitytime_step (
float
, default:-1.0
) – Fix the time interval between each step to a specific value. If it is <= 0, the model will use the real time elapsed between each step instead.
- step()[source]
Run a simulation step of the dynamical model. Called by the associated entity at each simulation step.
- Parameters:
args – Additional arguments
kwargs – Additional keyword arguments
- property subinputs_dict: Velocity2DSubinputs
The input of a system is the composition of subinputs.
Example
A car input [vx, vy, vz, s] is composed by the velocity and the steering angle.
>>> from symaware.base import DynamicalModel >>> class CarModel(DynamicalModel): ... @property ... def subinputs_dict(self): ... return { ... "velocity": self._control_input[:3], ... "steering_angle": self._control_input[3] ... } ...
Important
The order of the subinputs in the list must be the same as the order of the subinputs in the input vector
symaware.simulators.pybullet.entities module
- class symaware.simulators.pybullet.entities.A1Entity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/pybullet_data/a1/a1.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
A1 entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags (
int
, default:0
) – Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.AirplaneEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/symaware/simulators/pybullet/assets/airplane.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Airplane entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags: Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.BoxEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, sizes=<factory>)[source]
Bases:
Entity
Box entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
sizes (
ndarray
, default:<factory>
) – Size of the box
- class symaware.simulators.pybullet.entities.CubeEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/pybullet_data/cube.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Cube entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags: Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.DroneCf2pEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/symaware/simulators/pybullet/assets/cf2p.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Drone entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags: Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.DroneCf2xEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/symaware/simulators/pybullet/assets/cf2x.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Drone entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags: Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.DroneRacerEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/symaware/simulators/pybullet/assets/racer.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Drone entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags: Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.Entity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1)[source]
Bases:
Entity
Abstract class for the entities using the PyBullet physics engine. All the internal identifiers are set to -1 by default, and will be set to the correct values during the initialisation.
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
- property entity_id
- model: DynamicalModel
- class symaware.simulators.pybullet.entities.Plane100Entity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/pybullet_data/plane100.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Plane entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags: Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.PlaneEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/pybullet_data/plane.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Default plane entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags: Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.RacecarEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='/builds/sadegh/eicsymaware/.tox/docs/lib/python3.12/site-packages/pybullet_data/racecar/racecar_differential.urdf', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
URDFEntity
Racecar entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
init_flags (
int
, default:0
) – Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- class symaware.simulators.pybullet.entities.SphereEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, radius=1.0)[source]
Bases:
Entity
Sphere entity
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
radius (
float
, default:1.0
) – Radius of the sphere
- class symaware.simulators.pybullet.entities.URDFEntity(id=-1, model=<factory>, mass=1, position=<factory>, velocity=<factory>, orientation=<factory>, _entity_id=-1, _col_id=-1, _vis_id=-1, _bod_id=-1, urdf_path='', init_flags=0, global_scaling=1.0, texture_ids=-1, rgb_colors=(-1, -1, -1, -1))[source]
Bases:
Entity
Generic entity loaded from a URDF file
- Parameters:
id (
int
, default:-1
) – Identifier of the entity, if linked to anAgent
mass (
float
, default:1
) – Mass of the entity in the physics simulationposition (
ndarray
, default:<factory>
) – (3)-shaped initial position of the entity. If the size is less than 3, the missing values are set to 0velocity (
ndarray
, default:<factory>
) – (3)-shaped initial velocity of the entity. If the size is less than 3, the missing values are set to 0orientation (
ndarray
, default:<factory>
) – (3,4)-shaped initial orientation of the entity. A 3-sized array is interpreted as Euler angles and converted to a 4-sized quaternion arraymodel (
DynamicalModel
, default:<factory>
) – Dynamical model associated with the entity. Must be a subclass ofPybulletDynamicalModel
urdf_path (
str
, default:''
) – Path to the URDF file containing the definition of the entityinit_flags (
int
, default:0
) – Flags to use when loading the URDF fileglobal_scaling (
float
, default:1.0
) – Scaling factor to apply to the entity’s sizetexture_ids (
int
|dict
[int
,int
], default:-1
) – Unique id of the texture to apply to link -1 or dictionary of values { link_id: texture_id } If set to -1, no texture is applied.rgb_colors (
tuple
[float
,float
,float
,float
] |dict
[int
,tuple
[int
,int
,int
,int
]], default:(-1, -1, -1, -1)
) – Tuple of for elements (red, green, blu, alpha) to apply to link -1 or dictionary of values { link_id: (red, green, blu, alpha) }. The color values range from [0, 1]. If set to a tuple and any of its values are negative, no rgb_color is applied.
- rgb_colors: tuple[float, float, float, float] | dict[int, tuple[int, int, int, int]] = (-1, -1, -1, -1)
- texture_ids: int | dict[int, int] = -1
symaware.simulators.pybullet.environment module
- class symaware.simulators.pybullet.environment.Environment(real_time_interval=0, connection_method=1, plane_scaling=1.0, gravity=(0, 0, -9.8), async_loop_lock=None)[source]
Bases:
Environment
Environment based on the PyBullet physics engine.
- Parameters:
real_time_interval (
float
, default:0
) – If set to a strictly positive value, pybullet will run the simulation in real time. Otherwise, the simulation will run whenstep()
is called.connection_method (
int
, default:1
) – Method used to connect to the pybullet server. See the pybullet documentation for more information.plane_scaling (
float
, default:1.0
) – Scale of the plane automatically added to the environment to represent the ground. If set to a non positive value, the plane will not be added.gravity (
float
|tuple
[float
,float
,float
], default:(0, 0, -9.8)
) – Set the gravity the physics engine will apply at each simulation step. It can be a single floating point value, in which case it will be applied along the third axis, or a tuple of three values, one for each axis.async_loop_lock (
AsyncLoopLock
|None
, default:None
) – Async loop lock to use for the environment
- __LOGGER = <Logger symaware.simulators.pybullet.Pybullet.Environment (WARNING)>
- _add_entity(entity)[source]
Add an entity to the environment, initialising it. The actual implementation should be done in the derived class, based on the simulated environment API. The entity’s
initialise_entity()
function should be called within this function with the appropriate arguments.- Parameters:
entity (
Entity
) – entity to initialise
- configure_debug_visualizer(flag, enable, light_position, shadow_map_resolution, shadow_map_size, shadow_map_intensity, rgb_background)[source]
Configure the debug visualizer in the pybullet environment
- Parameters:
flag (
int
) – Flag to setenable (
bool
) – Enable or disable the debug visualizerlight_position (
tuple
[float
,float
,float
]) – Position of the lightshadow_map_resolution (
int
) – Resolution of the shadow mapshadow_map_size (
int
) – Size of the shadow mapshadow_map_intensity (
float
) – Intensity of the shadow maprgb_background (
tuple
[float
,float
,float
]) – Background color
- get_entity_state(entity)[source]
Get the state of an entity in the environment. The actual implementation should be done in the derived class, based on the simulated environment API.
- initialise()[source]
Initialise the simulation, allocating the required resources. Should be called when the simulation has been set up and is ready to be run. Some environment implementations may call it automatically when the environment is created. It is their responsibility to ensure that the method is idempotent.
- set_debug_camera_position(distance, yaw, pitch, position)[source]
Set the position of the debug camera in the pybullet environment.
- step()[source]
It can be called repeatedly step the environment forward in time, updating the state of all the entities.
- stop()[source]
Terminate the simulation, releasing the resources. Should be called when the simulation has been running manually and needs to be stopped. Some environment implementations may call it automatically when the environment is destroyed. It is their responsibility to ensure that the method is idempotent.
Warning
Depending on the simulator implementation, calling this method may invalidate all the entities previously added to the environment. In that case, entities and the environment should be recreated from scratch.
- take_screenshot(width=1440, height=1120, shadow=False, renderer=65536)[source]
Take a screenshot of the current view of the camera and return it as a 3-dimensional numpy array of (height x width x rgba). The rgba values are in the interval [0, 1].
An image produced this way can be saved on the disk using the matplotib utility.
Example
>>> >>> import pybullet as p >>> import matplotlib.pyplot as plt >>> from symaware.simulators.pybullet import Environment >>> >>> env = Environment(connection_method=p.DIRECT) >>> img = env.take_screenshot(width=1080, height=720) >>> plt.imsave("my_image", img)
- Parameters:
width (
int
, default:1440
) – Width of the imageheight (
int
, default:1120
) – Height of the imageshadow (
bool
, default:False
) – Whether to capture the shadows of the imagerenderer (
int
, default:65536
) – Underlying renderer used by pybulletReturns – 3-dimensional numpy array containing the screenshot of the simulation
- Return type:
symaware.simulators.pybullet.urdf module
- class symaware.simulators.pybullet.urdf.URDF(value, names=<not given>, *values, module=None, qualname=None, type=None, start=1, boundary=None)[source]
Bases:
Enum
Enum listing all the built-in URDF
- A1 = 'a1'
- AIRPLANE = 'airplane'
- CUBE = 'cube'
- DRONE_CF2P = 'drone_cf2p'
- DRONE_CF2X = 'drone_cf2x'
- DRONE_RACER = 'drone_racer'
- PLANE = 'plane'
- PLANE_100 = 'plane_100'
- RACECAR = 'racecar'