forked from mustafa-gokce/ardupilot-software-development
-
Notifications
You must be signed in to change notification settings - Fork 1
/
home-get-set.py
96 lines (80 loc) · 4.11 KB
/
home-get-set.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
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
"""
Once the vehicle has valid position after the boot, it immediately set this position as home
Easiest way to wait until get home position is to request it as stream
And stop this stream when it is received
With this way, you don't need request many times until you fetch the home position
Also, 0th index of mission list contains home position
https://mavlink.io/en/messages/common.html#COMMAND_LONG
https://mavlink.io/en/messages/common.html#MAV_CMD_SET_MESSAGE_INTERVAL
https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME
https://mavlink.io/en/messages/common.html#HOME_POSITION
"""
import time
import pymavlink.mavutil as utility
import pymavlink.dialects.v20.all as dialect
# new home location
new_home_location = (-35.36210556, 149.16373661, 583.9)
# connect to vehicle
vehicle = utility.mavlink_connection(device="udpin:127.0.0.1:14560")
# wait for a heartbeat
vehicle.wait_heartbeat()
# inform user
print("Connected to system:", vehicle.target_system, ", component:", vehicle.target_component)
"""
# create home position request message
command = dialect.MAVLink_command_long_message(target_system=vehicle.target_system,
target_component=vehicle.target_component,
command=dialect.MAV_CMD_SET_MESSAGE_INTERVAL,
confirmation=0,
param1=dialect.MAVLINK_MSG_ID_HOME_POSITION,
param2=1e6,
param3=0,
param4=0,
param5=0,
param6=0,
param7=0)
# send command to the vehicle
vehicle.mav.send(command)
"""
# create set home position command
command = dialect.MAVLink_command_long_message(target_system=vehicle.target_system,
target_component=vehicle.target_component,
command=dialect.MAV_CMD_DO_SET_HOME,
confirmation=0,
param1=0,
param2=0,
param3=0,
param4=0,
param5=new_home_location[0],
param6=new_home_location[1],
param7=new_home_location[2])
# send command to the vehicle
vehicle.mav.send(command)
# infinite loop
while True:
# get HOME_POSITION message
message = vehicle.recv_match(type=dialect.MAVLink_home_position_message.msgname,
blocking=True)
# convert this message to dictionary
message = message.to_dict()
# debug the message
print("Home Position >",
"Latitude:", message["latitude"] * 1e-7,
"Longitude:", message["longitude"] * 1e-7,
"Altitude:", message["altitude"] * 1e-3)
"""
# disable HOME_POSITION message stream
command = dialect.MAVLink_command_long_message(target_system=vehicle.target_system,
target_component=vehicle.target_component,
command=dialect.MAV_CMD_SET_MESSAGE_INTERVAL,
confirmation=0,
param1=dialect.MAVLINK_MSG_ID_HOME_POSITION,
param2=-1,
param3=0,
param4=0,
param5=0,
param6=0,
param7=0)
# send command to the vehicle
vehicle.mav.send(command)
"""