Locomotion¶
Preprogrammed steps¶
- class flygym.examples.locomotion.PreprogrammedSteps(path=None, neutral_pose_phases=(np.pi, np.pi, np.pi, np.pi, np.pi, np.pi))¶
Bases:
object
Preprogrammed steps by each leg extracted from experimental recordings.
- Parameters:
- pathstr or Path, optional
Path to the preprogrammed steps data. If None, the default preprogrammed steps data will be loaded.
- neutral_pose_phaseslist[float]
Phase during the preprogrammed step that should be considered the “neutral” resting pose. This is specified for each of the 6 limbs and normalized to [0, 2π).
- Attributes:
- legslist[str]
List of leg names (e.g. LF for left front leg).
- dofs_per_leglist[str]
List of names for degrees of freedom for each leg.
- durationfloat
Duration of the preprogrammed step (at 1x speed) in seconds.
- neutral_posdict[str, np.ndarray]
Neutral position of DoFs for each leg. Keys are leg names; values are joint angles in the order of
self.dofs_per_leg
.- swing_perioddict[str, np.ndarray]
The start and end of the lifted swing phase for each leg. Keys are leg names; values are arrays of shape (2,) with the start and end of the swing normalized to [0, 2π].
- property default_pose¶
Default pose of the fly (all legs in neutral position) given as a single array. It is ready to be used as the “joints” state in the action space of
NeuroMechFly
like the following:NeuroMechFly.step(action={"joints": preprogrammed_steps.default_pose})
.
- dofs_per_leg = ['Coxa', 'Coxa_roll', 'Coxa_yaw', 'Femur', 'Femur_roll', 'Tibia', 'Tarsus1']¶
- get_adhesion_onoff(leg, phase)¶
Get whether adhesion is on for a given leg at a given phase.
- Parameters:
- legstr
Leg name.
- phasefloat or np.ndarray
Phase or array of phases of the step normalized to [0, 2π].
- Returns:
- bool or np.ndarray
Whether adhesion is on for the leg at the given phase(s). A boolean array of shape (n,) is returned if
phase
is a 1D array of n elements; a bool is returned ifphase
is a scalar.
- get_joint_angles(leg, phase, magnitude=1)¶
Get joint angles for a given leg at a given phase.
- Parameters:
- legstr
Leg name.
- phasefloat or np.ndarray
Phase or array of phases of the step normalized to [0, 2π].
- magnitudefloat or np.ndarray, optional
Magnitude of the step. Default: 1 (the preprogrammed steps as provided).
- Returns:
- np.ndarray
Joint angles of the leg at the given phase(s). The shape of the array is (7, n) if
phase
is a 1D array of n elements, or (7,) ifphase
is a scalar.
- legs = ['LF', 'LM', 'LH', 'RF', 'RM', 'RH']¶
CPG controller¶
- class flygym.examples.locomotion.CPGNetwork(timestep, intrinsic_freqs, intrinsic_amps, coupling_weights, phase_biases, convergence_coefs, init_phases=None, init_magnitudes=None, seed=0)¶
Bases:
object
- reset(init_phases=None, init_magnitudes=None)¶
Reset the phases and magnitudes of the oscillators. High magnitudes and unfortunate phases might cause physics error.
- step()¶
Integrate the ODEs using Euler’s method.
Rule-based controller¶
- class flygym.examples.locomotion.RuleBasedController(timestep, rules_graph, weights, preprogrammed_steps, margin=0.001, seed=0)¶
Bases:
object
- Parameters:
- timestepfloat
The timestep of the simulation.
- rules_graphnx.MultiDiGraph
The rules graph that defines the interactions between the legs.
- weightsdict
The weights for each rule.
- preprogrammed_stepsPreprogrammedSteps, optional
Preprogrammed steps to be used for leg movement.
- marginfloat, optional
The margin for selecting the highest scoring leg.
- seedint, optional
The random seed to use for selecting the highest scoring leg.
- property combined_scores¶
The global score for all legs. The highest scoring leg is selected for stepping.
- legs = ['LF', 'LM', 'LH', 'RF', 'RM', 'RH']¶
- step()¶
Steps the controller for one timestep. Updates the leg phases. Updates the scores based on the rules.
Hybrid turning controller¶
- class flygym.examples.locomotion.HybridTurningController(fly: Fly, preprogrammed_steps=None, intrinsic_freqs=np.ones(6) * 12, intrinsic_amps=np.ones(6) * 1, phase_biases=_tripod_phase_biases, coupling_weights=_tripod_coupling_weights, convergence_coefs=np.ones(6) * 20, init_phases=None, init_magnitudes=None, stumble_segments=('Tibia', 'Tarsus1', 'Tarsus2'), stumbling_force_threshold=-1, correction_vectors=_default_correction_vectors, correction_rates=_default_correction_rates, amplitude_range=(-0.5, 1.5), draw_corrections=False, max_increment=80 / 1e-4, retraction_persistence_duration=20 / 1e-4, retraction_persistence_initiation_threshold=20 / 1e-4, seed=0, **kwargs)¶
Bases:
SingleFlySimulation
This class implements a controller that uses a CPG network to generate leg movements and uses a set of sensory-based rules to correct for stumbling and retraction. The controller also receives a 2D descending input to modulate the amplitudes and frequencies of the CPGs to accomplish turning.
- Parameters:
- flyFly
The fly object to be simulated.
- preprogrammed_stepsPreprogrammedSteps, optional
Preprogrammed steps to be used for leg movement.
- intrinsic_freqsnp.ndarray, optional
Intrinsic frequencies of the CPGs. See
CPGNetwork
for details.- intrinsic_ampsnp.ndarray, optional
Intrinsic amplitudes of the CPGs. See
CPGNetwork
for details.- phase_biasesnp.ndarray, optional
Phase biases of the CPGs. See
CPGNetwork
for details.- coupling_weightsnp.ndarray, optional
Coupling weights of the CPGs. See
CPGNetwork
for details.- convergence_coefsnp.ndarray, optional
Convergence coefficients of the CPGs. See
CPGNetwork
for details.- init_phasesnp.ndarray, optional
Initial phases of the CPGs. See
CPGNetwork
for details.- init_magnitudesnp.ndarray, optional
Initial magnitudes of the CPGs. See
CPGNetwork
for details.- stumble_segmentstuple, optional
Leg segments to be used for stumbling detection.
- stumbling_force_thresholdfloat, optional
Threshold for stumbling detection.
- correction_vectorsdict, optional
Correction vectors for each leg.
- correction_ratesdict, optional
Correction rates for retraction and stumbling.
- amplitude_rangetuple, optional
Range for leg lifting correction.
- draw_correctionsbool, optional
Whether to color-code legs to indicate if correction rules are active in the rendered video.
- max_incrementfloat, optional
Maximum duration of the correction before it is capped.
- retraction_persist3nce_durationfloat, optional
Time spend in a persistent state (leg is further retracted) even if the rule is no longer active
- retraction_persist3nce_initiation_thresholdfloat, 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)
- seedint, optional
Seed for the random number generator.
- **kwargs
Additional keyword arguments to be passed to
SingleFlySimulation.__init__
.
Notes
Please refer to the “MPD Task Specifications” page of the API references for the detailed specifications of the action space, the observation space, the reward, the “terminated” and “truncated” flags, and the “info” dictionary.
- property action_space¶
- close() None ¶
Close the simulation, save data, and release any resources.
- get_observation() ObsType ¶
- get_wrapper_attr(name: str) Any ¶
Gets the attribute name from the environment.
- property gravity¶
- has_wrapper_attr(name: str) bool ¶
Checks if the attribute name exists in the environment.
- metadata: dict[str, Any] = {'render_modes': []}¶
- property np_random: Generator¶
Returns the environment’s internal
_np_random
that if not set will initialise with a random seed.- Returns:
Instances of np.random.Generator
- property np_random_seed: int¶
Returns the environment’s internal
_np_random_seed
that if not set will first initialise with a random int as seed.If
np_random_seed
was set directly instead of throughreset()
orset_np_random_through_seed()
, the seed will take the value -1.- Returns:
int: the seed of the current np_random or -1, if the seed of the rng is unknown
- property observation_space¶
- render(*args, **kwargs)¶
Compute the render frames as specified by
render_mode
during the initialization of the environment.The environment’s
metadata
render modes (env.metadata[“render_modes”]) should contain the possible ways to implement the render modes. In addition, list versions for most render modes is achieved through gymnasium.make which automatically applies a wrapper to collect rendered frames.- Note:
As the
render_mode
is known during__init__
, the objects used to render the environment state should be initialised in__init__
.
By convention, if the
render_mode
is:None (default): no render is computed.
“human”: The environment is continuously rendered in the current display or terminal, usually for human consumption. This rendering should occur during
step()
andrender()
doesn’t need to be called. ReturnsNone
.“rgb_array”: Return a single frame representing the current state of the environment. A frame is a
np.ndarray
with shape(x, y, 3)
representing RGB values for an x-by-y pixel image.“ansi”: Return a strings (
str
) orStringIO.StringIO
containing a terminal-style text representation for each time step. The text can include newlines and ANSI escape sequences (e.g. for colors).“rgb_array_list” and “ansi_list”: List based version of render modes are possible (except Human) through the wrapper,
gymnasium.wrappers.RenderCollection
that is automatically applied duringgymnasium.make(..., render_mode="rgb_array_list")
. The frames collected are popped afterrender()
is called orreset()
.
- Note:
Make sure that your class’s
metadata
"render_modes"
key includes the list of supported modes.
Changed in version 0.25.0: The render function was changed to no longer accept parameters, rather these parameters should be specified in the environment initialised, i.e.,
gymnasium.make("CartPole-v1", render_mode="human")
- render_mode: str | None = None¶
- reset(seed=None, init_phases=None, init_magnitudes=None, **kwargs)¶
Reset the simulation.
- Parameters:
- seedint, optional
Seed for the random number generator. If None, the simulation is re-seeded without a specific seed. For reproducibility, always specify a seed.
- init_phasesnp.ndarray, optional
Initial phases of the CPGs. See
CPGNetwork
for details.- init_magnitudesnp.ndarray, optional
Initial magnitudes of the CPGs. See
CPGNetwork
for details.- **kwargs
Additional keyword arguments to be passed to
SingleFlySimulation.reset
.
- Returns:
- np.ndarray
Initial observation upon reset.
- dict
Additional information.
- set_slope(slope: float, rot_axis='y')¶
Set the slope of the simulation environment and modify the camera orientation so that gravity is always pointing down. Changing the gravity vector might be useful during climbing simulations. The change in the camera angle has been extensively tested for the simple cameras (left, right, top, bottom, front, back) but not for the composed ones.
- Parameters:
- slopefloat
The desired_slope of the environment in degrees.
- rot_axisstr, optional
The axis about which the slope is applied, by default “y”.
- set_wrapper_attr(name: str, value: Any)¶
Sets the attribute name on the environment with value.
- spec: EnvSpec | None = None¶
- step(action)¶
Step the simulation forward one timestep.
- Parameters:
- actionnp.ndarray
Array of shape (2,) containing descending signal encoding turning.
- property unwrapped: Env[ObsType, ActType]¶
Returns the base non-wrapped environment.
- Returns:
Env: The base non-wrapped
gymnasium.Env
instance
Hybrid turning fly¶
- class flygym.examples.locomotion.HybridTurningFly(timestep=1e-4, preprogrammed_steps=None, intrinsic_freqs=np.ones(6) * 12, intrinsic_amps=np.ones(6) * 1, phase_biases=_tripod_phase_biases, coupling_weights=_tripod_coupling_weights, convergence_coefs=np.ones(6) * 20, init_phases=None, init_magnitudes=None, stumble_segments=('Tibia', 'Tarsus1', 'Tarsus2'), stumbling_force_threshold=-1, correction_vectors=_default_correction_vectors, correction_rates=_default_correction_rates, amplitude_range=(-0.5, 1.5), draw_corrections=False, max_increment=80 / 1e-4, retraction_persistence_duration=20 / 1e-4, retraction_persistence_initiation_threshold=20 / 1e-4, seed=0, **kwargs)¶
Bases:
Fly
This class implements a controller that uses a CPG network to generate leg movements and uses a set of sensory-based rules to correct for stumbling and retraction. The controller also receives a 2D descending input to modulate the amplitudes and frequencies of the CPGs to accomplish turning.
- Parameters:
- preprogrammed_stepsPreprogrammedSteps, optional
Preprogrammed steps to be used for leg movement.
- intrinsic_freqsnp.ndarray, optional
Intrinsic frequencies of the CPGs. See
CPGNetwork
for details.- intrinsic_ampsnp.ndarray, optional
Intrinsic amplitudes of the CPGs. See
CPGNetwork
for details.- phase_biasesnp.ndarray, optional
Phase biases of the CPGs. See
CPGNetwork
for details.- coupling_weightsnp.ndarray, optional
Coupling weights of the CPGs. See
CPGNetwork
for details.- convergence_coefsnp.ndarray, optional
Convergence coefficients of the CPGs. See
CPGNetwork
for details.- init_phasesnp.ndarray, optional
Initial phases of the CPGs. See
CPGNetwork
for details.- init_magnitudesnp.ndarray, optional
Initial magnitudes of the CPGs. See
CPGNetwork
for details.- stumble_segmentstuple, optional
Leg segments to be used for stumbling detection.
- stumbling_force_thresholdfloat, optional
Threshold for stumbling detection.
- correction_vectorsdict, optional
Correction vectors for each leg.
- correction_ratesdict, optional
Correction rates for retraction and stumbling.
- amplitude_rangetuple, optional
Range for leg lifting correction.
- draw_correctionsbool, optional
Whether to color-code legs to indicate if correction rules are active in the rendered video.
- max_incrementfloat, optional
Maximum duration of the correction before it is capped.
- retraction_persistence_durationfloat, optional
Time spend in a persistent state (leg is further retracted) even if the rule is no longer active
- retraction_persistence_initiation_thresholdfloat, 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)
- seedint, optional
Seed for the random number generator.
- **kwargs
Additional keyword arguments to be passed to
SingleFlySimulation.__init__
.
- change_segment_color(physics: dm_control.mjcf.Physics, segment: str, color)¶
Change the color of a segment of the fly.
- Parameters:
- physicsmjcf.Physics
The physics object of the simulation.
- segmentstr
The name of the segment to change the color of.
- colortuple[float, float, float, float]
Target color as RGBA values normalized to [0, 1].
- close()¶
Release resources allocated by the environment.
- config = {'appearance': {'a12345': {'apply_to': ['A1A2', 'A3', 'A4', 'A5'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'gradient', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.82, 0.67, 0.47], 'size': 200}}, 'a6': {'apply_to': ['A6'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'gradient', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.39, 0.2, 0], 'rgb2': [0.82, 0.67, 0.47], 'size': 200}}, 'antenna': {'apply_to': ['LPedicel', 'RPedicel', 'LFuniculus', 'RFuniculus'], 'material': {'rgba': [1, 1, 1, 0.8]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.1, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'arista': {'apply_to': ['LArista', 'RArista'], 'material': {'rgba': [0.26, 0.2, 0.16, 1.0]}, 'texture': None}, 'coxa': {'apply_to': ['LFCoxa', 'RFCoxa', 'LMCoxa', 'RMCoxa', 'LHCoxa', 'RHCoxa'], 'material': {'rgba': [1, 1, 1, 0.8]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 500}}, 'eye': {'apply_to': ['LEye', 'REye'], 'material': {'rgba': [0.67, 0.21, 0.12, 1]}, 'texture': None}, 'femur': {'apply_to': ['LFFemur', 'RFFemur', 'LMFemur', 'RMFemur', 'LHFemur', 'RHFemur'], 'material': {'rgba': [1, 1, 1, 0.7]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.63, 0.43, 0.16], 'rgb2': [0.63, 0.43, 0.16], 'size': 500}}, 'haltere': {'apply_to': ['LHaltere', 'RHaltere'], 'material': {'rgba': [0.59, 0.43, 0.24, 0.6]}, 'texture': None}, 'head': {'apply_to': ['Head'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'flat', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'proboscis': {'apply_to': ['Haustellum', 'Rostrum'], 'material': {'rgba': [1, 1, 1, 0.8]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.1, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'tarsus': {'apply_to': ['LFTarsus1', 'RFTarsus1', 'LMTarsus1', 'RMTarsus1', 'LHTarsus1', 'RHTarsus1', 'LFTarsus2', 'RFTarsus2', 'LMTarsus2', 'RMTarsus2', 'LHTarsus2', 'RHTarsus2', 'LFTarsus3', 'RFTarsus3', 'LMTarsus3', 'RMTarsus3', 'LHTarsus3', 'RHTarsus3', 'LFTarsus4', 'RFTarsus4', 'LMTarsus4', 'RMTarsus4', 'LHTarsus4', 'RHTarsus4', 'LFTarsus5', 'RFTarsus5', 'LMTarsus5', 'RMTarsus5', 'LHTarsus5', 'RHTarsus5'], 'material': {'rgba': [1, 1, 1, 0.5]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.71, 0.51, 0.24], 'rgb2': [0.71, 0.51, 0.24], 'size': 500}}, 'thorax': {'apply_to': ['Thorax'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'flat', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'tibia': {'apply_to': ['LFTibia', 'RFTibia', 'LMTibia', 'RMTibia', 'LHTibia', 'RHTibia'], 'material': {'rgba': [1, 1, 1, 0.6]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.67, 0.47, 0.2], 'rgb2': [0.67, 0.47, 0.2], 'size': 500}}, 'wing': {'apply_to': ['LWing', 'RWing'], 'material': {'rgba': [0.8, 0.8, 0.9, 0.3]}, 'texture': None}}, 'color_cycle_rgb': [[31, 119, 180], [255, 127, 14], [44, 160, 44], [214, 39, 40], [148, 103, 189], [140, 86, 75], [227, 119, 194], [127, 127, 127], [188, 189, 34], [23, 190, 207]], 'olfaction': {'sensor_positions': {'LAntenna_sensor': {'marker_rgba': [0.08, 0.4, 0.9, 1], 'parent': 'LFuniculus', 'rel_pos': [0.02, 0.0, -0.1]}, 'LMaxillaryPalp_sensor': {'marker_rgba': [0.9, 0.73, 0.08, 1], 'parent': 'Rostrum', 'rel_pos': [-0.15, 0.15, -0.15]}, 'RAntenna_sensor': {'marker_rgba': [0.08, 0.4, 0.9, 1], 'parent': 'RFuniculus', 'rel_pos': [0.02, 0.0, -0.1]}, 'RMaxillaryPalp_sensor': {'marker_rgba': [0.9, 0.73, 0.08, 1], 'parent': 'Rostrum', 'rel_pos': [-0.15, -0.15, -0.15]}}}, 'paths': {'canonical_pale_type_mask': 'vision/pale_mask.npy', 'mjcf': {'deepfly3d': 'mjcf/neuromechfly_deepfly3d_kinorder_ryp.xml', 'deepfly3d_old': 'mjcf/neuromechfly_deepfly3d_kinorder_ryp_old.xml', 'seqik': 'mjcf/neuromechfly_seqik_kinorder_ypr.xml', 'seqik_old': 'mjcf/neuromechfly_seqik_kinorder_ypr_old.xml'}, 'ommatidia_id_map': 'vision/ommatidia_id_map.npy'}, 'vision': {'fisheye_distortion_coefficient': 3.8, 'fisheye_zoom': 2.72, 'fovy_per_eye': 157, 'hidden_segments': ['LFCoxa', 'LEye', 'LArista', 'LFuniculus', 'LPedicel', 'RFCoxa', 'REye', 'RArista', 'RFuniculus', 'RPedicel', 'Head', 'Rostrum', 'Haustellum', 'Thorax'], 'num_ommatidia_per_eye': 721, 'raw_img_height_px': 512, 'raw_img_width_px': 450, 'sensor_positions': {'LEye_cam': {'marker_rgba': [0.07, 0.45, 0.35, 1], 'orientation': [1.57, 0.0, -0.47], 'parent': 'LEye', 'rel_pos': [-0.03, 0.38, 0]}, 'REye_cam': {'marker_rgba': [0.07, 0.45, 0.35, 1], 'orientation': [-1.57, 3.14, 0.47], 'parent': 'REye', 'rel_pos': [-0.03, -0.38, 0]}}}}¶
- get_info()¶
Any additional information that is not part of the observation. This method always returns an empty dictionary unless extended by the user.
- Returns:
- dict[str, Any]
The dictionary containing additional information.
- get_observation(sim: Simulation) ObsType ¶
Get observation without stepping the physics simulation.
- Returns:
- ObsType
The observation as defined by the environment.
- get_reward()¶
Get the reward for the current state of the environment. This method always returns 0 unless extended by the user.
- Returns:
- float
The reward.
- init_floor_contacts(arena: BaseArena)¶
Initialize contacts between the fly and the floor. This is called by the Simulation after the fly is placed in the arena and before setting up the physics engine.
- Parameters:
- arenaBaseArena
The arena in which the fly is placed.
- is_terminated()¶
Whether the episode has terminated due to factors that are defined within the Markov Decision Process (e.g. task completion/ failure, etc.). This method always returns False unless extended by the user.
- Returns:
- bool
Whether the simulation is terminated.
- is_truncated()¶
- Whether the episode has terminated due to factors beyond the
Markov Decision Process (e.g. time limit, etc.). This method always returns False unless extended by the user.
- Returns:
- bool
Whether the simulation is truncated.
- n_legs = 6¶
- property name: str¶
- observation_space: spaces.Dict¶
- post_init(sim: Simulation)¶
Initialize attributes that depend on the arena or physics of the simulation.
- Parameters:
- simSimulation
Simulation object.
- post_step(sim: Simulation)¶
- pre_step(action, sim: Simulation)¶
Step the simulation forward one timestep.
- Parameters:
- simSimulation
Simulation object.
- actionnp.ndarray
Array of shape (2,) containing descending signal encoding turning.
- reset(sim: Simulation, seed=None, init_phases=None, init_magnitudes=None, **kwargs)¶
Reset the fly.
- Parameters:
- simSimulation
Simulation object.
- seedint, optional
Seed for the random number generator. If None, the simulation is re-seeded without a specific seed. For reproducibility, always specify a seed.
- init_phasesnp.ndarray, optional
Initial phases of the CPGs. See
CPGNetwork
for details.- init_magnitudesnp.ndarray, optional
Initial magnitudes of the CPGs. See
CPGNetwork
for details.- **kwargs
Additional keyword arguments to be passed to
SingleFlySimulation.reset
.
- Returns:
- np.ndarray
Initial observation upon reset.
- dict
Additional information.
- set_pose(pose: KinematicPose, physics: dm_control.mjcf.Physics)¶
- update_colors(physics: dm_control.mjcf.Physics)¶
Update the colors of the fly’s body segments. This is typically called by Simulation.render to update the colors of the fly before the cameras do the rendering.
- Parameters:
- physicsmjcf.Physics
The physics object of the simulation.
- property vision_update_mask: ndarray¶
The refresh frequency of the visual system is often loser than the same as the physics simulation time step. This 1D mask, whose size is the same as the number of simulation time steps, indicates in which time steps the visual inputs have been refreshed. In other words, the visual input frames where this mask is False are repetitions of the previous updated visual input frames.
Utility class for coloring body segments of the fly¶
The following utility class is a wrapper around the Fly
class that facilitates the recoloring of specific segments. This is useful for, as an example, recoloring parts of the leg depending on the activation of specific correction rules.
- class flygym.examples.locomotion.ColorableFly(recolor_types=('femur', 'tibia'), **kwargs)¶
Bases:
Fly
A wrapper around the Fly class that facilitates the recoloring of specific segments. This is useful for, as an example, recoloring parts of the leg depending on the activation of specific correction rules.
This class is necessary because the leg segments would otherwise not be colored as intended: “textures are applied in GL_MODULATE mode, meaning that the texture color and the color specified here are multiplied component-wise” as mentioned in the MuJoCo documentation. This class overrides the impact of the default texture on the resulting final color. See https://mujoco.readthedocs.io/en/stable/XMLreference.html#asset-material-rgba
- change_segment_color(physics: dm_control.mjcf.Physics, segment: str, color=None)¶
Change the color of a segment of the fly.
- Parameters:
- physicsmjcf.Physics
The physics object of the simulation.
- segmentstr
The name of the segment to change the color of.
- colortuple[float, float, float, float]
Target color as RGBA values normalized to [0, 1].
- close()¶
Release resources allocated by the environment.
- config = {'appearance': {'a12345': {'apply_to': ['A1A2', 'A3', 'A4', 'A5'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'gradient', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.82, 0.67, 0.47], 'size': 200}}, 'a6': {'apply_to': ['A6'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'gradient', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.39, 0.2, 0], 'rgb2': [0.82, 0.67, 0.47], 'size': 200}}, 'antenna': {'apply_to': ['LPedicel', 'RPedicel', 'LFuniculus', 'RFuniculus'], 'material': {'rgba': [1, 1, 1, 0.8]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.1, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'arista': {'apply_to': ['LArista', 'RArista'], 'material': {'rgba': [0.26, 0.2, 0.16, 1.0]}, 'texture': None}, 'coxa': {'apply_to': ['LFCoxa', 'RFCoxa', 'LMCoxa', 'RMCoxa', 'LHCoxa', 'RHCoxa'], 'material': {'rgba': [1, 1, 1, 0.8]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 500}}, 'eye': {'apply_to': ['LEye', 'REye'], 'material': {'rgba': [0.67, 0.21, 0.12, 1]}, 'texture': None}, 'femur': {'apply_to': ['LFFemur', 'RFFemur', 'LMFemur', 'RMFemur', 'LHFemur', 'RHFemur'], 'material': {'rgba': [1, 1, 1, 0.7]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.63, 0.43, 0.16], 'rgb2': [0.63, 0.43, 0.16], 'size': 500}}, 'haltere': {'apply_to': ['LHaltere', 'RHaltere'], 'material': {'rgba': [0.59, 0.43, 0.24, 0.6]}, 'texture': None}, 'head': {'apply_to': ['Head'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'flat', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'proboscis': {'apply_to': ['Haustellum', 'Rostrum'], 'material': {'rgba': [1, 1, 1, 0.8]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.1, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'tarsus': {'apply_to': ['LFTarsus1', 'RFTarsus1', 'LMTarsus1', 'RMTarsus1', 'LHTarsus1', 'RHTarsus1', 'LFTarsus2', 'RFTarsus2', 'LMTarsus2', 'RMTarsus2', 'LHTarsus2', 'RHTarsus2', 'LFTarsus3', 'RFTarsus3', 'LMTarsus3', 'RMTarsus3', 'LHTarsus3', 'RHTarsus3', 'LFTarsus4', 'RFTarsus4', 'LMTarsus4', 'RMTarsus4', 'LHTarsus4', 'RHTarsus4', 'LFTarsus5', 'RFTarsus5', 'LMTarsus5', 'RMTarsus5', 'LHTarsus5', 'RHTarsus5'], 'material': {'rgba': [1, 1, 1, 0.5]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.71, 0.51, 0.24], 'rgb2': [0.71, 0.51, 0.24], 'size': 500}}, 'thorax': {'apply_to': ['Thorax'], 'material': {'rgba': [1, 1, 1, 1]}, 'texture': {'builtin': 'flat', 'markrgb': [0.7, 0.49, 0.2], 'random': 0.3, 'rgb1': [0.59, 0.39, 0.12], 'rgb2': [0.59, 0.39, 0.12], 'size': 50}}, 'tibia': {'apply_to': ['LFTibia', 'RFTibia', 'LMTibia', 'RMTibia', 'LHTibia', 'RHTibia'], 'material': {'rgba': [1, 1, 1, 0.6]}, 'texture': {'builtin': 'flat', 'markrgb': [0, 0, 0], 'random': 0.05, 'rgb1': [0.67, 0.47, 0.2], 'rgb2': [0.67, 0.47, 0.2], 'size': 500}}, 'wing': {'apply_to': ['LWing', 'RWing'], 'material': {'rgba': [0.8, 0.8, 0.9, 0.3]}, 'texture': None}}, 'color_cycle_rgb': [[31, 119, 180], [255, 127, 14], [44, 160, 44], [214, 39, 40], [148, 103, 189], [140, 86, 75], [227, 119, 194], [127, 127, 127], [188, 189, 34], [23, 190, 207]], 'olfaction': {'sensor_positions': {'LAntenna_sensor': {'marker_rgba': [0.08, 0.4, 0.9, 1], 'parent': 'LFuniculus', 'rel_pos': [0.02, 0.0, -0.1]}, 'LMaxillaryPalp_sensor': {'marker_rgba': [0.9, 0.73, 0.08, 1], 'parent': 'Rostrum', 'rel_pos': [-0.15, 0.15, -0.15]}, 'RAntenna_sensor': {'marker_rgba': [0.08, 0.4, 0.9, 1], 'parent': 'RFuniculus', 'rel_pos': [0.02, 0.0, -0.1]}, 'RMaxillaryPalp_sensor': {'marker_rgba': [0.9, 0.73, 0.08, 1], 'parent': 'Rostrum', 'rel_pos': [-0.15, -0.15, -0.15]}}}, 'paths': {'canonical_pale_type_mask': 'vision/pale_mask.npy', 'mjcf': {'deepfly3d': 'mjcf/neuromechfly_deepfly3d_kinorder_ryp.xml', 'deepfly3d_old': 'mjcf/neuromechfly_deepfly3d_kinorder_ryp_old.xml', 'seqik': 'mjcf/neuromechfly_seqik_kinorder_ypr.xml', 'seqik_old': 'mjcf/neuromechfly_seqik_kinorder_ypr_old.xml'}, 'ommatidia_id_map': 'vision/ommatidia_id_map.npy'}, 'vision': {'fisheye_distortion_coefficient': 3.8, 'fisheye_zoom': 2.72, 'fovy_per_eye': 157, 'hidden_segments': ['LFCoxa', 'LEye', 'LArista', 'LFuniculus', 'LPedicel', 'RFCoxa', 'REye', 'RArista', 'RFuniculus', 'RPedicel', 'Head', 'Rostrum', 'Haustellum', 'Thorax'], 'num_ommatidia_per_eye': 721, 'raw_img_height_px': 512, 'raw_img_width_px': 450, 'sensor_positions': {'LEye_cam': {'marker_rgba': [0.07, 0.45, 0.35, 1], 'orientation': [1.57, 0.0, -0.47], 'parent': 'LEye', 'rel_pos': [-0.03, 0.38, 0]}, 'REye_cam': {'marker_rgba': [0.07, 0.45, 0.35, 1], 'orientation': [-1.57, 3.14, 0.47], 'parent': 'REye', 'rel_pos': [-0.03, -0.38, 0]}}}}¶
- get_info()¶
Any additional information that is not part of the observation. This method always returns an empty dictionary unless extended by the user.
- Returns:
- dict[str, Any]
The dictionary containing additional information.
- get_observation(sim: Simulation) ObsType ¶
Get observation without stepping the physics simulation.
- Returns:
- ObsType
The observation as defined by the environment.
- get_reward()¶
Get the reward for the current state of the environment. This method always returns 0 unless extended by the user.
- Returns:
- float
The reward.
- init_floor_contacts(arena: BaseArena)¶
Initialize contacts between the fly and the floor. This is called by the Simulation after the fly is placed in the arena and before setting up the physics engine.
- Parameters:
- arenaBaseArena
The arena in which the fly is placed.
- is_terminated()¶
Whether the episode has terminated due to factors that are defined within the Markov Decision Process (e.g. task completion/ failure, etc.). This method always returns False unless extended by the user.
- Returns:
- bool
Whether the simulation is terminated.
- is_truncated()¶
- Whether the episode has terminated due to factors beyond the
Markov Decision Process (e.g. time limit, etc.). This method always returns False unless extended by the user.
- Returns:
- bool
Whether the simulation is truncated.
- n_legs = 6¶
- property name: str¶
- observation_space: spaces.Dict¶
- post_init(sim: Simulation)¶
Initialize attributes that depend on the arena or physics of the simulation.
- Parameters:
- simSimulation
Simulation object.
- post_step(sim: Simulation)¶
- pre_step(action, sim: Simulation)¶
- reset(sim: Simulation, **kwargs)¶
- set_pose(pose: KinematicPose, physics: dm_control.mjcf.Physics)¶
- update_colors(physics: dm_control.mjcf.Physics)¶
Update the colors of the fly’s body segments. This is typically called by Simulation.render to update the colors of the fly before the cameras do the rendering.
- Parameters:
- physicsmjcf.Physics
The physics object of the simulation.
- property vision_update_mask: ndarray¶
The refresh frequency of the visual system is often loser than the same as the physics simulation time step. This 1D mask, whose size is the same as the number of simulation time steps, indicates in which time steps the visual inputs have been refreshed. In other words, the visual input frames where this mask is False are repetitions of the previous updated visual input frames.