Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Replace quad with hex to support hexacopter #241

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,4 +10,4 @@ install:
- pip3 install tox-travis

script:
- tox -e lint,vtol -c tox.ini
- tox -e lint,hex -c tox.ini
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1 +1 @@
[![Build Status](https://travis-ci.com/NGCP/VTOL.svg?token=pzpV4AQm2iKJkxHKKsEz&branch=master)](https://travis-ci.com/NGCP/VTOL)
[![Build Status](https://travis-ci.com/NGCP/HEX.svg?token=pzpV4AQm2iKJkxHKKsEz&branch=master)](https://travis-ci.com/NGCP/HEX)
36 changes: 18 additions & 18 deletions archives/detailed_search_autonomy.py
Original file line number Diff line number Diff line change
Expand Up @@ -80,43 +80,43 @@ def orbit_poi(vehicle, poi, configs):
waypoints.append(LocationGlobalRelative(lat, lon, alt))

# Go to center of POI
if (configs["vehicle_type"] == "VTOL"):
if (configs["vehicle_type"] == "HEX"):
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0,
0, waypoint_tolerance, 0, 0, poi.lat, poi.lon, poi_scan_altitude))

elif (configs["vehicle_type"] == "Quadcopter"):
elif (configs["vehicle_type"] == "Hexcopter"):
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0,
0, 0, 0, 0, poi.lat, poi.lon, poi_scan_altitude))

# Transition to quadcopter if applicable
if (configs["vehicle_type"] == "VTOL"):
# Transition to hexcopter if applicable
if (configs["vehicle_type"] == "HEX"):
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_DO_HEX_TRANSITION,
0, 0,
mavutil.mavlink.MAV_VTOL_STATE_MC, 0, 0, 0, 0, 0, 0))
mavutil.mavlink.MAV_HEX_STATE_MC, 0, 0, 0, 0, 0, 0))

# Circular waypoints
if (configs["vehicle_type"] == "VTOL"):
if (configs["vehicle_type"] == "HEX"):
for point in waypoints:
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0,
0,
waypoint_tolerance, 0, 0, 0, point.lat, point.lon, point.alt))
elif (configs["vehicle_type"] == "Quadcopter"):
elif (configs["vehicle_type"] == "Hexcopter"):
for point in waypoints:
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0,
0,
0, 0, 0, 0, point.lat, point.lon, point.alt))

# Transition to forward flight if applicable
if (configs["vehicle_type"] == "VTOL"):
if (configs["vehicle_type"] == "HEX"):
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_DO_HEX_TRANSITION,
0, 0,
mavutil.mavlink.MAV_VTOL_STATE_MC, 0, 0, 0, 0, 0, 0))
mavutil.mavlink.MAV_HEX_STATE_MC, 0, 0, 0, 0, 0, 0))

# Add dummy endpoint
cmds.add(
Expand All @@ -139,15 +139,15 @@ def detailed_search_adds_mission(configs, vehicle):
cmds.clear()

# Due to a bug presumed to be the fault of DroneKit, the first command is ignored. Thus we have two takeoff commands
if (configs["vehicle_type"] == "VTOL"):
# Separate MAVlink message for a VTOL takeoff. This takes off to altitude and transitions
if (configs["vehicle_type"] == "HEX"):
# Separate MAVlink message for a HEX takeoff. This takes off to altitude and transitions
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF, 0,
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_HEX_TAKEOFF, 0,
0, 0, 0, 0, 0, 0, 0, altitude))
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF, 0,
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_HEX_TAKEOFF, 0,
0, 0, 0, 0, 0, 0, 0, altitude))
elif (configs["vehicle_type"] == "Quadcopter"):
elif (configs["vehicle_type"] == "Hexcopter"):
cmds.add(
Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0,
0, 0, 0, 0, 0, 0, altitude))
Expand Down Expand Up @@ -233,9 +233,9 @@ def detailed_search_autonomy(configs, autonomyToCV, GCS_TIMESTAMP, CONNECTION_TI

# Holds the copter in place if receives pause
if autonomy.PAUSE_MISSION:
if (configs["vehicle_type"] == "VTOL"):
if (configs["vehicle_type"] == "HEX"):
vehicle.mode = VehicleMode("QHOVER")
elif (configs["vehicle_type"] == "Quadcopter"):
elif (configs["vehicle_type"] == "Hexcopter"):
vehicle.mode = VehicleMode("ALT_HOLD")
change_status("paused")

Expand Down
4 changes: 2 additions & 2 deletions archives/executable_picker.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
'''
The GCS allocates roles to vehicles. The purpose of this program is to connect to the GCS and then
read a start message from the GCS, which contains a certain job_type. It then runs the
corresponding VTOL program (quick scan, detailed search, guide) based on the start message.
corresponding HEX program (quick scan, detailed search, guide) based on the start message.
'''
import sys
import json
import time
from util import parse_configs, new_output_file
from autonomy import VTOL
from autonomy import HEX
import autonomy

XBEE = None
Expand Down
18 changes: 9 additions & 9 deletions archives/quick_scan_autonomy.py
Original file line number Diff line number Diff line change
Expand Up @@ -160,12 +160,12 @@ def quick_scan_adds_mission(configs, vehicle, lla_waypoint_list):
print(" Define/add new commands.")

# Due to a bug presumed to be the fault of DroneKit, the first command is ignored. Thus we have two takeoff commands
if (configs["vehicle_type"] == "VTOL"):
# Separate MAVlink message for a VTOL takeoff. This takes off to altitude and transitions
cmds.add(Command( 0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, 0, altitude))
cmds.add(Command( 0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, 0, altitude))
if (configs["vehicle_type"] == "HEX"):
# Separate MAVlink message for a HEX takeoff. This takes off to altitude and transitions
cmds.add(Command( 0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_HEX_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, 0, altitude))
cmds.add(Command( 0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_HEX_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, 0, altitude))

elif (configs["vehicle_type"] == "Quadcopter"):
elif (configs["vehicle_type"] == "Hexcopter"):
cmds.add(Command( 0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, 0, altitude))
cmds.add(Command( 0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, 0, altitude))

Expand All @@ -174,15 +174,15 @@ def quick_scan_adds_mission(configs, vehicle, lla_waypoint_list):
0, configs["air_speed"], -1, 0, 0, 0, 0))

