magtest.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 rotate APMs on bench to test magnetometers
5 
6 '''
7 from __future__ import print_function
8 
9 import time
10 from math import radians
11 
12 from pymavlink import mavutil
13 
14 from argparse import ArgumentParser
15 parser = ArgumentParser(description=__doc__)
16 
17 parser.add_argument("--device1", required=True, help="mavlink device1")
18 parser.add_argument("--device2", required=True, help="mavlink device2")
19 parser.add_argument("--baudrate", type=int,
20  help="master port baud rate", default=115200)
21 args = parser.parse_args()
22 
23 def set_attitude(rc3, rc4):
24  global mav1, mav2
25  values = [ 65535 ] * 8
26  values[2] = rc3
27  values[3] = rc4
28  mav1.mav.rc_channels_override_send(mav1.target_system, mav1.target_component, *values)
29  mav2.mav.rc_channels_override_send(mav2.target_system, mav2.target_component, *values)
30 
31 
32 # create a mavlink instance
33 mav1 = mavutil.mavlink_connection(args.device1, baud=args.baudrate)
34 
35 # create a mavlink instance
36 mav2 = mavutil.mavlink_connection(args.device2, baud=args.baudrate)
37 
38 print("Waiting for HEARTBEAT")
39 mav1.wait_heartbeat()
40 mav2.wait_heartbeat()
41 print("Heartbeat from APM (system %u component %u)" % (mav1.target_system, mav1.target_system))
42 print("Heartbeat from APM (system %u component %u)" % (mav2.target_system, mav2.target_system))
43 
44 print("Waiting for MANUAL mode")
45 mav1.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True)
46 mav2.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True)
47 
48 print("Setting declination")
49 mav1.mav.param_set_send(mav1.target_system, mav1.target_component,
50  'COMPASS_DEC', radians(12.33))
51 mav2.mav.param_set_send(mav2.target_system, mav2.target_component,
52  'COMPASS_DEC', radians(12.33))
53 
54 
55 set_attitude(1060, 1160)
56 
59 rc3_min = 1060
60 rc3_max = 1850
61 rc4_min = 1080
62 rc4_max = 1500
63 rc3 = rc3_min
64 rc4 = 1160
65 delta3 = 2
66 delta4 = 1
67 use_pitch = 1
68 
69 MAV_ACTION_CALIBRATE_GYRO = 17
70 mav1.mav.action_send(mav1.target_system, mav1.target_component, MAV_ACTION_CALIBRATE_GYRO)
71 mav2.mav.action_send(mav2.target_system, mav2.target_component, MAV_ACTION_CALIBRATE_GYRO)
72 
73 print("Waiting for gyro calibration")
74 mav1.recv_match(type='ACTION_ACK')
75 mav2.recv_match(type='ACTION_ACK')
76 
77 print("Resetting mag offsets")
78 mav1.mav.set_mag_offsets_send(mav1.target_system, mav1.target_component, 0, 0, 0)
79 mav2.mav.set_mag_offsets_send(mav2.target_system, mav2.target_component, 0, 0, 0)
80 
81 def TrueHeading(SERVO_OUTPUT_RAW):
82  p = float(SERVO_OUTPUT_RAW.servo3_raw - rc3_min) / (rc3_max - rc3_min)
83  return 172 + p*(326 - 172)
84 
85 while True:
86  mav1.recv_msg()
87  mav2.recv_msg()
88  if event.trigger():
89  if not use_pitch:
90  rc4 = 1160
91  set_attitude(rc3, rc4)
92  rc3 += delta3
93  if rc3 > rc3_max or rc3 < rc3_min:
94  delta3 = -delta3
95  use_pitch ^= 1
96  rc4 += delta4
97  if rc4 > rc4_max or rc4 < rc4_min:
98  delta4 = -delta4
99  if pevent.trigger():
100  print("hdg1: %3u hdg2: %3u ofs1: %4u, %4u, %4u ofs2: %4u, %4u, %4u" % (
101  mav1.messages['VFR_HUD'].heading,
102  mav2.messages['VFR_HUD'].heading,
103  mav1.messages['SENSOR_OFFSETS'].mag_ofs_x,
104  mav1.messages['SENSOR_OFFSETS'].mag_ofs_y,
105  mav1.messages['SENSOR_OFFSETS'].mag_ofs_z,
106  mav2.messages['SENSOR_OFFSETS'].mag_ofs_x,
107  mav2.messages['SENSOR_OFFSETS'].mag_ofs_y,
108  mav2.messages['SENSOR_OFFSETS'].mag_ofs_z,
109  ))
110  time.sleep(0.01)
111 
112 # 314M 326G
113 # 160M 172G
114 


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02