diff --git a/PyFlyt/core/abstractions/base_controller.py b/PyFlyt/core/abstractions/base_controller.py index 95594990..0ef49dec 100644 --- a/PyFlyt/core/abstractions/base_controller.py +++ b/PyFlyt/core/abstractions/base_controller.py @@ -17,7 +17,9 @@ def step(self, state: np.ndarray, setpoint: np.ndarray) -> np.ndarray: """Step the controller. Args: + ---- state (np.ndarray): state setpoint (np.ndarray): setpoint + """ pass diff --git a/PyFlyt/core/abstractions/base_drone.py b/PyFlyt/core/abstractions/base_drone.py index a89fe2d3..48f8b06a 100644 --- a/PyFlyt/core/abstractions/base_drone.py +++ b/PyFlyt/core/abstractions/base_drone.py @@ -18,6 +18,7 @@ class DroneClass(ABC): Each drone inheriting from this class must have several attributes and methods implemented before they can be considered usable. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. start_pos (np.ndarray): an `(3,)` array for the starting X, Y, Z position for the drone. start_orn (np.ndarray): an `(3,)` array for the starting X, Y, Z orientation for the drone. @@ -64,6 +65,7 @@ class DroneClass(ABC): >>> self.use_camera = use_camera >>> if self.use_camera: >>> self.camera = Camera(...) + """ def __init__( @@ -80,6 +82,7 @@ def __init__( """Defines the default configuration for UAVs, to be used in conjunction with the Aviary class. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. start_pos (np.ndarray): an `(3,)` array for the starting X, Y, Z position for the drone. start_orn (np.ndarray): an `(3,)` array for the starting X, Y, Z orientation for the drone. @@ -88,6 +91,7 @@ def __init__( drone_model (str): name of the drone itself, must be the same name as the folder where the URDF and YAML files are located. model_dir (None | str = None): directory where the drone model folder is located, if none is provided, defaults to the directory of the default drones. np_random (None | np.random.RandomState = None): random number generator of the simulation. + """ if physics_hz % control_hz != 0: raise ValueError( @@ -264,9 +268,11 @@ def register_controller( """Default register_controller. Args: + ---- controller_id (int): ID to bind to this controller controller_constructor (type[ControlClass]): A class pointer to the controller implementation, must be subclass of `ControlClass`. base_mode (int): Whether this controller uses outputs of an underlying controller as setpoints. + """ if controller_id <= 0: raise ValueError( diff --git a/PyFlyt/core/abstractions/base_wind_field.py b/PyFlyt/core/abstractions/base_wind_field.py index 59ce7b88..d77bfae5 100644 --- a/PyFlyt/core/abstractions/base_wind_field.py +++ b/PyFlyt/core/abstractions/base_wind_field.py @@ -47,8 +47,10 @@ def __call__(self, time: float, position: np.ndarray) -> np.ndarray: """When given the time float and a position as an (n, 3) array, must return a (n, 3) array representing the local wind velocity. Args: + ---- time (float): float representing the timestep of the simulation in seconds. position (np.ndarray): (n, 3) array representing a series of n positions to sample wind velocites. + """ pass diff --git a/PyFlyt/core/abstractions/boosters.py b/PyFlyt/core/abstractions/boosters.py index 81efb9eb..5f07da70 100644 --- a/PyFlyt/core/abstractions/boosters.py +++ b/PyFlyt/core/abstractions/boosters.py @@ -16,6 +16,7 @@ class Boosters: Additionally, some boosters, typically of the solid fuel variety, cannot be extinguished and reignited, a property we call reignitability. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -31,6 +32,7 @@ class Boosters: thrust_unit (np.ndarray): an `(n, 3)` array representing the unit vector pointing in the direction of force for each booster, relative to the booster link's body frame. reignitable (np.ndarray | list[bool]): a list of booleans representing whether the booster can be extinguished and then reignited. noise_ratio (np.ndarray): a list of floats representing the percent amount of fluctuation present in each booster. + """ def __init__( @@ -54,6 +56,7 @@ def __init__( """Used for simulating an array of boosters. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -69,6 +72,7 @@ def __init__( thrust_unit (np.ndarray): an `(n, 3)` array representing the unit vector pointing in the direction of force for each booster, relative to the booster link's body frame. reignitable (np.ndarray | list[bool]): a list of booleans representing whether the booster can be extinguished and then reignited. noise_ratio (np.ndarray): a list of floats representing the percent amount of fluctuation present in each booster. + """ self.p = p self.physics_period = physics_period @@ -118,7 +122,9 @@ def reset(self, starting_fuel_ratio: float | np.ndarray = 1.0): """Reset the boosters. Args: + ---- starting_fuel_ratio (float | np.ndarray): ratio amount of fuel that the booster is reset to. + """ # deal with everything in percents self.ratio_fuel_remaining = ( @@ -135,8 +141,10 @@ def get_states(self) -> np.ndarray: - (b0, b1, ..., bn) represent the remaining fuel ratio - (c0, c1, ..., cn) represent the current throttle state - Returns: + Returns + ------- np.ndarray: A (3 * num_boosters, ) array + """ return np.concatenate( [ @@ -156,9 +164,11 @@ def physics_update( """Converts booster settings into forces on the booster and inertia change on fuel tank. Args: + ---- ignition (np.ndarray): (num_boosters,) array of booleans for engine on or off. pwm (np.ndarray): (num_boosters,) array of floats between [0, 1] for min or max thrust. rotation (np.ndarray): (num_boosters, 3, 3) rotation matrices to rotate each booster's thrust axis around, this is readily obtained from the `gimbals` component. + """ assert np.all(ignition >= 0.0) and np.all( ignition <= 1.0 @@ -214,8 +224,10 @@ def _compute_thrust_mass_inertia( """_compute_thrust_mass_inertia. Args: + ---- ignition (np.ndarray): (num_boosters,) array of booleans for engine on or off. pwm (np.ndarray): (num_boosters,) array of floats between [0, 1] for min or max thrust. + """ # if not reignitable, logical or ignition_state with ignition # otherwise, just follow ignition diff --git a/PyFlyt/core/abstractions/boring_bodies.py b/PyFlyt/core/abstractions/boring_bodies.py index fb454376..443d45f1 100644 --- a/PyFlyt/core/abstractions/boring_bodies.py +++ b/PyFlyt/core/abstractions/boring_bodies.py @@ -13,6 +13,7 @@ class BoringBodies: The `BoringBodies` component is used to represent a normal body moving through the air. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -20,6 +21,7 @@ class BoringBodies: body_ids (np.ndarray | Sequence[int]): (n,) array of IDs for the links representing the bodies. drag_coefs (np.ndarray): (n, 3) array of drag coefficients for each body in the link-referenced XYZ directions. normal_areas (np.ndarray): (n, 3) array of frontal areas in the link-referenced XYZ directions. + """ def __init__( @@ -35,6 +37,7 @@ def __init__( """Used for simulating a body moving through the air. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -42,6 +45,7 @@ def __init__( body_ids (np.ndarray | Sequence[int]): (n,) array of IDs for the links representing the bodies. drag_coefs (np.ndarray): (n, 3) array of drag coefficients for each body in the link-referenced XYZ directions. normal_areas (np.ndarray): (n, 3) array of frontal areas in the link-referenced XYZ directions. + """ self.p = p self.physics_period = physics_period @@ -76,7 +80,9 @@ def state_update(self, rotation_matrix: np.ndarray): """Updates the local surface velocity of the boring body. Args: + ---- rotation_matrix (np.ndarray): (3, 3) rotation_matrix of the main body + """ # get all the states for all the bodies link_states = self.p.getLinkStates( diff --git a/PyFlyt/core/abstractions/camera.py b/PyFlyt/core/abstractions/camera.py index 3636993a..ce288d0e 100644 --- a/PyFlyt/core/abstractions/camera.py +++ b/PyFlyt/core/abstractions/camera.py @@ -19,6 +19,7 @@ class Camera: On image capture, the camera returns an RGBA image, a depth map, and a segmentation map with pixel values representing the IDs of objects in the environment. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. uav_id (int): ID of the drone. camera_id (int): integer representing the ID of the link that the camera is attached to. @@ -29,6 +30,7 @@ class Camera: camera_position_offset (np.ndarray = np.array([0.0, 0.0, 0.0])): an (3,) array representing an offset of where the camera is from the center of the link in `camera_id`. is_tracking_camera (bool = False): if the camera is a tracking camera, the focus point of the camera is adjusted to focus on the center body of the aircraft instead of at infinity. cinematic (bool = False): it's not a bug, it's a feature. + """ def __init__( @@ -47,6 +49,7 @@ def __init__( """Used for implementing camera modules. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. uav_id (int): ID of the drone. camera_id (int): integer representing the ID of the link that the camera is attached to. @@ -57,6 +60,7 @@ def __init__( camera_position_offset (np.ndarray = np.array([0.0, 0.0, 0.0])): an (3,) array representing an offset of where the camera is from the center of the link in `camera_id`. is_tracking_camera (bool = False): if the camera is a tracking camera, the focus point of the camera is adjusted to focus on the center body of the aircraft instead of at infinity. cinematic (bool = False): it's not a bug, it's a feature. + """ check_numpy() if is_tracking_camera and use_gimbal: @@ -96,8 +100,10 @@ def __init__( def view_mat(self) -> np.ndarray: """Generates the view matrix for the camera depending on the current orientation and implicit parameters. - Returns: + Returns + ------- np.ndarray: view matrix. + """ # get the state of the camera on the robot camera_state = self.p.getLinkState(self.uav_id, self.camera_id) @@ -155,8 +161,10 @@ def physics_update(self): def capture_image(self) -> tuple[np.ndarray, np.ndarray, np.ndarray]: """Captures the 3 relevant images from the camera. - Returns: + Returns + ------- tuple[np.ndarray, np.ndarray, np.ndarray]: rgbaImg, depthImg, segImg + """ _, _, rgbaImg, depthImg, segImg = self.p.getCameraImage( height=self.camera_resolution[0], diff --git a/PyFlyt/core/abstractions/gimbals.py b/PyFlyt/core/abstractions/gimbals.py index b2533882..f0984a7a 100644 --- a/PyFlyt/core/abstractions/gimbals.py +++ b/PyFlyt/core/abstractions/gimbals.py @@ -16,6 +16,7 @@ class Gimbals: Each gimbal can rotate about two arbitrary axis that may not be orthogonal to each other. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -23,6 +24,7 @@ class Gimbals: gimbal_unit_2 (np.ndarray): second unit vector that the gimbal rotates around. gimbal_tau (np.ndarray): gimbal actuation time constant. gimbal_range_degrees (np.ndarray): gimbal actuation range in degrees. + """ def __init__( @@ -38,6 +40,7 @@ def __init__( """Used for simulating an array of gimbals. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -45,6 +48,7 @@ def __init__( gimbal_unit_2 (np.ndarray): second unit vector that the gimbal rotates around. gimbal_tau (np.ndarray): gimbal actuation time constant. gimbal_range_degrees (np.ndarray): gimbal actuation range in degrees. + """ self.p = p self.physics_period = physics_period @@ -119,8 +123,10 @@ def reset(self): def get_states(self) -> np.ndarray: """Gets the current state of the components. - Returns: + Returns + ------- np.ndarray: a (2 * num_gimbals, ) array where every pair of values represents the current state of the gimbal + """ return np.concatenate( [ @@ -142,10 +148,13 @@ def compute_rotation(self, gimbal_command: np.ndarray) -> np.ndarray: """Returns a rotation vector after the gimbal rotation. Args: + ---- gimbal_command (np.ndarray): (num_gimbals, 2) array of floats between [-1, 1]. Returns: + ------- rotation_vector (np.ndarray): (num_gimbals, 3, 3) rotation matrices for all gimbals. + """ assert np.all(gimbal_command >= -1.0) and np.all( gimbal_command <= 1.0 @@ -182,6 +191,7 @@ def _jitted_compute_rotation( """Compute the rotation matrix given the gimbal action values. Args: + ---- gimbal_angles (np.ndarray): gimbal_angles w1 (np.ndarray): w1 from self w2 (np.ndarray): w2 from self @@ -189,7 +199,9 @@ def _jitted_compute_rotation( w2_squared (np.ndarray): w2_squared from self Returns: + ------- tuple[np.ndarray, np.ndarray]: + """ # precompute some things sin_angles = np.sin(gimbal_angles) diff --git a/PyFlyt/core/abstractions/lifting_surfaces.py b/PyFlyt/core/abstractions/lifting_surfaces.py index 41ecd3be..148de490 100644 --- a/PyFlyt/core/abstractions/lifting_surfaces.py +++ b/PyFlyt/core/abstractions/lifting_surfaces.py @@ -16,14 +16,18 @@ class LiftingSurfaces: Simply pass it a list of `LiftingSurface` objects. Args: + ---- lifting_surfaces (list[LiftingSurface]): a list of `LiftingSurface` objects. + """ def __init__(self, lifting_surfaces: list[LiftingSurface]): """__init__. Args: + ---- lifting_surfaces (list[LiftingSurface]): a list of `LiftingSurface` objects. + """ # assert all is lifting surfaces assert all( @@ -43,8 +47,10 @@ def reset(self): def get_states(self) -> np.ndarray: """Gets the current state of the components. - Returns: + Returns + ------- np.ndarray: a (num_surfaces, ) array representing the actuation state for each surface + """ return np.array([surface.actuation for surface in self.surfaces]) @@ -52,7 +58,9 @@ def physics_update(self, cmd: np.ndarray): """Converts actuation commands into forces on the lifting surfaces. Args: + ---- cmd (np.ndarray): the full command array, command mapping is handled through `command_id` and `command_sign` on each surface, normalized in [-1, 1]. + """ assert len(cmd.shape) == 1, f"`{cmd=}` must be 1D array." assert ( @@ -69,7 +77,9 @@ def state_update(self, rotation_matrix: np.ndarray): """Updates all local surface velocities of the lifting surface, place under `update_state`. Args: + ---- rotation_matrix (np.ndarray): (3, 3) OR (num_surfaces, 3, 3) array rotation_matrix + """ # get all the states for all the surfaces link_states = self.p.getLinkStates( @@ -110,6 +120,7 @@ class LiftingSurface: The `Lifting Surface` component is used to simulate a single lifting surface based on "Real-time modeling of agile fixed-wing uav aerodynamics, Khan et. al.". Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -128,6 +139,7 @@ class LiftingSurface: Cd_0 (float): drag coefficient at zero angle-of-attack. deflection_limit (float): maximum deflection limit of the actuated flap in degrees. tau (float): actuation ramp time constant. + """ def __init__( @@ -154,6 +166,7 @@ def __init__( """Used for simulating a single lifting surface. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -172,6 +185,7 @@ def __init__( Cd_0 (float): drag coefficient at zero angle-of-attack. deflection_limit (float): maximum deflection limit of the actuated flap in degrees. tau (float): actuation ramp time constant. + """ self.p = p self.physics_period = physics_period @@ -240,8 +254,10 @@ def reset(self): def get_states(self) -> float: """Gets the current state of the components. - Returns: + Returns + ------- float: the level of deflection of the surface. + """ return self.actuation @@ -249,7 +265,9 @@ def state_update(self, surface_velocity: np.ndarray): """Updates the local surface velocity of the lifting surface. Args: + ---- surface_velocity (np.ndarray): surface_velocity. + """ self.local_surface_velocity = surface_velocity @@ -257,10 +275,13 @@ def physics_update(self, cmd: float): """Converts a commanded actuation state into forces on the lifting surface. Args: + ---- cmd (float): normalized actuation in [-1, 1]. Returns: + ------- tuple[np.ndarray, np.ndarray]: vec3 force, vec3 torque + """ # model the deflection using first order ODE, y' = T/tau * (setpoint - y) self.actuation += (self.physics_period / self.cmd_tau) * (cmd - self.actuation) @@ -320,12 +341,15 @@ def _compute_aoa_freestream( """Computes the angle of attack (alpha) as well as the freestream speed. Args: + ---- local_surface_velocity (np.ndarray): local_surface_velocity from self lift_unit (np.ndarray): lift_unit from self drag_unit (np.ndarray): drag_unit from self Returns: + ------- tuple[float, float]: + """ freestream_speed = np.linalg.norm(local_surface_velocity).item() lifting_airspeed = np.dot(local_surface_velocity, lift_unit) @@ -353,6 +377,7 @@ def _jitted_compute_aero_data( """Computes the relevant aerodynamic data depending on the current state of the lifting surface. Args: + ---- alpha (float): alpha aspect (float): aspect from self flap_to_chord (float): flap_to_chord from self @@ -367,7 +392,9 @@ def _jitted_compute_aero_data( Cd_0 (float): Cd_0 from self Returns: + ------- tuple[float, float, float]: + """ # deflection must be in degrees because engineering uses degrees deflection_radians = np.deg2rad(actuation * deflection_limit) @@ -452,6 +479,7 @@ def _jitted_compute_force_torque( """Compute the force and torque vectors on the surface. Args: + ---- alpha (float): alpha freestream_speed (float): freestream_speed Cl (float): Cl @@ -465,7 +493,9 @@ def _jitted_compute_force_torque( torque_unit (np.ndarray): torque_unit from self Returns: + ------- tuple[np.ndarray, np.ndarray]: + """ # compute dynamic pressure Q = half_rho * np.square(freestream_speed) diff --git a/PyFlyt/core/abstractions/motors.py b/PyFlyt/core/abstractions/motors.py index 0ac76ebf..82c7ff62 100644 --- a/PyFlyt/core/abstractions/motors.py +++ b/PyFlyt/core/abstractions/motors.py @@ -17,6 +17,7 @@ class Motors: The maximum RPM can be easily computed using `max_rpm = max_thrust / thrust_coef`. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -28,6 +29,7 @@ class Motors: torque_coef (np.ndarray): an (n,) array of floats representing all motor torque coefficients, uses right hand rotation rule around the `thrust_unit` axis. thrust_unit (np.ndarray): an (n, 3) array of floats representing n unit vectors along with the thrust of each motor acts. noise_ratio (np.ndarray): an (n,) array of floats representing the ratio amount of noise fluctuation present in each motor. + """ def __init__( @@ -47,6 +49,7 @@ def __init__( """Used for simulating an array of motors. Args: + ---- p (bullet_client.BulletClient): PyBullet physics client ID. physics_period (float): physics period of the simulation. np_random (np.random.RandomState): random number generator of the simulation. @@ -58,6 +61,7 @@ def __init__( torque_coef (np.ndarray): an (n,) array of floats representing all motor torque coefficients, uses right hand rotation rule around the `thrust_unit` axis. thrust_unit (np.ndarray): an (n, 3) array of floats representing n unit vectors along with the thrust of each motor acts. noise_ratio (np.ndarray): an (n,) array of floats representing the ratio amount of noise fluctuation present in each motor. + """ self.p = p self.physics_period = physics_period @@ -94,8 +98,10 @@ def reset(self) -> None: def get_states(self) -> np.ndarray: """Gets the current state of the components. - Returns: + Returns + ------- np.ndarray: an (num_motors, ) array for the current throttle level of each motor + """ return self.throttle.flatten() @@ -109,8 +115,10 @@ def physics_update( """Converts motor PWM values to forces, this motor allows negative thrust. Args: + ---- pwm (np.ndarray): [num_motors, ] array defining the pwm values of each motor from -1 to 1. rotation (np.ndarray): (num_motors, 3, 3) rotation matrices to rotate each booster's thrust axis around, this is readily obtained from the `gimbals` component. + """ assert np.all(pwm >= -1.0) and np.all( pwm <= 1.0 @@ -162,6 +170,7 @@ def _jitted_compute_thrust_torque( """Computes the thrusts and torques for the array of motors. Args: + ---- rotation (None | np.ndarray): rotation throttle (np.ndarray): throttle from self max_rpm (np.ndarray): max_rpm from self @@ -170,7 +179,9 @@ def _jitted_compute_thrust_torque( torque_coef (np.ndarray): torque_coef from self Returns: + ------- tuple[np.ndarray, np.ndarray]: + """ # throttle to rpm rpm = throttle * max_rpm diff --git a/PyFlyt/core/abstractions/pid.py b/PyFlyt/core/abstractions/pid.py index ab372c52..db45369b 100644 --- a/PyFlyt/core/abstractions/pid.py +++ b/PyFlyt/core/abstractions/pid.py @@ -31,6 +31,7 @@ def __init__( Because of this, all arguments passed into this function, except `period`, must be a 1D np array and have the same shape. Example: + ------- Invalid implementation: >>> controller = PID(0.5, 0.4, 0.3, 1.0, 0.01) >>> controller.step(5.0, 2.0) @@ -44,11 +45,13 @@ def __init__( >>> controller.step(np.array([5.0]), np.array([2.0])) Args: + ---- kp (np.ndarray): kp ki (np.ndarray): ki kd (np.ndarray): kd limits (np.ndarray): limits period (float): period + """ self.kp = kp self.ki = ki @@ -69,11 +72,14 @@ def step(self, state: np.ndarray, setpoint: np.ndarray) -> np.ndarray: """Steps the PID controller. Args: + ---- state (np.ndarray): the state of the system, must be same shape as controller parameters. setpoint (np.ndarray): the setpoint of the system, must be same shape as controller parameters. Returns: + ------- np.ndarray: + """ error = setpoint - state diff --git a/PyFlyt/core/aviary.py b/PyFlyt/core/aviary.py index 90c145a1..91b29bcb 100644 --- a/PyFlyt/core/aviary.py +++ b/PyFlyt/core/aviary.py @@ -18,11 +18,31 @@ class AviaryInitException(Exception): + """AviaryInitException.""" + def __init__(self, message: str) -> None: + """__init__. + + Args: + ---- + message (str): message + + Returns: + ------- + None: + + """ self.message = message super().__init__(self.message) def __str__(self) -> str: + """__str__. + + Returns + ------- + str: + + """ return f"Aviary Error: {self.message}" @@ -33,6 +53,7 @@ class Aviary(bullet_client.BulletClient): It provides a common endpoint from where users may control drones or define tasks. Args: + ---- start_pos (np.ndarray): an `(n, 3)` array for the starting X, Y, Z positions for each drone. start_orn (np.ndarray): an `(n, 3)` array for the starting orientations for each drone, in terms of Euler angles. drone_type (str | Sequence[str]): a _lowercase_ string representing what type of drone to spawn. @@ -44,6 +65,7 @@ class Aviary(bullet_client.BulletClient): physics_hz (int): physics looprate (not recommended to be changed). world_scale (float): how big to spawn the floor. seed (None | int): optional int for seeding the simulation RNG. + """ def __init__( @@ -66,6 +88,7 @@ def __init__( The Aviary also handles dealing with physics and control looprates, as well as automatic construction of several default UAVs and their corresponding cameras. Args: + ---- start_pos (np.ndarray): an `(n, 3)` array for the starting X, Y, Z positions for each drone. start_orn (np.ndarray): an `(n, 3)` array for the starting orientations for each drone, in terms of Euler angles. drone_type (str | Sequence[str]): a _lowercase_ string representing what type of drone to spawn. @@ -77,6 +100,7 @@ def __init__( physics_hz (int): physics looprate (not recommended to be changed). world_scale (float): how big to spawn the floor. seed (None | int): optional int for seeding the simulation RNG. + """ super().__init__(p.GUI if render else p.DIRECT) print("\033[A \033[A") @@ -183,7 +207,9 @@ def reset(self, seed: None | int = None) -> None: """Resets the simulation. Args: + ---- seed (None | int): seed + """ self.resetSimulation() self.setGravity(0, 0, -9.81) @@ -292,7 +318,9 @@ def register_wind_field_function(self, wind_field: Callable) -> None: """For less complicated wind field models (time invariant models), this allows the registration of a normal function as a wind field model. Args: + ---- wind_field (Callable): given the time float and a position as an (n, 3) array, must return a (n, 3) array representing the local wind velocity. + """ assert callable(wind_field), "`wind_field` function must be callable." WindFieldClass._check_wind_field_validity(wind_field) @@ -308,10 +336,13 @@ def state(self, index: DroneIndex) -> np.ndarray: - `state[3, :]` represents ground frame linear position Args: + ---- index (DRONE_INDEX): index Returns: + ------- np.ndarray: state + """ return self.drones[index].state @@ -325,10 +356,13 @@ def aux_state(self, index: DroneIndex) -> np.ndarray: - etc... Args: + ---- index (DRONE_INDEX): index Returns: + ------- np.ndarray: auxiliary state + """ return self.drones[index].aux_state @@ -346,8 +380,10 @@ def all_states(self) -> list[np.ndarray]: This function is not very optimized, if you want the state of a single drone, do `state(i)`. - Returns: + Returns + ------- np.ndarray: list of states + """ states = [] for drone in self.drones: @@ -363,8 +399,10 @@ def all_aux_states(self) -> list[np.ndarray]: This function is not very optimized, if you want the aux state of a single drone, do `aux_state(i)`. - Returns: + Returns + ------- np.ndarray: list of auxiliary states + """ aux_states = [] for drone in self.drones: @@ -386,7 +424,9 @@ def set_armed(self, settings: int | bool | list[int] | list[bool]) -> None: """Sets the arming state of each drone in the environment. Unarmed drones won't receive updates and will ragdoll. Args: + ---- settings (int | bool | list[int | bool]): arm setting + """ if isinstance(settings, list): assert len(settings) == len( @@ -405,7 +445,9 @@ def set_mode(self, flight_modes: int | list[int]) -> None: When this is a list of integers, sets a different flight mode for each drone depending on the list. Args: + ---- flight_modes (int | list[int]): flight mode + """ if isinstance(flight_modes, list): assert len(flight_modes) == len( @@ -421,8 +463,10 @@ def set_setpoint(self, index: DroneIndex, setpoint: np.ndarray) -> None: """Sets the setpoint of one drone in the environment. Args: + ---- index (DRONE_INDEX): index setpoint (np.ndarray): setpoint + """ self.drones[index].setpoint = setpoint @@ -430,7 +474,9 @@ def set_all_setpoints(self, setpoints: np.ndarray) -> None: """Sets the setpoints of each drone in the environment. Args: + ---- setpoints (np.ndarray): list of setpoints + """ for i, drone in enumerate(self.drones): drone.setpoint = setpoints[i] diff --git a/PyFlyt/core/drones/fixedwing.py b/PyFlyt/core/drones/fixedwing.py index b7cb0691..e18040af 100644 --- a/PyFlyt/core/drones/fixedwing.py +++ b/PyFlyt/core/drones/fixedwing.py @@ -36,6 +36,7 @@ def __init__( """Creates a Fixedwing UAV and handles all relevant control and physics. Args: + ---- p (bullet_client.BulletClient): p start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn @@ -52,6 +53,7 @@ def __init__( camera_position_offset (np.ndarray): offset position of the camera camera_fps (None | int): camera_fps starting_velocity (np.ndarray): vector representing the velocity at spawn + """ super().__init__( p=p, @@ -209,7 +211,9 @@ def set_mode(self, mode) -> None: - 0: Pitch, Roll, Yaw, Thrust Args: + ---- mode (int): flight mode + """ if (mode < -1 or mode > 0) and mode not in self.registered_controllers.keys(): raise ValueError( @@ -227,7 +231,9 @@ def update_control(self, physics_step: int) -> None: """Runs through controllers. Args: + ---- physics_step (int): the current physics step + """ # skip control if we don't have enough physics steps if physics_step % self.physics_control_ratio != 0: @@ -290,7 +296,9 @@ def update_last(self, physics_step: int) -> None: """Updates things only at the end of `Aviary.step()`. Args: + ---- physics_step (int): the current physics step + """ if self.use_camera and (physics_step % self.physics_camera_ratio == 0): self.rgbaImg, self.depthImg, self.segImg = self.camera.capture_image() diff --git a/PyFlyt/core/drones/quadx.py b/PyFlyt/core/drones/quadx.py index b1c71643..fac7ad1b 100644 --- a/PyFlyt/core/drones/quadx.py +++ b/PyFlyt/core/drones/quadx.py @@ -38,6 +38,7 @@ def __init__( """Creates a drone in the QuadX configuration and handles all relevant control and physics. Args: + ---- p (bullet_client.BulletClient): p start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn @@ -52,6 +53,7 @@ def __init__( camera_FOV_degrees (int): camera_FOV_degrees camera_resolution (tuple[int, int]): camera_resolution camera_fps (None | int): camera_fps + """ super().__init__( p=p, @@ -248,7 +250,9 @@ def set_mode(self, mode: int) -> None: - T = thrust Args: + ---- mode (int): flight mode + """ if (mode < -1 or mode > 7) and mode not in self.registered_controllers.keys(): raise ValueError( @@ -375,9 +379,11 @@ def register_controller( """Registers a new controller for the UAV. Args: + ---- controller_id (int): controller_id controller_constructor (type[ControlClass]): controller_constructor base_mode (int): base_mode + """ if controller_id <= 7: raise ValueError( @@ -395,7 +401,9 @@ def update_control(self, physics_step: int) -> None: """Runs through controllers. Args: + ---- physics_step (int): the current physics step + """ # skip control if we don't have enough physics steps if physics_step % self.physics_control_ratio != 0: @@ -530,7 +538,9 @@ def update_last(self, physics_step: int) -> None: """Updates things only at the end of `Aviary.step()`. Args: + ---- physics_step (int): the current physics step + """ if self.use_camera and (physics_step % self.physics_camera_ratio == 0): self.rgbaImg, self.depthImg, self.segImg = self.camera.capture_image() diff --git a/PyFlyt/core/drones/rocket.py b/PyFlyt/core/drones/rocket.py index 6ecacace..8ba46398 100644 --- a/PyFlyt/core/drones/rocket.py +++ b/PyFlyt/core/drones/rocket.py @@ -48,6 +48,7 @@ def __init__( """Creates a drone in the QuadX configuration and handles all relevant control and physics. Args: + ---- p (bullet_client.BulletClient): p start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn @@ -64,6 +65,7 @@ def __init__( camera_position_offset (np.ndarray): offset position of the camera camera_fps (None | int): camera_fps starting_fuel_ratio (float): amount of fuel that the rocket has to beginwith + """ super().__init__( p=p, @@ -240,7 +242,9 @@ def set_mode(self, mode) -> None: - 0: finlet x deflection, finlet y deflection, finlet yaw, ignition, throttle, booster gimbal axis 1, booster gimbal axis 2 Args: + ---- mode (int): flight mode + """ super().set_mode(mode) @@ -248,7 +252,9 @@ def update_control(self, physics_step: int) -> None: """Runs through controllers. Args: + ---- physics_step (int): the current physics step + """ # skip control if we don't have enough physics steps if physics_step % self.physics_control_ratio != 0: @@ -331,7 +337,9 @@ def update_last(self, physics_step: int) -> None: """Updates things only at the end of `Aviary.step()`. Args: + ---- physics_step (int): the current physics step + """ if self.use_camera and (physics_step % self.physics_camera_ratio == 0): self.rgbaImg, self.depthImg, self.segImg = self.camera.capture_image() diff --git a/PyFlyt/core/utils/load_objs.py b/PyFlyt/core/utils/load_objs.py index 649be572..c7412112 100644 --- a/PyFlyt/core/utils/load_objs.py +++ b/PyFlyt/core/utils/load_objs.py @@ -18,6 +18,7 @@ def loadOBJ( """Loads an object into the environment. Args: + ---- env (Aviary): env fileName (str): fileName visualId (int): visualId @@ -26,6 +27,7 @@ def loadOBJ( meshScale (list[float] | np.ndarray): meshScale basePosition (list[float] | np.ndarray): basePosition baseOrientation (list[float] | np.ndarray): baseOrientation + """ if len(baseOrientation) == 3: baseOrientation = env.getQuaternionFromEuler(baseOrientation) @@ -54,9 +56,11 @@ def obj_visual( """Loads an object visual model. Args: + ---- env (Aviary): env fileName (str): fileName meshScale (list[float] | np.ndarray): meshScale + """ return env.createVisualShape( shapeType=env.GEOM_MESH, @@ -76,10 +80,12 @@ def obj_collision( """Loads an object collision model. Args: + ---- env (Aviary): env fileName (str): fileName meshScale (list[float] | np.ndarray): meshScale concave (bool): Whether the object should use concave trimesh, do not use this for dynamic/moving objects + """ return ( env.createCollisionShape( diff --git a/PyFlyt/gym_envs/fixedwing_envs/fixedwing_base_env.py b/PyFlyt/gym_envs/fixedwing_envs/fixedwing_base_env.py index 7167a9c7..2bb9a803 100644 --- a/PyFlyt/gym_envs/fixedwing_envs/fixedwing_base_env.py +++ b/PyFlyt/gym_envs/fixedwing_envs/fixedwing_base_env.py @@ -32,6 +32,7 @@ def __init__( """__init__. Args: + ---- start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn flight_mode (int): flight_mode @@ -41,6 +42,7 @@ def __init__( agent_hz (int): agent_hz render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution + """ if 120 % agent_hz != 0: lowest = int(120 / (int(120 / agent_hz) + 1)) @@ -123,8 +125,10 @@ def reset( """reset. Args: + ---- seed: seed to pass to the base environment. options: None + """ raise NotImplementedError @@ -258,10 +262,13 @@ def step(self, action: np.ndarray) -> tuple[Any, float, bool, bool, dict]: """Steps the environment. Args: + ---- action (np.ndarray): action Returns: + ------- state, reward, termination, truncation, info + """ # unsqueeze the action to be usable in aviary self.action = action.copy() diff --git a/PyFlyt/gym_envs/fixedwing_envs/fixedwing_waypoints_env.py b/PyFlyt/gym_envs/fixedwing_envs/fixedwing_waypoints_env.py index ed78d7f1..b834a598 100644 --- a/PyFlyt/gym_envs/fixedwing_envs/fixedwing_waypoints_env.py +++ b/PyFlyt/gym_envs/fixedwing_envs/fixedwing_waypoints_env.py @@ -17,6 +17,7 @@ class FixedwingWaypointsEnv(FixedwingBaseEnv): The target is a set of `[x, y, z]` targets in space Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. num_targets (int): number of waypoints in the environment. goal_reach_distance (float): distance to the waypoints for it to be considered reached. @@ -27,6 +28,7 @@ class FixedwingWaypointsEnv(FixedwingBaseEnv): agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution + """ def __init__( @@ -45,6 +47,7 @@ def __init__( """__init__. Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. num_targets (int): number of waypoints in the environment. goal_reach_distance (float): distance to the waypoints for it to be considered reached. @@ -55,6 +58,7 @@ def __init__( agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution + """ super().__init__( start_pos=np.array([[0.0, 0.0, 10.0]]), @@ -103,8 +107,10 @@ def reset( """reset. Args: + ---- seed: seed to pass to the base environment. options: None + """ super().begin_reset(seed, options) self.waypoints.reset(self.env, self.np_random) diff --git a/PyFlyt/gym_envs/quadx_envs/quadx_base_env.py b/PyFlyt/gym_envs/quadx_envs/quadx_base_env.py index 70a2d150..29b477e9 100644 --- a/PyFlyt/gym_envs/quadx_envs/quadx_base_env.py +++ b/PyFlyt/gym_envs/quadx_envs/quadx_base_env.py @@ -32,6 +32,7 @@ def __init__( """__init__. Args: + ---- start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn flight_mode (int): flight_mode @@ -41,6 +42,7 @@ def __init__( agent_hz (int): agent_hz render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution + """ if 120 % agent_hz != 0: lowest = int(120 / (int(120 / agent_hz) + 1)) @@ -129,11 +131,14 @@ def reset( """reset. Args: + ---- seed (None | int): seed options (dict[str, Any]): options Returns: + ------- tuple[Any, dict[str, Any]]: + """ raise NotImplementedError @@ -261,10 +266,13 @@ def step(self, action: np.ndarray) -> tuple[Any, float, bool, bool, dict[str, An """Steps the environment. Args: + ---- action (np.ndarray): action Returns: + ------- state, reward, termination, truncation, info + """ # unsqueeze the action to be usable in aviary self.action = action.copy() diff --git a/PyFlyt/gym_envs/quadx_envs/quadx_gates_env.py b/PyFlyt/gym_envs/quadx_envs/quadx_gates_env.py index bc42f2ec..f63369e8 100644 --- a/PyFlyt/gym_envs/quadx_envs/quadx_gates_env.py +++ b/PyFlyt/gym_envs/quadx_envs/quadx_gates_env.py @@ -23,6 +23,7 @@ class QuadXGatesEnv(QuadXBaseEnv): Reward is -(distance from waypoint + angle error) for each timestep, and -100.0 for hitting the ground. Args: + ---- flight_mode (int): the flight mode of the UAV num_targets (int): num_targets goal_reach_distance (float): goal_reach_distance @@ -36,6 +37,7 @@ class QuadXGatesEnv(QuadXBaseEnv): agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution + """ def __init__( @@ -57,6 +59,7 @@ def __init__( """__init__. Args: + ---- flight_mode (int): the flight mode of the UAV num_targets (int): num_targets goal_reach_distance (float): goal_reach_distance @@ -70,6 +73,7 @@ def __init__( agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution + """ super().__init__( flight_mode=flight_mode, @@ -118,8 +122,10 @@ def reset( """Resets the environment. Args: + ---- seed: seed to pass to the base environment. options: None + """ aviary_options = dict() aviary_options["use_camera"] = True @@ -200,7 +206,9 @@ def colour_dead_gate(self, gate: int) -> None: """Colours the gates that are done. Args: + ---- gate (int): body ID of the gate + """ # colour the dead gates red for i in range(p.getNumJoints(gate)): diff --git a/PyFlyt/gym_envs/quadx_envs/quadx_hover_env.py b/PyFlyt/gym_envs/quadx_envs/quadx_hover_env.py index 2fd51d7a..744c4bde 100644 --- a/PyFlyt/gym_envs/quadx_envs/quadx_hover_env.py +++ b/PyFlyt/gym_envs/quadx_envs/quadx_hover_env.py @@ -15,6 +15,7 @@ class QuadXHoverEnv(QuadXBaseEnv): The target is to not crash for the longest time possible. Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. flight_mode (int): the flight mode of the UAV flight_dome_size (float): size of the allowable flying area. @@ -23,6 +24,7 @@ class QuadXHoverEnv(QuadXBaseEnv): agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution. + """ def __init__( @@ -39,6 +41,7 @@ def __init__( """__init__. Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. flight_mode (int): the flight mode of the UAV flight_dome_size (float): size of the allowable flying area. @@ -47,6 +50,7 @@ def __init__( agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution. + """ super().__init__( flight_mode=flight_mode, @@ -70,8 +74,10 @@ def reset( """reset. Args: + ---- seed: seed to pass to the base environment. options: None + """ super().begin_reset(seed, options) super().end_reset(seed, options) diff --git a/PyFlyt/gym_envs/quadx_envs/quadx_waypoints_env.py b/PyFlyt/gym_envs/quadx_envs/quadx_waypoints_env.py index e5b5be1a..b5aaa720 100644 --- a/PyFlyt/gym_envs/quadx_envs/quadx_waypoints_env.py +++ b/PyFlyt/gym_envs/quadx_envs/quadx_waypoints_env.py @@ -17,6 +17,7 @@ class QuadXWaypointsEnv(QuadXBaseEnv): The target is a set of `[x, y, z, (optional) yaw]` waypoints in space. Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. num_targets (int): number of waypoints in the environment. use_yaw_targets (bool): whether to match yaw targets before a waypoint is considered reached. @@ -29,6 +30,7 @@ class QuadXWaypointsEnv(QuadXBaseEnv): agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution. + """ def __init__( @@ -49,6 +51,7 @@ def __init__( """__init__. Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. num_targets (int): number of waypoints in the environment. use_yaw_targets (bool): whether to match yaw targets before a waypoint is considered reached. @@ -61,6 +64,7 @@ def __init__( agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution. + """ super().__init__( start_pos=np.array([[0.0, 0.0, 1.0]]), @@ -109,8 +113,10 @@ def reset( """Resets the environment. Args: + ---- seed: seed to pass to the base environment. options: None + """ super().begin_reset(seed, options) self.waypoints.reset(self.env, self.np_random) diff --git a/PyFlyt/gym_envs/rocket_envs/rocket_base_env.py b/PyFlyt/gym_envs/rocket_envs/rocket_base_env.py index 37895961..87723a6b 100644 --- a/PyFlyt/gym_envs/rocket_envs/rocket_base_env.py +++ b/PyFlyt/gym_envs/rocket_envs/rocket_base_env.py @@ -32,6 +32,7 @@ def __init__( """__init__. Args: + ---- start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn drone_type (str): drone_type @@ -43,6 +44,7 @@ def __init__( agent_hz (int): agent_hz render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution + """ if 120 % agent_hz != 0: lowest = int(120 / (int(120 / agent_hz) + 1)) @@ -134,8 +136,10 @@ def reset( """Resets the environment. Args: + ---- seed: int options: None + """ raise NotImplementedError @@ -278,7 +282,9 @@ def compute_base_term_trunc_reward( """compute_base_term_trunc_reward. Args: + ---- collision_ignore_mask (np.ndarray | list[int]): list of ids to ignore collisions between + """ # exceed step count if self.step_count > self.max_steps: @@ -309,10 +315,13 @@ def step(self, action: np.ndarray): """Steps the environment. Args: + ---- action (np.ndarray): action Returns: + ------- state, reward, termination, truncation, info + """ # unsqueeze the action to be usable in aviary self.action = action.copy() diff --git a/PyFlyt/gym_envs/rocket_envs/rocket_landing_env.py b/PyFlyt/gym_envs/rocket_envs/rocket_landing_env.py index 4ac697d8..4afc317a 100644 --- a/PyFlyt/gym_envs/rocket_envs/rocket_landing_env.py +++ b/PyFlyt/gym_envs/rocket_envs/rocket_landing_env.py @@ -18,6 +18,7 @@ class RocketLandingEnv(RocketBaseEnv): The goal is to land the rocket on the landing pad. Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. ceiling (float): the absolute ceiling of the flying area. max_displacement (float): the maximum horizontal distance the rocket can go. @@ -26,6 +27,7 @@ class RocketLandingEnv(RocketBaseEnv): agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution. + """ def __init__( @@ -42,6 +44,7 @@ def __init__( """__init__. Args: + ---- sparse_reward (bool): whether to use sparse rewards or not. ceiling (float): the absolute ceiling of the flying area. max_displacement (float): the maximum horizontal distance the rocket can go. @@ -50,6 +53,7 @@ def __init__( agent_hz (int): looprate of the agent to environment interaction. render_mode (None | Literal["human", "rgb_array"]): render_mode render_resolution (tuple[int, int]): render_resolution. + """ super().__init__( start_pos=np.array([[0.0, 0.0, ceiling * 0.9]]), @@ -89,8 +93,10 @@ def reset( """Resets the environment. Args: + ---- seed: int options: None + """ if options is None: options = dict(randomize_drop=True, accelerate_drop=True) diff --git a/PyFlyt/gym_envs/utils/flatten_waypoint_env.py b/PyFlyt/gym_envs/utils/flatten_waypoint_env.py index aab515e6..665b3b4a 100644 --- a/PyFlyt/gym_envs/utils/flatten_waypoint_env.py +++ b/PyFlyt/gym_envs/utils/flatten_waypoint_env.py @@ -15,8 +15,10 @@ def __init__(self, env: Env, context_length=2): """__init__. Args: + ---- env (Env): a PyFlyt Waypoints environment. context_length: how many waypoints should be included in the flattened observation space. + """ super().__init__(env=env) if not hasattr(env, "waypoints") and not isinstance( @@ -41,7 +43,9 @@ def observation(self, observation) -> np.ndarray: """Flattens an observation from the super env. Args: + ---- observation: a dictionary observation with an "attitude" and "target_deltas" keys. + """ num_targets = min(self.context_length, observation["target_deltas"].shape[0]) # pyright: ignore[reportGeneralTypeIssues] diff --git a/PyFlyt/gym_envs/utils/waypoint_handler.py b/PyFlyt/gym_envs/utils/waypoint_handler.py index b8d1a27e..199ebdb0 100644 --- a/PyFlyt/gym_envs/utils/waypoint_handler.py +++ b/PyFlyt/gym_envs/utils/waypoint_handler.py @@ -24,6 +24,7 @@ def __init__( """__init__. Args: + ---- enable_render (bool): enable_render num_targets (int): num_targets use_yaw_targets (bool): use_yaw_targets @@ -31,6 +32,7 @@ def __init__( goal_reach_angle (float): goal_reach_angle flight_dome_size (float): flight_dome_size np_random (np.random.Generator): np_random + """ # constants self.enable_render = enable_render @@ -110,9 +112,11 @@ def distance_to_target( """distance_to_target. Args: + ---- ang_pos (np.ndarray): ang_pos lin_pos (np.ndarray): lin_pos quarternion (np.ndarray): quarternion + """ # rotation matrix rotation = np.array(self.p.getMatrixFromQuaternion(quarternion)).reshape(3, 3) diff --git a/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_base_env.py b/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_base_env.py index 09d818f4..f6ae36dc 100644 --- a/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_base_env.py +++ b/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_base_env.py @@ -29,6 +29,7 @@ def __init__( """__init__. Args: + ---- start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn assisted_flight (bool): assisted_flight @@ -37,6 +38,7 @@ def __init__( angle_representation (str): angle_representation agent_hz (int): agent_hz render_mode (None | str): render_mode + """ if 120 % agent_hz != 0: lowest = int(120 / (int(120 / agent_hz) + 1)) @@ -132,16 +134,20 @@ def __init__( def observation_space(self, agent: Any = None) -> Space: """observation_space. - Returns: + Returns + ------- Space: + """ raise NotImplementedError def action_space(self, agent: Any = None) -> spaces.Box: """action_space. - Returns: + Returns + ------- spaces.Box: + """ return self._action_space @@ -156,11 +162,14 @@ def reset( """reset. Args: + ---- seed (None | int): seed options (dict | None): options Returns: + ------- tuple[dict[str, Any], dict[str, Any]]: + """ raise NotImplementedError @@ -252,10 +261,13 @@ def compute_observation_by_id(self, agent_id: int) -> Any: """compute_observation_by_id. Args: + ---- agent_id (int): agent_id Returns: + ------- Any: + """ raise NotImplementedError @@ -289,10 +301,13 @@ def compute_term_trunc_reward_info_by_id( """compute_term_trunc_reward_info_by_id. Args: + ---- agent_id (int): agent_id Returns: + ------- Tuple[bool, bool, float, dict[str, Any]]: + """ raise NotImplementedError @@ -308,10 +323,13 @@ def step( """step. Args: + ---- actions (dict[str, np.ndarray]): actions Returns: + ------- tuple[dict[str, Any], dict[str, float], dict[str, bool], dict[str, bool], dict[str, dict[str, Any]]]: + """ # copy over the past actions self.past_actions = deepcopy(self.current_actions) diff --git a/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_dogfight_env.py b/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_dogfight_env.py index cff660ed..1425e216 100644 --- a/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_dogfight_env.py +++ b/PyFlyt/pz_envs/fixedwing_envs/ma_fixedwing_dogfight_env.py @@ -13,6 +13,7 @@ class MAFixedwingDogfightEnv(MAFixedwingBaseEnv): """Base Dogfighting Environment for the Acrowing model using the PettingZoo API. Args: + ---- spawn_height (float): how high to spawn the agents at the beginning of the simulation. damage_per_hit (float): how much damage per hit per physics step, each agent starts with a health of 1.0. lethal_distance (float): how close before weapons become effective. @@ -23,6 +24,7 @@ class MAFixedwingDogfightEnv(MAFixedwingBaseEnv): max_duration_seconds (float): maximum simulation time of the environment. agent_hz (int): looprate of the agent to environment interaction. render_mode (None | str): can be "human" or None + """ metadata = { @@ -46,6 +48,7 @@ def __init__( """__init__. Args: + ---- spawn_height (float): how high to spawn the agents at the beginning of the simulation. damage_per_hit (float): how much damage per hit per physics step, each agent starts with a health of 1.0. lethal_distance (float): how close before weapons become effective. @@ -56,6 +59,7 @@ def __init__( max_duration_seconds (float): maximum simulation time of the environment. agent_hz (int): looprate of the agent to environment interaction. render_mode (None | str): can be "human" or None + """ # placeholder starting positions super().__init__( @@ -87,10 +91,13 @@ def observation_space(self, agent: Any = None) -> spaces.Box: """observation_space. Args: - agent: + ---- + agent (Any): agent Returns: + ------- spaces.Box: + """ return self._observation_space @@ -98,9 +105,13 @@ def _get_start_pos_orn(self, seed: None | int) -> tuple[np.ndarray, np.ndarray]: """_get_start_pos_orn. Args: + ---- + seed (None | int): seed Returns: + ------- tuple[np.ndarray, np.ndarray]: + """ np_random = np.random.RandomState(seed=seed) start_pos = np.zeros((2, 3)) @@ -117,11 +128,14 @@ def reset( """reset. Args: + ---- seed (None | int): seed options (dict[str, Any]): options Returns: + ------- tuple[dict[str, Any], dict[str, Any]]: + """ self.start_pos, self.start_orn = self._get_start_pos_orn(seed) @@ -164,10 +178,10 @@ def reset( def _compute_agent_states(self) -> None: """_compute_agent_states. - Args: - - Returns: + Returns + ------- None: + """ # get the states of both drones self.attitudes = np.stack(self.aviary.all_states, axis=0) @@ -251,10 +265,13 @@ def compute_observation_by_id(self, agent_id: int) -> np.ndarray: """compute_observation_by_id. Args: + ---- agent_id (int): agent_id Returns: + ------- np.ndarray: + """ # don't recompute if we've already done it if self.last_obs_time != self.aviary.elapsed_time: @@ -323,11 +340,14 @@ def compute_rotation_forward(orn: np.ndarray) -> tuple[np.ndarray, np.ndarray]: """Computes the rotation matrix and forward vector of an aircraft given its orientation. Args: + ---- orn (np.ndarray): an [n, 3] array of each drone's orientation Returns: + ------- np.ndarray: an [n, 3, 3] rotation matrix of each aircraft np.ndarray: an [n, 3] forward vector of each aircraft + """ c, s = np.cos(orn), np.sin(orn) eye = np.stack([np.eye(3)] * orn.shape[0], axis=0) @@ -367,9 +387,11 @@ def step( """step. Args: + ---- actions (dict[str, np.ndarray]): actions Returns: + ------- tuple[ dict[str, Any], dict[str, float], @@ -377,6 +399,7 @@ def step( dict[str, bool], dict[str, dict[str, Any]], ]: + """ returns = super().step(actions=actions) diff --git a/PyFlyt/pz_envs/quadx_envs/ma_quadx_base_env.py b/PyFlyt/pz_envs/quadx_envs/ma_quadx_base_env.py index a6868634..07310011 100644 --- a/PyFlyt/pz_envs/quadx_envs/ma_quadx_base_env.py +++ b/PyFlyt/pz_envs/quadx_envs/ma_quadx_base_env.py @@ -33,6 +33,7 @@ def __init__( """__init__. Args: + ---- start_pos (np.ndarray): start_pos start_orn (np.ndarray): start_orn flight_mode (int): flight_mode @@ -41,6 +42,7 @@ def __init__( angle_representation (str): angle_representation agent_hz (int): agent_hz render_mode (None | str): render_mode + """ if 120 % agent_hz != 0: lowest = int(120 / (int(120 / agent_hz) + 1)) @@ -152,10 +154,13 @@ def observation_space(self, agent: Any = None) -> Space: """observation_space. Args: - agent: + ---- + agent (Any): agent Returns: + ------- Space: + """ raise NotImplementedError @@ -163,10 +168,13 @@ def action_space(self, agent: Any = None) -> spaces.Box: """action_space. Args: - agent: + ---- + agent (Any): agent Returns: + ------- spaces.Box: + """ return self._action_space @@ -181,11 +189,14 @@ def reset( """reset. Args: - seed: - options: + ---- + seed (None | int): seed + options (None | dict[str, Any]): options Returns: - tuple[dict[str, Any], dict[str, Any]]: observation and infos + ------- + tuple[dict[str, Any], dict[str, Any]]: + """ raise NotImplementedError @@ -195,7 +206,19 @@ def begin_reset( options: None | dict[str, Any] = dict(), drone_options: None | dict[str, Any] | Sequence[dict[str, Any]] = dict(), ) -> None: - """The first half of the reset function.""" + """The first half of the reset function. + + Args: + ---- + seed (None | int): seed + options (None | dict[str, Any]): options + drone_options (None | dict[str, Any] | Sequence[dict[str, Any]]): drone_options + + Returns: + ------- + None: + + """ # if we already have an env, disconnect from it if hasattr(self, "aviary"): self.aviary.disconnect() @@ -259,10 +282,13 @@ def compute_observation_by_id(self, agent_id: int) -> Any: """compute_observation_by_id. Args: + ---- agent_id (int): agent_id Returns: + ------- Any: + """ raise NotImplementedError @@ -299,10 +325,13 @@ def compute_term_trunc_reward_info_by_id( """compute_term_trunc_reward_info_by_id. Args: + ---- agent_id (int): agent_id Returns: + ------- Tuple[bool, bool, float, dict[str, Any]]: + """ raise NotImplementedError @@ -318,10 +347,13 @@ def step( """step. Args: + ---- actions (dict[str, np.ndarray]): actions Returns: + ------- tuple[dict[str, Any], dict[str, float], dict[str, bool], dict[str, bool], dict[str, dict[str, Any]]]: + """ # copy over the past actions self.past_actions = deepcopy(self.current_actions) diff --git a/PyFlyt/pz_envs/quadx_envs/ma_quadx_hover_env.py b/PyFlyt/pz_envs/quadx_envs/ma_quadx_hover_env.py index f8a07a5a..871650d9 100644 --- a/PyFlyt/pz_envs/quadx_envs/ma_quadx_hover_env.py +++ b/PyFlyt/pz_envs/quadx_envs/ma_quadx_hover_env.py @@ -16,6 +16,7 @@ class MAQuadXHoverEnv(MAQuadXBaseEnv): The target is for each agent to not crash for the longest time possible. Args: + ---- start_pos (np.ndarray): an (num_drones x 3) numpy array specifying the starting positions of each agent. start_orn (np.ndarray): an (num_drones x 3) numpy array specifying the starting orientations of each agent. sparse_reward (bool): whether to use sparse rewards or not. @@ -25,6 +26,7 @@ class MAQuadXHoverEnv(MAQuadXBaseEnv): angle_representation (str): can be "euler" or "quaternion". agent_hz (int): looprate of the agent to environment interaction. render_mode (None | str): can be "human" or None. + """ metadata = { @@ -51,6 +53,7 @@ def __init__( """__init__. Args: + ---- start_pos (np.ndarray): an (num_drones x 3) numpy array specifying the starting positions of each agent. start_orn (np.ndarray): an (num_drones x 3) numpy array specifying the starting orientations of each agent. sparse_reward (bool): whether to use sparse rewards or not. @@ -60,6 +63,7 @@ def __init__( angle_representation (str): can be "euler" or "quaternion". agent_hz (int): looprate of the agent to environment interaction. render_mode (None | str): can be "human" or None. + """ super().__init__( start_pos=start_pos, @@ -85,7 +89,13 @@ def observation_space(self, agent: Any = None) -> spaces.Space: """observation_space. Args: - _: + ---- + agent (Any): agent + + Returns: + ------- + spaces.Space: + """ return self._observation_space @@ -95,8 +105,10 @@ def reset( """reset. Args: + ---- seed: seed to pass to the base environment. options: None + """ super().begin_reset(seed, options) super().end_reset(seed, options) @@ -112,10 +124,13 @@ def compute_observation_by_id(self, agent_id: int) -> np.ndarray: """compute_observation_by_id. Args: + ---- agent_id (int): agent_id Returns: + ------- np.ndarray: + """ # get all the relevant things raw_state = self.compute_attitude_by_id(agent_id) diff --git a/examples/core/05_custom_controller.py b/examples/core/05_custom_controller.py index 2305697f..e2f12a99 100644 --- a/examples/core/05_custom_controller.py +++ b/examples/core/05_custom_controller.py @@ -20,8 +20,10 @@ def step(self, state: np.ndarray, setpoint: np.ndarray): """Step the controller here. Args: + ---- state (np.ndarray): Current state of the UAV setpoint (np.ndarray): Desired setpoint + """ # outputs a command to base flight mode 6 that makes the drone stay at x=1, y=1, z=1, yawrate=0.5 target_velocity = np.array([1.0, 1.0, 1.0]) - state[-1] diff --git a/examples/core/09_simple_wind.py b/examples/core/09_simple_wind.py index 35c7b9d4..45fd7a9d 100644 --- a/examples/core/09_simple_wind.py +++ b/examples/core/09_simple_wind.py @@ -9,8 +9,10 @@ def simple_wind(time: float, position: np.ndarray): """Defines a simple wind updraft model. Args: + ---- time (float): time position (np.ndarray): position as an (n, 3) array + """ # the xy velocities are 0... wind = np.zeros_like(position) diff --git a/examples/core/10_custom_wind.py b/examples/core/10_custom_wind.py index d9774fe3..c4ee8a2c 100644 --- a/examples/core/10_custom_wind.py +++ b/examples/core/10_custom_wind.py @@ -15,8 +15,10 @@ def __init__( """__init__. Args: + ---- my_parameter: supports an arbitrary number of parameters np_random (None | np.random.RandomState): np random state + """ super().__init__(np_random) self.strength = my_parameter @@ -25,8 +27,10 @@ def __call__(self, time: float, position: np.ndarray): """__call__. Args: + ---- time (float): time position (np.ndarray): position as an (n, 3) array + """ wind = np.zeros_like(position) wind[:, -1] = np.exp(position[:, -1]) * self.strength diff --git a/examples/core/custom_uavs/rocket_brick.py b/examples/core/custom_uavs/rocket_brick.py index c00364f9..88026b92 100644 --- a/examples/core/custom_uavs/rocket_brick.py +++ b/examples/core/custom_uavs/rocket_brick.py @@ -33,6 +33,7 @@ def __init__( """Creates a UAV a brick acting as a lifting surface with a rocket attached. Args: + ---- p (bullet_client.BulletClient): p. start_pos (np.ndarray): start_pos. start_orn (np.ndarray): start_orn. @@ -47,6 +48,7 @@ def __init__( camera_FOV_degrees (int): camera_FOV_degrees. camera_resolution (tuple[int, int]): camera_resolution. camera_fps (None | int): camera_fps + """ super().__init__( p=p, @@ -145,7 +147,9 @@ def update_control(self, physics_step: int) -> None: """Runs through controllers. Args: + ---- physics_step (int): the current physics step + """ # skip control if we don't have enough physics steps if physics_step % self.physics_control_ratio != 0: @@ -199,7 +203,9 @@ def update_last(self, physics_step: int) -> None: """Updates things only at the end of `Aviary.step()`. Args: + ---- physics_step (int): the current physics step + """ if self.use_camera and (physics_step % self.physics_camera_ratio == 0): self.rgbaImg, self.depthImg, self.segImg = self.camera.capture_image() diff --git a/pyproject.toml b/pyproject.toml index da09befc..d805ccb5 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -4,7 +4,7 @@ build-backend = "setuptools.build_meta" [project] name = "PyFlyt" -version = "0.22.1" +version = "0.22.2" authors = [ { name="Jet", email="taijunjet@hotmail.com" }, ] @@ -46,8 +46,8 @@ Documentation = "https://jjshoots.github.io/PyFlyt/documentation.html" reportMissingImports = "none" [tool.ruff.lint] -select = ["E4", "E7", "E9", "F", "I"] -ignore = [] +ignore = ["D401", "D404", "D203", "D213"] +select = ["E4", "E7", "E9", "F", "I", "D"] [tool.ruff.lint.per-file-ignores] "__init__.py" = ["F401"] diff --git a/tests/test_core.py b/tests/test_core.py index aeabb690..504872a7 100644 --- a/tests/test_core.py +++ b/tests/test_core.py @@ -138,7 +138,7 @@ def test_camera(): def test_custom_controller(): - """Tests implementing a custom controller""" + """Tests implementing a custom controller.""" class CustomController(ControlClass): """A custom controller that inherits from the CtrlClass.""" @@ -155,8 +155,10 @@ def step(self, state: np.ndarray, setpoint: np.ndarray): """Step the controller here. Args: + ---- state (np.ndarray): Current state of the UAV setpoint (np.ndarray): Desired setpoint + """ # outputs a command to base flight mode 6 that makes the drone stay at x=1, y=1, z=1, yawrate=0.1 target_velocity = np.array([1.0, 1.0, 1.0]) - state[-1] @@ -262,10 +264,12 @@ def test_mixed_drones(): ["fixedwing", "rocket"], ) def test_simple_wind(model: str): - """Tests the wind field functionality + """Tests the wind field functionality. Args: + ---- model (str): model name + """ # define the wind field @@ -296,10 +300,12 @@ def simple_wind(time: float, position: np.ndarray): ["fixedwing", "rocket"], ) def test_custom_wind(model: str): - """Tests the wind field functionality + """Tests the wind field functionality. Args: + ---- model (str): model name + """ # define the wind field