@@ -2402,7 +2402,7 @@ def calibrate_gyro(self):
2402
2402
"""Request gyroscope calibration."""
2403
2403
2404
2404
calibration_command = self .message_factory .command_long_encode (
2405
- 0 , 0 , # target_system, target_component
2405
+ self . _handler . target_system , 0 , # target_system, target_component
2406
2406
mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
2407
2407
0 , # confirmation
2408
2408
1 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
@@ -2418,10 +2418,10 @@ def calibrate_gyro(self):
2418
2418
def calibrate_magnetometer (self ):
2419
2419
"""Request magnetometer calibration."""
2420
2420
2421
- # APM requires the MAV_CMD_DO_START_MAG_CAL command, only present in the APM MAVLink dialect
2421
+ # ArduPilot requires the MAV_CMD_DO_START_MAG_CAL command, only present in the ardupilotmega.xml definition
2422
2422
if self ._autopilot_type == mavutil .mavlink .MAV_AUTOPILOT_ARDUPILOTMEGA :
2423
2423
calibration_command = self .message_factory .command_long_encode (
2424
- 0 , 0 , # target_system, target_component
2424
+ self . _handler . target_system , 0 , # target_system, target_component
2425
2425
mavutil .mavlink .MAV_CMD_DO_START_MAG_CAL , # command
2426
2426
0 , # confirmation
2427
2427
0 , # param 1, uint8_t bitmask of magnetometers (0 means all).
@@ -2434,7 +2434,7 @@ def calibrate_magnetometer(self):
2434
2434
)
2435
2435
else :
2436
2436
calibration_command = self .message_factory .command_long_encode (
2437
- 0 , 0 , # target_system, target_component
2437
+ self . _handler . target_system , 0 , # target_system, target_component
2438
2438
mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
2439
2439
0 , # confirmation
2440
2440
0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
@@ -2449,35 +2449,21 @@ def calibrate_magnetometer(self):
2449
2449
self ._logger .critical (calibration_command )
2450
2450
self .send_mavlink (calibration_command )
2451
2451
2452
- def calibrate_accelerometer (self ):
2453
- """Request accelerometer calibration."""
2454
-
2455
- calibration_command = self .message_factory .command_long_encode (
2456
- 0 , 0 , # target_system, target_component
2457
- mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
2458
- 0 , # confirmation
2459
- 0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
2460
- 0 , # param 2, 1: magnetometer calibration
2461
- 0 , # param 3, 1: ground pressure calibration
2462
- 0 , # param 4, 1: radio RC calibration, 2: RC trim calibration
2463
- 1 , # param 5, 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration
2464
- 0 , # param 6, 2: airspeed calibration
2465
- 0 , # param 7, 1: ESC calibration, 3: barometer temperature calibration
2466
- )
2467
- self .send_mavlink (calibration_command )
2452
+ def calibrate_accelerometer (self , simple = False ):
2453
+ """Request accelerometer calibration.
2468
2454
2469
- def calibrate_accelerometer_simple ( self ):
2470
- """Request simple accelerometer calibration."""
2455
+ :param simple: if True, perform simple accelerometer calibration
2456
+ """
2471
2457
2472
2458
calibration_command = self .message_factory .command_long_encode (
2473
- 0 , 0 , # target_system, target_component
2459
+ self . _handler . target_system , 0 , # target_system, target_component
2474
2460
mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
2475
2461
0 , # confirmation
2476
2462
0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
2477
2463
0 , # param 2, 1: magnetometer calibration
2478
2464
0 , # param 3, 1: ground pressure calibration
2479
2465
0 , # param 4, 1: radio RC calibration, 2: RC trim calibration
2480
- 4 , # param 5, 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration
2466
+ 4 if simple else 1 , # param 5, 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration
2481
2467
0 , # param 6, 2: airspeed calibration
2482
2468
0 , # param 7, 1: ESC calibration, 3: barometer temperature calibration
2483
2469
)
@@ -2487,7 +2473,7 @@ def calibrate_board_level(self):
2487
2473
"""Request board level calibration."""
2488
2474
2489
2475
calibration_command = self .message_factory .command_long_encode (
2490
- 0 , 0 , # target_system, target_component
2476
+ self . _handler . target_system , 0 , # target_system, target_component
2491
2477
mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
2492
2478
0 , # confirmation
2493
2479
0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
@@ -2504,7 +2490,7 @@ def calibrate_barometer(self):
2504
2490
"""Request barometer calibration."""
2505
2491
2506
2492
calibration_command = self .message_factory .command_long_encode (
2507
- 0 , 0 , # target_system, target_component
2493
+ self . _handler . target_system , 0 , # target_system, target_component
2508
2494
mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
2509
2495
0 , # confirmation
2510
2496
0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
0 commit comments