Skip to content

Commit

Permalink
correct typos and grammar
Browse files Browse the repository at this point in the history
  • Loading branch information
tkclam committed Jun 19, 2024
1 parent f34b5d7 commit 1fb303a
Show file tree
Hide file tree
Showing 17 changed files with 62 additions and 62 deletions.
2 changes: 1 addition & 1 deletion doc/source/gallery/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ NeuroMechFly can be used to emulate a wide range of behaviours and scenarios. He
<div class="gallery-item">
<a href="video_13_plume_navigation.html">
<img src="https://github.com/NeLy-EPFL/_media/blob/main/flygym/videos/video_13_plume_navigation_v2_SWC_thumbnail.jpeg/?raw=true" alt="Plume navigation">
<p>Navigating dynamic olfactive environements</p>
<p>Navigating dynamic olfactive environments</p>
</a>
</div>
<div class="gallery-item">
Expand Down
2 changes: 1 addition & 1 deletion doc/source/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ FlyGym is the Python library for NeuroMechFly v2, a digital twin of the adult fr
FlyGym consists of the following components:

- **Biomechanical model:** The biomechanical model is based on a micro-CT scan of a real adult female fly (see our `original NeuroMechFly <https://doi.org/10.1038/s41592-022-01466-7>`_ publication). In NeuroMechFly v2 we have updated several body segments (in particular in the antennae) to better reflect the biological reality.
- **Vision:** The fly has compound eyes consisting of individual units called ommatidia. These are arranged on a hexagonal lattice. We have simulated visual inputs on the fly's retinae.
- **Vision:** The fly has compound eyes consisting of individual units called ommatidia. These are arranged on a hexagonal lattice. We have simulated visual inputs on the fly's retinas.
- **Olfaction:** The fly has odor receptors in the antennae and maxillary palps. We have simulated olfactory signals experienced by the fly by computing odor/chemical intensities at the locations of the antennae and maxillary palps.
- **Hierarchical control:** The fly's central nervous system (CNS) consists of the brain and the ventral nerve cord (VNC). This hierarchy is analogous to the brain-spinal cord organization of vertebrates. The user can build a two-part model --- one handling brain-level sensory integration and decision making as well as one handling VNC-level motor control --- with a interface between the two consisting of descending (brain-to-VNC) and ascending (VNC-to-brain) neuronal pathways.
- **Leg adhesion:** Insects have evolved specialized adhesive structures at the tips of their legs. These enable locomotion on inclined and overhanging surfaces. We have simulated adhesion in our model. The mechanism by which the fly lifts the legs during locomotion despite adhesive forces is currently not well understood. Therefore, to abstract this, adhesion can be turned on or off during stance or swing of the legs, respectively.
Expand Down
6 changes: 3 additions & 3 deletions doc/source/tutorials/advanced_olfaction.rst
Original file line number Diff line number Diff line change
Expand Up @@ -983,7 +983,7 @@ NeuroMechFly v2 paper for more details.
WalkingState.STOP: np.array((0.0, 0.0)),
}
# evidence acccumulation parameters
# evidence accumulation parameters
self.accumulated_evidence = 0.0
self.accumulation_decay = 0.0001
self.accumulation_odor_gain = 0.05
Expand All @@ -999,8 +999,8 @@ NeuroMechFly v2 paper for more details.
)
# descending neuron drive parameters
self.dn_drive_update_inteval = 0.1 # s
self.dn_drive_update_steps = int(self.dn_drive_update_inteval / self.timestep)
self.dn_drive_update_interval = 0.1 # s
self.dn_drive_update_steps = int(self.dn_drive_update_interval / self.timestep)
self.dn_drive = self.dn_drives[WalkingState.STOP]
# controller state parameters
Expand Down
2 changes: 1 addition & 1 deletion doc/source/tutorials/advanced_vision.rst
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ network model (`Lappalainen et al.,
2023 <https://www.biorxiv.org/content/10.1101/2023.03.11.532232>`__;
`code <https://github.com/TuragaLab/flyvis>`__). This study has
constructed an artificial neural network (ANN) representing the retina,
lamina, medula, lobula plate, and lobula of the fly visual system (see
lamina, medulla, lobula plate, and lobula of the fly visual system (see
figure below). The connectivity in this network is informed by the
connectome and, unlike typical ANNs, models biologically meaningful
variables such as voltage.
Expand Down
10 changes: 5 additions & 5 deletions flygym/data/mjcf/clean_xml.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ def set_mirrored_meshes(xml, symmetrical_bodies):
L_mesh_scaling[1] *= -1
R_mesh_rot.set(
"scale", " ".join([str(a) for a in L_mesh_scaling])
) # flip arround the plane x=0
) # flip around the plane x=0
R_mesh_rot.set("name", L_mesh_name)
mesh_parent.remove(L_mesh)
mesh_parent.append(R_mesh_rot)
Expand All @@ -84,7 +84,7 @@ def set_mirrored_meshes(xml, symmetrical_bodies):


