@@ -203,6 +203,10 @@ def __init__(self, physics_controller: PhysicsInterface, robot: MyRobot):
203203
204204 self .imu = robot .chassis .imu .sim_state
205205
206+ self .injector = rev .SparkMaxSim (
207+ robot .injector_component .injector_1 , DCMotor .NEO550 (1 )
208+ )
209+
206210 self .vision_sim = VisionSystemSim ("main" )
207211 self .vision_sim .addAprilTags (game .apriltag_layout )
208212 properties = SimCameraProperties .OV9281_1280_720 ()
@@ -222,9 +226,6 @@ def __init__(self, physics_controller: PhysicsInterface, robot: MyRobot):
222226 robot .injector_component .algae_limit_switch
223227 )
224228 self .algae_pickup_counter = 0
225- self .floor_intake = robot .floor_intake
226- self .reef_intake = robot .reef_intake
227- self .algae_shooter = robot .algae_shooter
228229
229230 def update_sim (self , now : float , tm_diff : float ) -> None :
230231 # Enable the Phoenix6 simulated devices
@@ -277,25 +278,35 @@ def update_sim(self, now: float, tm_diff: float) -> None:
277278
278279 # Update intake arm simulation
279280 self .intake_arm .update (tm_diff )
281+ intake_arm_angle = self .intake_arm .mech_sim .getAngle ()
280282 self .intake_arm_encoder_sim .set (
281- self . intake_arm . mech_sim . getAngle () + IntakeComponent .ARM_ENCODER_OFFSET
283+ intake_arm_angle + IntakeComponent .ARM_ENCODER_OFFSET
282284 )
283285
284286 # Update wrist simulation
285287 self .wrist .update (tm_diff )
286- self .wrist_encoder_sim .set (
287- self .wrist .mech_sim .getAngle () + WristComponent .ENCODER_ZERO_OFFSET
288- )
288+ wrist_angle = self .wrist .mech_sim .getAngle ()
289+ self .wrist_encoder_sim .set (wrist_angle + WristComponent .ENCODER_ZERO_OFFSET )
289290
291+ injector_output = self .injector .getAppliedOutput ()
290292 # Simulate algae pick up
291- if self .floor_intake .current_state == "intaking" :
293+ if (
294+ wrist_angle < WristComponent .NEUTRAL_ANGLE
295+ and intake_arm_angle < IntakeComponent .RETRACTED_ANGLE
296+ and injector_output < 0
297+ ):
292298 # Simulate driving around for a couple of seconds
293299 self .algae_pickup_counter += 1
294300 if self .algae_pickup_counter == 100 :
295301 self .algae_limit_switch_sim .setValue (False )
296302 else :
297303 self .algae_pickup_counter = 0
298- if self .reef_intake .current_state == "intaking" :
304+
305+ # Reef intake
306+ if (
307+ wrist_angle > WristComponent .NEUTRAL_ANGLE + WristComponent .TOLERANCE
308+ and injector_output < 0
309+ ):
299310 # Check near reef
300311 pose = self .physics_controller .get_pose ()
301312 pos = pose .translation ()
@@ -304,6 +315,7 @@ def update_sim(self, now: float, tm_diff: float) -> None:
304315 or pos .distance (game .RED_REEF_POS ) < 2.0
305316 ):
306317 self .algae_limit_switch_sim .setValue (False )
318+
307319 # Algae shooting
308- if self . algae_shooter . current_state == "shooting" :
320+ if injector_output > 0 :
309321 self .algae_limit_switch_sim .setValue (True )
0 commit comments