Skip to content

Commit

Permalink
fix up mavlink controller
Browse files Browse the repository at this point in the history
  • Loading branch information
misko committed Mar 4, 2024
1 parent d80f9c2 commit 6dc8380
Showing 1 changed file with 9 additions and 6 deletions.
15 changes: 9 additions & 6 deletions spf/mavlink/mavlink_controller.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
# Import mavutil
import argparse
import subprocess
import glob
import logging
import math
Expand Down Expand Up @@ -161,7 +162,7 @@ def __init__(self, connection, planner, boundary, tolerance_in_m=5):
"POSITION_TARGET_GLOBAL_INT",
"POWER_STATUS",
"RAW_IMU",
"RC_CHANNELS",
#"RC_CHANNELS",
"RC_CHANNELS_SCALED",
"SCALED_IMU2",
"SCALED_IMU3",
Expand Down Expand Up @@ -250,9 +251,7 @@ def run_planner(self):
logging.info("DRONE IS READY TO ROLL")

for point in self.boundary:
self.single_operation_mode_on()
self.move_to_point(point)
self.single_operation_mode_off()
self.move_to_point(self.boundary[0])

self.move_to_point(home)
Expand Down Expand Up @@ -539,6 +538,10 @@ def process_message(self, msg):
# msg.seq,
# )
pass
elif msg.get_type() == "RC_CHANNELS":
print(msg.to_dict())
if msg.chan9_raw>1500:
subprocess.run(["sudo", "shutdown", "0"])
elif msg.get_type() in self.ignore_messages:
pass
else:
Expand Down Expand Up @@ -615,7 +618,6 @@ def set_mode(self, mode):

# do_mission(connection)

time.sleep(1)

# connection.set_mode_auto() # MAV_CMD_MISSION_START

Expand All @@ -627,8 +629,9 @@ def set_mode(self, mode):
# connection.motors_armed_wait()
# logging.info("Armed!")

time.sleep(20)
logging.info(f"MODE {drone.mav_mode}")
while True:
time.sleep(200)
#logging.info(f"MODE {drone.mav_mode}")

# logging.info("DONE")
# drone.process_messages()

0 comments on commit 6dc8380

Please sign in to comment.