def make_symmetric(xml, symmetrical_bodies, centered_bodies):
# Make the xml symmetrical by setting the orgin of every body symmetric to the origin
# Make the xml symmetrical by setting the origin of every body symmetric to the origin
# This is done for now by taking the mean of the two possible non symmetrical position

symmetry_vect = np.array([1, -1, 1])
Expand Down Expand Up @@ -145,7 +145,7 @@ def clean_geoms(xml):
), f"Visual geom {final_geom_name}_visual not found the file does not follow the basic naming convention"

if (not collision_geom is None) and (not visual_geom is None):
# This geom has both a visual and a collision geom: we shoudl remove the visual geom and the mesh referencing it and rename the collsion geom
# This geom has both a visual and a collision geom: we should remove the visual geom and the mesh referencing it and rename the collision geom
visual_mesh_name = visual_geom.get("mesh")
visual_mesh = xml.find(f".//mesh[@name='{visual_mesh_name}']")
collision_mesh_name = collision_geom.get("mesh")
Expand Down Expand Up @@ -230,7 +230,7 @@ def get_body_min_descendant(xml, names):


def remove_dummy_bodies(xml, kin_chain_order=["yaw", "pitch", "roll"]):
# remove dummy bodies that form the muli dof joints
# remove dummy bodies that form the multi dof joints

multi_dof_joint = get_all_multidof_joints(xml)
# start at the bottom of the chain for safety not sure this is necessary
Expand Down Expand Up @@ -324,7 +324,7 @@ def remove_inertials(xml):
def save_xml(xml, path):
# xml.write(path)