# Add waypoints to the auto mission
if (configs["vehicle_type"] == "VTOL"):
if (configs["vehicle_type"] == "HEX"):
for point in lla_waypoint_list:
# Planes need a waypoint tolerance
cmds.add(Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0,
0, configs["waypoint_tolerance"], 0, 0, point.lat, point.lon, point.alt))
# Adds dummy end point - this endpoint is the same as the last waypoint and lets us know we have reached destination.
cmds.add(Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0,
0, configs["waypoint_tolerance"], 0, 0, lla_waypoint_list[-1].lat, lla_waypoint_list[-1].lon, lla_waypoint_list[-1].alt))
elif (configs["vehicle_type"] == "Quadcopter"):
elif (configs["vehicle_type"] == "Hexcopter"):
for point in lla_waypoint_list:
cmds.add(Command(0, 0, 0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0,
0, 0, 0, 0, point.lat, point.lon, point.alt))
Expand Down Expand Up @@ -259,9 +259,9 @@ def quick_scan_autonomy(configs, autonomyToCV, GCS_TIMESTAMP, CONNECTION_TIMESTA
time.sleep(1)
# Holds the copter in place if receives pause
if autonomy.PAUSE_MISSION:
if (configs["vehicle_type"] == "VTOL"):
if (configs["vehicle_type"] == "HEX"):
vehicle.mode = VehicleMode("QHOVER")
elif (configs["vehicle_type"] == "Quadcopter"):
elif (configs["vehicle_type"] == "Hexcopter"):
vehicle.mode = VehicleMode("ALT_HOLD")
# Lands the vehicle if receives stop mission
elif autonomy.STOP_MISSION:
Expand Down
2 changes: 1 addition & 1 deletion simulator/sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
if DO_DOWNLOAD:
SIM.download('copter', '3.3', verbose=False)

SIM.launch(['--model', 'quad', ], await_ready=True, restart=False)
SIM.launch(['--model', 'hex', ], await_ready=True, restart=False)
print("Simulator lanched")

while True:
Expand Down
6 changes: 3 additions & 3 deletions src/quad.py → src/hex.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
"""Automous tools for VTOL"""
"""Automous tools for HEX"""
import time
import json
from dronekit import VehicleMode, Vehicle, LocationGlobalRelative
from coms import Coms
from util import get_distance_metres


class QUAD(Vehicle):
""" VTOL basic state isolated"""
class HEX(Vehicle):
""" HEX basic state isolated"""

coms = None

Expand Down
12 changes: 7 additions & 5 deletions src/main.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,15 @@
"""main executable for setting up VTOL"""
"""main executable for setting up HEX"""
import json
from util import setup_vehicle
from quad import QUAD
from hex import HEX


def main(configs):
"""Configure vtol and ready for mission"""
quad = setup_vehicle(configs, QUAD)
quad.land()
"""Configure hexcopter and ready for mission"""
hexa = setup_vehicle(configs, HEX)
hexa.takeoff()
hexa.go_to(27.28, 153.01)
hexa.land()


if __name__ == "__main__":
Expand Down
10 changes: 5 additions & 5 deletions src/tests/test_quad.py → src/tests/test_hex.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
"""test for vtol.py"""
"""test for hex.py"""
from dronekit_sitl import start_default
from util import setup_vehicle
from quad import QUAD
from hex import HEX

CONFIGS = {
"vehicle_simulated": True,
Expand All @@ -16,19 +16,19 @@
CON_STR = start_default().connection_string()

with open("configs.json", "r") as data:
VEHICLE = setup_vehicle(CONFIGS, QUAD)
VEHICLE = setup_vehicle(CONFIGS, HEX)


def test_takeoff():
"""quadcopter dronekit-sitl takeoff"""
"""hexcopter dronekit-sitl takeoff"""
global VEHICLE # pylint: disable=global-statement
VEHICLE.takeoff()
alt = VEHICLE.location.global_relative_frame.alt
assert 4 < alt < 6, "vehicle did not reach target alt"


def test_land():
"""quadcopter dronekit-sitl land"""
"""hexcopter dronekit-sitl land"""
global VEHICLE # pylint: disable=global-statement
VEHICLE.land()
alt = VEHICLE.location.global_relative_frame.alt
Expand Down
4 changes: 2 additions & 2 deletions src/util.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
"""Util methods for VTOL"""
"""Util methods for HEX"""
import json
import datetime
import subprocess
Expand All @@ -10,7 +10,7 @@


def setup_vehicle(configs, v_type):
"""Sets up self as a quadplane vehicle"""
"""Sets up self as a hexcopter vehicle"""
v_type = partial(v_type, configs)
veh = scan_ports(configs, v_type)
return veh
Expand Down
4 changes: 2 additions & 2 deletions tox.ini
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[tox]
minversion = 2.0
envlist = lint, vtol
envlist = lint, hex
skipsdist = True

[testenv]
Expand All @@ -13,6 +13,6 @@ passenv = *
basepython=python3.7
commands=pylint --rcfile=.pylintrc src

[testenv:vtol]
[testenv:hex]
basepython=python3.7
commands = python3 -m pytest