From c1b71943993718c91e62577817c07a4ee1d623c3 Mon Sep 17 00:00:00 2001 From: Jonathan Kelm Date: Mon, 6 Jan 2025 19:11:28 +0100 Subject: [PATCH 1/3] Removed closing "controller" and replaced it with crazyswarm magic (#23) * Removed closing "controller" and replaced it with crazyswarm magic (tested on hardware) --------- Co-authored-by: Martin Schuck <57562633+amacati@users.noreply.github.com> --- .../control/closing_controller.py | 320 ------------------ .../envs/drone_racing_deploy_env.py | 62 ++-- lsy_drone_racing/envs/drone_racing_env.py | 46 --- 3 files changed, 23 insertions(+), 405 deletions(-) delete mode 100644 lsy_drone_racing/control/closing_controller.py diff --git a/lsy_drone_racing/control/closing_controller.py b/lsy_drone_racing/control/closing_controller.py deleted file mode 100644 index f915dee8..00000000 --- a/lsy_drone_racing/control/closing_controller.py +++ /dev/null @@ -1,320 +0,0 @@ -"""This controller is only called when the drone passes the last gate and the environment gets closed. - -The controller works in two steps: First, is slows down from any initial speed. Second, it returns to the starting position -> return to home (RTH) - -The waypoints for the stopping part are generated using a quintic spline, to be able to set the start and end velocity and acceleration. -The waypoints for the RTH trajectory are created by a cubic spline with waypoints in a predefined height. -""" - -from __future__ import annotations # Python 3.10 type hints - -import logging -from enum import Enum -from typing import TYPE_CHECKING, Union - -import numpy as np -import pybullet as p -from scipy.interpolate import CubicSpline - -from lsy_drone_racing.control import BaseController - -if TYPE_CHECKING: - from numpy.typing import NDArray - -logger = logging.getLogger("rosout." + __name__) # Get ROS compatible logger - - -class Mode(Enum): - """Enum class for the different modes of the controller.""" - - STOP = 0 - HOVER = 1 - RETURN = 2 - LAND = 3 - - -class ClosingController(BaseController): - """Controller that creates and follows a braking and homing trajectory.""" - - def __init__(self, initial_obs: dict[str, NDArray[np.floating]], initial_info: dict): - """Initialization of the controller. - - Args: - initial_obs: The initial observation of the environment's state. See the environment's - observation space for details. - initial_info: Additional environment information from the reset. - """ - super().__init__(initial_obs, initial_info) - - self._tick = 0 - self.info = initial_info - self._freq = self.info["env_freq"] - self._t_step_ctrl = 1 / self._freq # control step - - self.debug = False # Plot the trajectories in sim. TODO: Make configurable - self._return_height = 2.0 # height of the return path - - self._target_pos = initial_obs["pos"] - self._brake_trajectory, self._t_brake = self._generate_brake_trajectory(initial_obs) - self._return_trajectory = None # Gets generated on the fly based on the current state - - self._t_hover = 2.0 # time the drone hovers before returning home and before landing - self._t_return = 9.0 # time it takes to get back to start (return to home) - self.t_total = self._t_brake + self._t_hover + self._t_return + self._t_hover - - def compute_control( - self, obs: dict[str, NDArray[np.floating]], info: dict | None = None - ) -> NDArray[np.floating]: - """Compute the next desired state of the drone. - - Args: - obs: The current observation of the environment. See the environment's observation space - for details. - info: Optional additional information as a dictionary. - - Returns: - The drone state [x, y, z, vx, vy, vz, ax, ay, az, yaw, rrate, prate, yrate] as a numpy - array. - """ - t = self._tick * self._t_step_ctrl - if self.mode == Mode.STOP: - target_pos = self._brake_trajectory(t, order=0) - target_vel = self._brake_trajectory(t, order=1) - target_acc = self._brake_trajectory(t, order=2) - self._target_pos = obs["pos"] # store for hover mode - elif self.mode == Mode.HOVER: - target_pos = self._target_pos - target_vel = [0, 0, 0] - target_acc = [0, 0, 0] - elif self.mode == Mode.RETURN: - if self._return_trajectory is None: - self._return_trajectory = self._generate_return_trajectory(obs, t) - target_pos = self._return_trajectory(t) - trajectory_v = self._return_trajectory.derivative() - trajectory_a = trajectory_v.derivative() - target_vel = trajectory_v(t) * 0 - target_acc = trajectory_a(t) * 0 - elif self.mode == Mode.LAND: - target_pos = np.array(self.info["drone_start_pos"]) + np.array([0, 0, 0.25]) - target_vel = [0, 0, 0] - target_acc = [0, 0, 0] - return np.concatenate((target_pos, target_vel, target_acc, np.zeros(4))) - - @property - def mode(self) -> Mode: - """Return the current mode of the controller.""" - t = self._tick * self._t_step_ctrl - if t <= self._t_brake: - return Mode.STOP - if self._t_brake < t <= self._t_brake + self._t_hover: - return Mode.HOVER - if self._t_brake + self._t_hover < t <= self._t_brake + self._t_hover + self._t_return: - return Mode.RETURN - return Mode.LAND - - def step_callback( - self, - action: NDArray[np.floating], - obs: dict[str, NDArray[np.floating]], - reward: float, - terminated: bool, - truncated: bool, - info: dict, - ): - """Increment the time step counter.""" - self._tick += 1 - - def episode_reset(self): - """Reset the time step counter.""" - self._tick = 0 - - def _generate_brake_trajectory( - self, obs: dict[str, NDArray[np.floating]] - ) -> Union[QuinticSpline, np.floating]: - start_pos = obs["pos"] - start_vel = obs["vel"] - start_acc = obs["acc"] - - direction = start_vel / np.linalg.norm(start_vel) # Unit vector in the direction of travel - # Angle to the floor => negative means v_z < 0 - direction_angle = -(np.arccos((np.dot(direction, [0, 0, 1]))) - np.pi / 2) - # Calculate the distance the drone can travel before stopping - dist = np.clip(np.linalg.norm(start_vel), 0.5, 2.0) / np.cos(direction_angle) - # Check if drone would crash into floor or ceiling, and clip the values if necessary - pos_z = start_pos[2] + dist * np.sin(direction_angle) - dist = (np.clip(pos_z, 0.2, 2.5) - start_pos[2]) / np.sin(direction_angle) - - pos_z = start_pos[2] + dist * np.sin(direction_angle) # Recalculate pos_z after clipping - logger.debug(f"Start height: {start_pos[2]:.2f}, End height: {pos_z:.2f}, Dist: {dist:.2f}") - logger.debug(f"Angle: {direction_angle*180/np.pi:.0f}°") - - # Estimate the constant deceleration that is necessary for braking - const_acc = np.linalg.norm(start_vel) ** 2 / (dist) - # The time it takes to brake completely. Clip to 1s minimum to avoid short braking times - t_brake_max = max(1.0, np.sqrt(4 * dist / const_acc)) - - logger.debug(f"Gate velocity: {start_vel}, Braking time: {t_brake_max:.2f}s") - - brake_trajectory = QuinticSpline( - 0, - t_brake_max, - start_pos, - start_vel, - start_acc, - start_pos + direction * dist, - start_vel * 0, - start_acc * 0, - ) - - if self.debug: - plot_trajectory(brake_trajectory, color=[0, 1, 0]) - return brake_trajectory, t_brake_max - - def _generate_return_trajectory( - self, obs: dict[str, NDArray[np.floating]], t: np.floating - ) -> CubicSpline: - start_pos = obs["pos"] - # Landing position is 0.25m above the ground - landing_pos = np.array(self.info["drone_start_pos"]) + np.array([0, 0, 0.25]) - - delta_pos = landing_pos - start_pos - intermed_pos1 = start_pos + delta_pos / 4 - intermed_pos1[2] = self._return_height - - intermed_pos2 = intermed_pos1 + delta_pos / 2 - intermed_pos2[2] = self._return_height - - intermed_pos3 = 5 * landing_pos / 6 + intermed_pos2 / 6 - intermed_pos3[2] = landing_pos[2] / 2 + intermed_pos2[2] / 2 - - waypoints = np.array([start_pos, intermed_pos1, intermed_pos2, intermed_pos3, landing_pos]) - bc_type = ((1, [0, 0, 0]), (1, [0, 0, 0])) # Set boundary conditions for the derivative (1) - t = np.linspace(t, t + self._t_return, len(waypoints)) - return_trajectory = CubicSpline(t, waypoints, bc_type=bc_type) - - if self.debug: - plot_trajectory(return_trajectory) - return return_trajectory - - -def plot_trajectory(spline: CubicSpline | QuinticSpline, color: list[float] = [0, 0, 1]): - """Plot the drone's and the controller's trajectories.""" - n_segments = 20 - t = np.linspace(spline.x[0], spline.x[-1], n_segments) - pos = spline(t) - try: - for i in range(len(pos)): - p.addUserDebugLine( - pos[max(i - 1, 0)], - pos[i], - lineColorRGB=color, - lineWidth=2, - lifeTime=0, # 0 means the line persists indefinitely - physicsClientId=0, - ) - for x in spline(spline.x): - p.addUserDebugText("x", x, textColorRGB=color) - except p.error: - logger.warning("PyBullet not available") # Ignore errors if PyBullet is not available - - -class QuinticSpline: - """This class and the code below is mostly written by ChatGPT 4.0.""" - - def __init__( - self, - t0: np.floating, - t1: np.floating, - x0: np.floating, - v0: np.floating, - a0: np.floating, - x1: np.floating, - v1: np.floating, - a1: np.floating, - ): - """Initialize the quintic spline for multidimensional conditions. - - Params: - t0: Start time. - t1: End time. - x0: Initial position. - v0: Initial velocity. - a0: Initial acceleration. - x1: Final position. - v1: Final velocity. - a1: Final acceleration. - """ - self.t_points = (t0, t1) # Start and end time points - self.dimensions = len(x0) # Number of dimensions - # Boundary conditions per dimension - self.boundary_conditions = np.array([x0, v0, a0, x1, v1, a1]) - self.splines = np.array([self._compute_spline(i) for i in range(self.dimensions)]) - self.x = np.array([t0, t1]) # Make compatible to CubicSpline API - - def _compute_spline(self, dim: int) -> NDArray: - t0, t1 = self.t_points - x0, v0, a0, x1, v1, a1 = self.boundary_conditions[:, dim] - - # Constructing the coefficient matrix for the quintic polynomial - M = np.array( - [ - [1, t0, t0**2, t0**3, t0**4, t0**5], # position @ t0 - [0, 1, 2 * t0, 3 * t0**2, 4 * t0**3, 5 * t0**4], # velocity @ t0 - [0, 0, 2, 6 * t0, 12 * t0**2, 20 * t0**3], # acceleration @ t0 - [1, t1, t1**2, t1**3, t1**4, t1**5], # position @ t1 - [0, 1, 2 * t1, 3 * t1**2, 4 * t1**3, 5 * t1**4], # velocity @ t1 - [0, 0, 2, 6 * t1, 12 * t1**2, 20 * t1**3], # acceleration @ t1 - ] - ) - # Construct the boundary condition vector - b = np.array([x0, v0, a0, x1, v1, a1]) - # Solve for coefficients of the quintic polynomial - coefficients = np.linalg.solve(M, b) - return coefficients - - def __call__(self, t: np.floating, order: int = 0) -> NDArray: - """Evaluate the quintic spline or its derivatives at a given time t for all dimensions. - - Params: - t: Time at which to evaluate - order: Derivative order (0=position, 1=velocity, 2=acceleration) - - Examples: - >>> t0, t1 = 0, 1 - >>> x0, v0, a0 = [0.0, 0.0], [0.0, 1.0], [0.0, 0.0] # Initial conditions for x and y - >>> x1, v1, a1 = [1.0, 1.0], [0.0, 0.0], [0.0, 0.0] # Final conditions for x and y - >>> spline = QuinticSpline(t0, t1, x0, v0, a0, x1, v1, a1) - >>> t_values = np.linspace(t0, t1, 100) - >>> pos_values = spline(t_values, order=0) # Position - >>> vel_values = np.array([spline(t, order=1) for t in t_values]) # Velocity - >>> acc_values = np.array([spline(t, order=2) for t in t_values]) # Acceleration - - Returns: - A list of evaluated values for each dimension - """ - t = np.atleast_1d(t) - if order == 0: - return self._position(t).squeeze() - elif order == 1: - return self._velocity(t).squeeze() - elif order == 2: - return self._acceleration(t).squeeze() - raise ValueError(f"Spline orders (0, 1, 2) are supported, got {order}") - - def _position(self, t: NDArray[np.floating]) -> NDArray[np.floating]: - powers = t[:, None] ** np.arange(len(self.splines[0])) - return np.dot(powers, self.splines.T) - - def _velocity(self, t: NDArray[np.floating]) -> NDArray[np.floating]: - mult = np.arange(len(self.splines[0])) - powers = np.zeros((len(t), len(self.splines[0]))) - powers[1:, :] = t[1:, None] ** (mult - 1) - coeffs = self.splines * mult[None, :] # Multiply by i - return np.dot(powers, coeffs.T) - - def _acceleration(self, t: NDArray[np.floating]) -> NDArray[np.floating]: - mult = np.arange(len(self.splines[0])) - powers = np.zeros((len(t), len(self.splines[0]))) - powers[1:, :] = t[1:, None] ** (mult - 2) - coeffs = self.splines * (mult * (mult - 1))[None, :] # Multiply by i*(i-1) - return np.dot(powers, coeffs.T) diff --git a/lsy_drone_racing/envs/drone_racing_deploy_env.py b/lsy_drone_racing/envs/drone_racing_deploy_env.py index 2e762883..d3cea48a 100644 --- a/lsy_drone_racing/envs/drone_racing_deploy_env.py +++ b/lsy_drone_racing/envs/drone_racing_deploy_env.py @@ -28,10 +28,10 @@ import gymnasium import numpy as np +import rospy from gymnasium import spaces from scipy.spatial.transform import Rotation as R -from lsy_drone_racing.control.closing_controller import ClosingController from lsy_drone_racing.sim.drone import Drone from lsy_drone_racing.sim.sim import Sim from lsy_drone_racing.utils import check_gate_pass @@ -179,45 +179,29 @@ def step( def close(self): """Close the environment by stopping the drone and landing back at the starting position.""" - return_home = True # makes the drone simulate the return to home after stopping - - if return_home: - # This is done to run the closing controller at a different frequency than the controller before - # Does not influence other code, since this part is already in closing! - # WARNING: When changing the frequency, you must also change the current _step!!! - freq_new = 100 # Hz - self.config.env.freq = freq_new - t_step_ctrl = 1 / self.config.env.freq - + RETURN_HEIGHT = 1.75 # m + BREAKING_DISTANCE = 1.0 # m + BREAKING_DURATION = 4.0 # s + RETURN_DURATION = 5.0 # s + LAND_DURATION = 4.5 # s + + try: # prevent hanging process if drone not reachable + self.cf.notifySetpointsStop() obs = self.obs - obs["acc"] = np.array( - [0, 0, 0] - ) # TODO, use actual value when avaiable or do one step to calculate from velocity - info = self.info - info["env_freq"] = self.config.env.freq - info["drone_start_pos"] = self.config.env.track.drone.pos - - controller = ClosingController(obs, info) - t_total = controller.t_total - - for i in np.arange(int(t_total / t_step_ctrl)): # hover for some more time - action = controller.compute_control(obs) - action = action.astype(np.float64) # Drone firmware expects float64 - pos, vel, acc, yaw, rpy_rate = ( - action[:3], - action[3:6], - action[6:9], - action[9], - action[10:], - ) - self.cf.cmdFullState(pos, vel, acc, yaw, rpy_rate) - obs = self.obs - obs["acc"] = np.array([0, 0, 0]) - controller.step_callback(action, obs, 0, True, False, info) - time.sleep(t_step_ctrl) - - self.cf.notifySetpointsStop() - self.cf.land(0.05, 2.0) + + return_pos = obs['pos'] + obs['vel']/(np.linalg.norm(obs['vel']) + 1e-8) * BREAKING_DISTANCE + return_pos[2] = RETURN_HEIGHT + self.cf.goTo(goal = return_pos, yaw=0, duration=BREAKING_DURATION) + time.sleep(BREAKING_DURATION - 1) # Smoothly transition to next position by setting the next goal earlier + + return_pos[:2] = self.config.env.track.drone.pos[:2] + self.cf.goTo(goal=return_pos, yaw=0, duration=RETURN_DURATION) + time.sleep(RETURN_DURATION) + + self.cf.land(self.config.env.track.drone.pos[2], LAND_DURATION) + time.sleep(LAND_DURATION) + except rospy.service.ServiceException as e: + logger.error('Cannot return home: ' + str(e)) @property def obs(self) -> dict: diff --git a/lsy_drone_racing/envs/drone_racing_env.py b/lsy_drone_racing/envs/drone_racing_env.py index d17d9955..c5b14ef4 100644 --- a/lsy_drone_racing/envs/drone_racing_env.py +++ b/lsy_drone_racing/envs/drone_racing_env.py @@ -27,7 +27,6 @@ import copy as copy import logging -import time from typing import TYPE_CHECKING import gymnasium @@ -35,7 +34,6 @@ from gymnasium import spaces from scipy.spatial.transform import Rotation as R -from lsy_drone_racing.control.closing_controller import ClosingController from lsy_drone_racing.sim.physics import PhysicsMode from lsy_drone_racing.sim.sim import Sim from lsy_drone_racing.utils import check_gate_pass @@ -310,50 +308,6 @@ def gate_passed(self) -> bool: def close(self): """Close the environment by stopping the drone and landing back at the starting position.""" - return_home = True # makes the drone simulate the return to home after stopping - - if return_home: - # This is done to run the closing controller at a different frequency than the controller before - # Does not influence other code, since this part is already in closing! - # WARNING: When changing the frequency, you must also change the current _step!!! - freq_new = 100 # Hz - self._steps = int(self._steps / self.config.env.freq * freq_new) - self.config.env.freq = freq_new - t_step_ctrl = 1 / self.config.env.freq - - obs = self.obs - obs["acc"] = np.array( - [0, 0, 0] - ) # TODO, use actual value when avaiable or do one step to calculate from velocity - info = self.info - info["env_freq"] = self.config.env.freq - info["drone_start_pos"] = self.config.env.track.drone.pos - - controller = ClosingController(obs, info) - t_total = controller.t_total - - for i in np.arange(int(t_total / t_step_ctrl)): # hover for some more time - action = controller.compute_control(obs) - action = action.astype(np.float64) # Drone firmware expects float64 - if self.config.sim.physics == PhysicsMode.SYS_ID: - print("[Warning] sys_id model not supported by return home script") - break - pos, vel, acc, yaw, rpy_rate = ( - action[:3], - action[3:6], - action[6:9], - action[9], - action[10:], - ) - self.sim.drone.full_state_cmd(pos, vel, acc, yaw, rpy_rate) - collision = self._inner_step_loop() - terminated = self.terminated or collision - obs = self.obs - obs["acc"] = np.array([0, 0, 0]) - controller.step_callback(action, obs, self.reward, terminated, False, info) - if self.config.sim.gui: # Only sync if gui is active - time.sleep(t_step_ctrl) - self.sim.close() From 86f8d7d1521047d38c9e59aac3547611911d2e09 Mon Sep 17 00:00:00 2001 From: Niklas Schlueter Date: Wed, 8 Jan 2025 17:00:43 +0100 Subject: [PATCH 2/3] Fixed a bug where gates_visited and obstacles_visited would not be updated if the practice_without_track_objects setting was enabled. --- .../envs/drone_racing_deploy_env.py | 47 +++++++++++-------- 1 file changed, 27 insertions(+), 20 deletions(-) diff --git a/lsy_drone_racing/envs/drone_racing_deploy_env.py b/lsy_drone_racing/envs/drone_racing_deploy_env.py index d3cea48a..28deb58a 100644 --- a/lsy_drone_racing/envs/drone_racing_deploy_env.py +++ b/lsy_drone_racing/envs/drone_racing_deploy_env.py @@ -185,14 +185,18 @@ def close(self): RETURN_DURATION = 5.0 # s LAND_DURATION = 4.5 # s - try: # prevent hanging process if drone not reachable + try: # prevent hanging process if drone not reachable self.cf.notifySetpointsStop() obs = self.obs - - return_pos = obs['pos'] + obs['vel']/(np.linalg.norm(obs['vel']) + 1e-8) * BREAKING_DISTANCE + + return_pos = ( + obs["pos"] + obs["vel"] / (np.linalg.norm(obs["vel"]) + 1e-8) * BREAKING_DISTANCE + ) return_pos[2] = RETURN_HEIGHT - self.cf.goTo(goal = return_pos, yaw=0, duration=BREAKING_DURATION) - time.sleep(BREAKING_DURATION - 1) # Smoothly transition to next position by setting the next goal earlier + self.cf.goTo(goal=return_pos, yaw=0, duration=BREAKING_DURATION) + time.sleep( + BREAKING_DURATION - 1 + ) # Smoothly transition to next position by setting the next goal earlier return_pos[:2] = self.config.env.track.drone.pos[:2] self.cf.goTo(goal=return_pos, yaw=0, duration=RETURN_DURATION) @@ -201,7 +205,7 @@ def close(self): self.cf.land(self.config.env.track.drone.pos[2], LAND_DURATION) time.sleep(LAND_DURATION) except rospy.service.ServiceException as e: - logger.error('Cannot return home: ' + str(e)) + logger.error("Cannot return home: " + str(e)) @property def obs(self) -> dict: @@ -230,6 +234,9 @@ def obs(self) -> dict: obstacles_pos = np.array([o.pos for o in self.config.env.track.obstacles]) obstacle_names = [f"obstacle{g}" for g in range(1, len(obstacles_pos) + 1)] + real_gates_pos = gates_pos + real_gates_rpy = gates_rpy + real_obstacles_pos = obstacles_pos # Update objects position with vicon data if not in practice mode and object # either is in range or was in range previously. if not self.config.deploy.practice_without_track_objects: @@ -237,20 +244,20 @@ def obs(self) -> dict: real_gates_rpy = np.array([self.vicon.rpy[g] for g in gate_names]) real_obstacles_pos = np.array([self.vicon.pos[o] for o in obstacle_names]) - # Use x-y distance to calucate sensor range, otherwise it would depend on the height of the drone - # and obstacle how early the obstacle is in range. - in_range = np.linalg.norm(real_gates_pos[:, :2] - drone_pos[:2], axis=1) < sensor_range - self.gates_visited = np.logical_or(self.gates_visited, in_range) - gates_pos[self.gates_visited] = real_gates_pos[self.gates_visited] - gates_rpy[self.gates_visited] = real_gates_rpy[self.gates_visited] - obs["gates_visited"] = in_range - - in_range = ( - np.linalg.norm(real_obstacles_pos[:, :2] - drone_pos[:2], axis=1) < sensor_range - ) - self.obstacles_visited = np.logical_or(self.obstacles_visited, in_range) - obstacles_pos[self.obstacles_visited] = real_obstacles_pos[self.obstacles_visited] - obs["obstacles_visited"] = in_range + # Use x-y distance to calucate sensor range, otherwise it would depend on the height of the drone + # and obstacle how early the obstacle is in range. + in_range = np.linalg.norm(real_gates_pos[:, :2] - drone_pos[:2], axis=1) < sensor_range + self.gates_visited = np.logical_or(self.gates_visited, in_range) + gates_pos[self.gates_visited] = real_gates_pos[self.gates_visited] + gates_rpy[self.gates_visited] = real_gates_rpy[self.gates_visited] + obs["gates_visited"] = self.gates_visited + print(f"gates visited: {self.gates_visited}") + + in_range = np.linalg.norm(real_obstacles_pos[:, :2] - drone_pos[:2], axis=1) < sensor_range + self.obstacles_visited = np.logical_or(self.obstacles_visited, in_range) + obstacles_pos[self.obstacles_visited] = real_obstacles_pos[self.obstacles_visited] + obs["obstacles_visited"] = self.obstacles_visited + print(f"obs visited: {self.obstacles_visited}") obs["gates_pos"] = gates_pos.astype(np.float32) obs["gates_rpy"] = gates_rpy.astype(np.float32) From b1781456d1b6502b49314ac7cb95add753e95e87 Mon Sep 17 00:00:00 2001 From: Martin Schuck Date: Thu, 30 Jan 2025 00:48:48 +0100 Subject: [PATCH 3/3] Prevent CI/CD from failing because of kaggle submission --- .github/workflows/kaggle.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/kaggle.yml b/.github/workflows/kaggle.yml index 340cfebe..22903205 100644 --- a/.github/workflows/kaggle.yml +++ b/.github/workflows/kaggle.yml @@ -10,6 +10,8 @@ on: jobs: online-competition: + # Skip this job if running on the main repo to prevent failing CI/CD. Only run on student forks. + if: ${{ github.repository != 'utiasDSL/lsy_drone_racing' }} runs-on: ubuntu-latest env: # Or as an environment variable