# reparse the xml wiht nicely aligned children
# reparse the xml with nicely aligned children
rough_string = etree.tostring(xml).decode("utf-8")
reparsed = minidom.parseString(rough_string)
smooth_string = reparsed.toprettyxml()
Expand Down
2 changes: 1 addition & 1 deletion flygym/examples/head_stabilization/data.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
class JointAngleScaler:
"""
A class for standardizing joint angles (i.e., using mean and standard
deviation.
deviation.)
Attributes
----------
Expand Down
20 changes: 10 additions & 10 deletions flygym/examples/locomotion/controller_comparison.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@
stumbling_force_threshold = -1
correction_rates = {"retraction": (800, 700), "stumbling": (2200, 1800)}
max_increment = 80
retraction_persistance = 20
persistance_init_thr = 20
retraction_persistence = 20
persistence_init_thr = 20


########### FUNCTIONS ############
Expand Down Expand Up @@ -158,7 +158,7 @@ def run_hybrid(
obs, info = sim.reset()
target_num_steps = int(run_time / sim.timestep)
obs_list = []
retraction_perisitance_counter = np.zeros(6)
retraction_persistence_counter = np.zeros(6)

for _ in range(target_num_steps):
# retraction rule: does a leg need to be retracted from a hole?
Expand All @@ -167,15 +167,15 @@ def run_hybrid(
end_effector_z_pos_sorted = end_effector_z_pos[end_effector_z_pos_sorted_idx]
if end_effector_z_pos_sorted[-1] > end_effector_z_pos_sorted[-3] + 0.05:
leg_to_correct_retraction = end_effector_z_pos_sorted_idx[-1]
if retraction_correction[leg_to_correct_retraction] > persistance_init_thr:
retraction_perisitance_counter[leg_to_correct_retraction] = 1
if retraction_correction[leg_to_correct_retraction] > persistence_init_thr:
retraction_persistence_counter[leg_to_correct_retraction] = 1
else:
leg_to_correct_retraction = None

# update persistance counter
retraction_perisitance_counter[retraction_perisitance_counter > 0] += 1
retraction_perisitance_counter[
retraction_perisitance_counter > retraction_persistance
# update persistence counter
retraction_persistence_counter[retraction_persistence_counter > 0] += 1
retraction_persistence_counter[
retraction_persistence_counter > retraction_persistence
] = 0

cpg_network.step()
Expand All @@ -185,7 +185,7 @@ def run_hybrid(
for j, leg in enumerate(preprogrammed_steps.legs):
# update amount of retraction correction
if (
j == leg_to_correct_retraction or retraction_perisitance_counter[j] > 0
j == leg_to_correct_retraction or retraction_persistence_counter[j] > 0
): # lift leg
increment = correction_rates["retraction"][0] * sim.timestep
retraction_correction[j] += increment
Expand Down
2 changes: 1 addition & 1 deletion flygym/examples/locomotion/hybrid_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ def run_hybrid_simulation(sim, cpg_network, preprogrammed_steps, run_time):

sim.render()
except PhysicsError:
print("Simulation was interupted because of a physics error")
print("Simulation was interrupted because of a physics error")
return obs_hist, info_hist, True

return obs_hist, info_hist, False
Expand Down
4 changes: 2 additions & 2 deletions flygym/examples/locomotion/turning_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -419,10 +419,10 @@ def step(self, action):
)

# get net correction amount
net_correction, reset_stumbing = self._get_net_correction(
net_correction, reset_stumbling = self._get_net_correction(
self.retraction_correction[i], self.stumbling_correction[i]
)
if reset_stumbing:
if reset_stumbling:
self.stumbling_correction[i] = 0.0

net_correction = np.clip(net_correction, 0, self.max_increment)
Expand Down
54 changes: 27 additions & 27 deletions flygym/examples/locomotion/turning_fly.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,8 @@ def __init__(
amplitude_range=(-0.5, 1.5),
draw_corrections=False,
max_increment=80 / 1e-4,
retraction_persistance_duration=20 / 1e-4,
retraction_persistance_initiation_threshold=20 / 1e-4,
retraction_persistence_duration=20 / 1e-4,
retraction_persistence_initiation_threshold=20 / 1e-4,
seed=0,
**kwargs,
):
Expand Down Expand Up @@ -107,12 +107,12 @@ def __init__(
are active in the rendered video.
max_increment : float, optional
Maximum duration of the correction before it is capped.
retraction_persistance_duration : float, optional
retraction_persistence_duration : float, optional
Time spend in a persistent state (leg is further retracted)
even if the rule is no longer active
retraction_persistance_initiation_threshold : float, optional
Amount of time the leg had to be retracted for for the persistance
to be initiated (prevents activation of persistance for noise driven
retraction_persistence_initiation_threshold : float, optional
Amount of time the leg had to be retracted for for the persistence
to be initiated (prevents activation of persistence for noise driven
rule activations)
seed : int, optional
Seed for the random number generator.
Expand Down Expand Up @@ -147,13 +147,13 @@ def __init__(
self.amplitude_range = amplitude_range
self.draw_corrections = draw_corrections
self.max_increment = max_increment * self.timestep
self.retraction_persistance_duration = (
retraction_persistance_duration * self.timestep
self.retraction_persistence_duration = (
retraction_persistence_duration * self.timestep
)
self.retraction_persistance_initiation_threshold = (
retraction_persistance_initiation_threshold * self.timestep
self.retraction_persistence_initiation_threshold = (
retraction_persistence_initiation_threshold * self.timestep
)
self.retraction_persistance_counter = np.zeros(6)
self.retraction_persistence_counter = np.zeros(6)
# Define the joints that need to be inverted to
# mirror actions from left to right
self.right_leg_inversion = [1, -1, -1, 1, -1, 1, 1]
Expand Down Expand Up @@ -238,10 +238,10 @@ def _find_stumbling_sensor_indices(self):
def _retraction_rule_find_leg(self, obs):
"""Returns the index of the leg that needs to be retracted, or None
if none applies.
Retraction can be due to the activation of a rule or persistance.
Every time the rule is active the persistance counter is set to 1. At every step the persistance
Retraction can be due to the activation of a rule or persistence.
Every time the rule is active the persistence counter is set to 1. At every step the persistence
counter is incremented. If the rule is still active it is again reset to 1 otherwise, it will
be incremented until it reaches the persistance duration. At this point the persistance counter
be incremented until it reaches the persistence duration. At this point the persistence counter
is reset to 0."""
end_effector_z_pos = obs["fly"][0][2] - obs["end_effectors"][:, 2]
end_effector_z_pos_sorted_idx = np.argsort(end_effector_z_pos)
Expand All @@ -250,23 +250,23 @@ def _retraction_rule_find_leg(self, obs):
leg_to_correct_retraction = end_effector_z_pos_sorted_idx[-1]
if (
self.retraction_correction[leg_to_correct_retraction]
> self.retraction_persistance_initiation_threshold
> self.retraction_persistence_initiation_threshold
):
self.retraction_persistance_counter[leg_to_correct_retraction] = 1
self.retraction_persistence_counter[leg_to_correct_retraction] = 1
else:
leg_to_correct_retraction = None
return leg_to_correct_retraction

def _update_persistance_counter(self):
"""Increment the persistance counter if it is nonzero. Zero the counter
when it reaches the persistance duration."""
def _update_persistence_counter(self):
"""Increment the persistence counter if it is nonzero. Zero the counter
when it reaches the persistence duration."""
# increment every nonzero counter
self.retraction_persistance_counter[
self.retraction_persistance_counter > 0
self.retraction_persistence_counter[
self.retraction_persistence_counter > 0
] += 1
# zero the increment when reaching the threshold
self.retraction_persistance_counter[
self.retraction_persistance_counter > self.retraction_persistance_duration
self.retraction_persistence_counter[
self.retraction_persistence_counter > self.retraction_persistence_duration
] = 0

def _stumbling_rule_check_condition(self, obs, leg):
Expand Down Expand Up @@ -386,8 +386,8 @@ def pre_step(self, action, sim: "Simulation"):

# Retraction rule: is any leg stuck in a gap and needing to be retracted?
leg_to_correct_retraction = self._retraction_rule_find_leg(obs)
self._update_persistance_counter()
persistent_retraction = self.retraction_persistance_counter > 0
self._update_persistence_counter()
persistent_retraction = self.retraction_persistence_counter > 0

self.cpg_network.step()

Expand Down Expand Up @@ -421,10 +421,10 @@ def pre_step(self, action, sim: "Simulation"):
)

# get net correction amount
net_correction, reset_stumbing = self._get_net_correction(
net_correction, reset_stumbling = self._get_net_correction(
self.retraction_correction[i], self.stumbling_correction[i]
)
if reset_stumbing:
if reset_stumbling:
self.stumbling_correction[i] = 0.0

net_correction = np.clip(net_correction, 0, self.max_increment)
Expand Down
2 changes: 1 addition & 1 deletion flygym/examples/olfaction/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ This subpackage includes the following files:
### Tracking complex plumes
- `simulate_plume_dataset.py`: This script simulates a complex plume by solving (a simplified version of) the incompressible Navier–Stokes equations.
- `plume_tracking_arena.py`: This module implements an `OdorPlumeArena`, which allows the fly to sense the intensity of the odor plume as it moves in space.
- `plume_tracking_task.py`: This module implements `PlumeNavigationTask`, a wrapper around `HybridTurningController`. This class enables rendering with odor intensity overlayed on top of the arena floor, along with some other utilities such as detecting if the fly has reached the limit of the arena.
- `plume_tracking_task.py`: This module implements `PlumeNavigationTask`, a wrapper around `HybridTurningController`. This class enables rendering with odor intensity overlaid on top of the arena floor, along with some other utilities such as detecting if the fly has reached the limit of the arena.
- `plume_tracking_controller.py`: This module implements the plume following algorithm proposed in [Demir et al., _eLife_, 2020](https://doi.org/10.7554/eLife.57524).
- `track_plume_closed_loop.py`: This script uses the controller above to perform the `PlumeNavigationTask` in closed loop. It is computationally heavy — for reference, we ran it on a 36-core node on the university cluster for a few hours.
- `visualize_plume_tracking_results.py`: This light script visualizes the results of the closed-loop plume following simulations. Please note that this script requires a manually entered string, `chosen_trial`, which is the trial for which a final video should be generated. The user must enter one of the trials printed by an earlier part of this script, and the script re-run. This is because the simulation results is only deterministic within the same MuJoCo version and chip architecture, and the set of successful trials might differ.
Expand Down
2 changes: 1 addition & 1 deletion flygym/examples/olfaction/plume_tracking_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ def overlay_focused_plume(self, focus_img, t_idx):
fc_y_fov = np.tan(fc_fov / 2) * fc_pos[2] * 2
fc_x_fov = fc_y_fov * self.fc_width / self.fc_height

# get a grid of points in the physical flygym space centered arround the fly
# get a grid of points in the physical flygym space centered around the fly
xs_physical_fov = (
np.arange(
0, np.ceil(fc_x_fov).astype(int) + 5, self.arena.dimension_scale_factor
Expand Down
2 changes: 1 addition & 1 deletion flygym/examples/path_integration/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
This subpackage includes the following files:
- `arena.py`: This module defines the arena that our path integration task is performed in.
- `controller.py`: This module defines the NeuroMechFly controller that performs random exploration (i.e., bouts of straight walking separated by stochastic turning).
- `exploration.py`: With the controller mentioned above, this script runs random exploration trials using differnt gait patterns. It is somewhat computationally heavy — for reference, we ran it on a 16-core workstation for about 1.5 hours.
- `exploration.py`: With the controller mentioned above, this script runs random exploration trials using different gait patterns. It is somewhat computationally heavy — for reference, we ran it on a 16-core workstation for about 1.5 hours.
- `model.py`: This module defines the path integration model.
- `build_models.py`: This script trains and tests the path integrations models using the exploration trials. We ran it on a 16-core machine for about an hour.
- `util.py`: Utilities for feature extraction.
Expand Down
4 changes: 2 additions & 2 deletions flygym/examples/path_integration/tests/test_exploration.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,13 @@ def test_random_exploration_controller():
dn_drive_hist = np.array(dn_drive_hist)

forward_mask = state_hist == controller.WalkingState.FORWARD
left_rurn_mask = state_hist == controller.WalkingState.TURN_LEFT
left_turn_mask = state_hist == controller.WalkingState.TURN_LEFT
right_turn_mask = state_hist == controller.WalkingState.TURN_RIGHT
stop_mask = state_hist == controller.WalkingState.STOP

assert forward_mask[: int(1 / dt)].all() # always walking forward during init_time
assert (dn_drive_hist[forward_mask, :] == [1.0, 1.0]).all()
assert (dn_drive_hist[left_rurn_mask, :] == [0.2, 1.0]).all()
assert (dn_drive_hist[left_turn_mask, :] == [0.2, 1.0]).all()
assert (dn_drive_hist[right_turn_mask, :] == [1.0, 0.2]).all()
assert (~stop_mask).all() # never stops

Expand Down
Loading

0 comments on commit 1fb303a

Please sign in to comment.