Skip to content

Commit 084ab9a

Browse files
committed
Changed timings to match mech requirements
1 parent a5be499 commit 084ab9a

File tree

1 file changed

+20
-7
lines changed
  • pio_workspace/test/thruster_tests/Docker/catkin_ws/src/propulsion/src

1 file changed

+20
-7
lines changed

pio_workspace/test/thruster_tests/Docker/catkin_ws/src/propulsion/src/thruster_tests.py

Lines changed: 20 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -21,28 +21,41 @@
2121
pwm_array = [1500] * 8
2222

2323
# Ascending sequence
24-
for pwm in range(1520, 1901, 20):
24+
for pwm in range(1508, 1901, 8): # Changed step to 8
2525
pwm_array[thruster_num] = pwm
2626
pub.publish(ThrusterMicroseconds(pwm_array))
2727
print(f"Sent PWM {pwm} to thruster {thruster_num + 1}")
28-
time.sleep(1.5)
28+
29+
# Sleep for 3.5 seconds if not 1500, otherwise 15 seconds
30+
if pwm != 1500:
31+
time.sleep(3.5)
32+
else:
33+
time.sleep(15)
2934

3035
# Set back to neutral
3136
pwm_array[thruster_num] = 1500
3237
pub.publish(ThrusterMicroseconds(pwm_array))
33-
time.sleep(1.5)
38+
39+
# Sleep for 3.5 seconds when going back to neutral (1500)
40+
time.sleep(15)
3441

3542
# Descending sequence
36-
for pwm in range(1480, 1099, -20):
43+
for pwm in range(1492, 1099, -8): # Changed step to 8
3744
pwm_array[thruster_num] = pwm
3845
pub.publish(ThrusterMicroseconds(pwm_array))
3946
print(f"Sent PWM {pwm} to thruster {thruster_num + 1}")
40-
time.sleep(1.5)
47+
48+
# Sleep for 3.5 seconds if not 1500, otherwise 15 seconds
49+
if pwm != 1500:
50+
time.sleep(3.5)
51+
else:
52+
time.sleep(15)
4153

4254
# Set back to neutral
4355
pwm_array[thruster_num] = 1500
4456
pub.publish(ThrusterMicroseconds(pwm_array))
45-
time.sleep(1.5)
57+
58+
# Sleep for 3.5 seconds when going back to neutral (1500)
59+
time.sleep(15)
4660

4761
print("Thruster test complete.")
48-

0 commit comments

Comments
 (0)