forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathexample2.py
52 lines (34 loc) · 1.37 KB
/
example2.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
import clr
import MissionPlanner
clr.AddReference("MAVLink")
from System import Byte
from System import Func
import MAVLink
from MAVLink import mavlink_command_long_t
import MAVLink
print 'Start Script'
def OtherMethod(message):
print "got HB";
print dir(message.data)
return True
sub = MAV.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.HEARTBEAT.value__, Func[MAVLink.MAVLinkMessage, bool] (OtherMethod))
#MAV.UnSubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.HEARTBEAT.value__, sub);
MAV.doCommand(MAVLink.MAV_CMD.DO_DIGICAM_CONTROL, 0, 0, 0, 0, 0, 0, 0);
MAV.doCommand(MAVLink.MAV_CMD.DO_DIGICAM_CONTROL, MAVLink.MAV_MOUNT_MODE.NEUTRAL.value__, 0, 0, 0, 0, 0, 0);
MAV.setDigicamControl(True);
MAV.doARM(True);
#MAV.doReboot(False);
MAV.setWPCurrent(MAV.sysidcurrent, MAV.compidcurrent, 1);
MAV.GetParam("PARAMNAME");
MAV.setParam("PARM",1.0);
MAV.getWPCount();
MAV.getWP(1);
MAV.getParamList();
commandlong = mavlink_command_long_t()
mavlink_command_long_t.target_system.SetValue(commandlong,71)
mavlink_command_long_t.target_component.SetValue(commandlong,67)
mavlink_command_long_t.param1.SetValue(commandlong, MAVLink.MAV_MOUNT_MODE.NEUTRAL.value__)
mavlink_command_long_t.command.SetValue(commandlong, MAVLink.MAV_CMD.DO_DIGICAM_CONTROL.value__)
# command , target sysid, target compid used to keep track of the remote state
MAV.sendPacket(commandlong, 71, 67)