forked from 218Drone/multiDrone_Com
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathtest02.py
70 lines (59 loc) · 2.05 KB
/
test02.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
import time
from droneapi.lib import VehicleMode, Location
from pymavlink import mavutil
# First get an instance of the API endpoint
api = local_connect()
# Get the connected vehicle (currently only one vehicle can be returned).
vehicle = api.get_vehicles()[0]
def arm_and_takeoff(aTargetAltitude):
print "Basic pre-arm checks"
if vehicle.mode.name == "INITIALISING":
print "Waiting for vehicle to initialise"
time.sleep(1)
while vehicle.gps_0.fix_type < 2:
print "Waiting for GPS........", vehicle.gps_0.fix_type
time.sleep(1)
print "Arming motors"
vehicle.mode = VehicleMode("GUIDED")
vehicle.armed = True
vehicle.flush()
while not vehicle.armed and not api.exit:
print "Waiting for arming..."
time.sleep(1)
print "Take off!"
vehicle.commands.takeoff(aTargetAltitude)
vehicle.flush()
#Wait until the vehicle reaches a safe height
while not api.exit:
print "Altitude: ", vehicle.location.alt
if vehicle.location.alt >= aTargetAltitude*0.95:
print "Reached target altitude"
break;
time.sleep(1)
# controlling vehicle movement using velocity
def send_ned_velocity(velocity_x, velocity_y, velocity_z):
"""
Move vehicle in direction based on specified velocity vectors.
"""
msg = vehicle.message_factory.set_position_target_local_ned_encode(
0, # time_boot_ms (not used)
0, 0, # target system, target component
mavutil.mavlink.MAV_FRAME_BODY_NED, # frame
0b0000111111000111, # type_mask (only speeds enabled)
0, 0, 0, # x, y, z positions (not used)
velocity_x, velocity_y, velocity_z, # x, y, z velocity in m/s
0, 0, 0, # x, y, z acceleration (not supported yet, ignored in GCS_Mavlink)
0, 0) # yaw, yaw_rate (not supported yet, ignored in GCS_Mavlink)
# send command to vehicle
vehicle.send_mavlink(msg)
vehicle.flush()
arm_and_takeoff(3)
send_ned_velocity(1, 1, 0)
time.sleep(5)
send_ned_velocity(-1, -1, 0)
time.sleep(5)
send_ned_velocity(1.5, 0, 0)
time.sleep(5)
send_ned_velocity(-1.5, 0, 0)
time.sleep(5)
vehicle.mode = VehicleMode("LAND")