@@ -2402,7 +2402,7 @@ def calibrate_gyro(self):
24022402 """Request gyroscope calibration."""
24032403
24042404 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
24062406 mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
24072407 0 , # confirmation
24082408 1 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
@@ -2418,10 +2418,10 @@ def calibrate_gyro(self):
24182418 def calibrate_magnetometer (self ):
24192419 """Request magnetometer calibration."""
24202420
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
24222422 if self ._autopilot_type == mavutil .mavlink .MAV_AUTOPILOT_ARDUPILOTMEGA :
24232423 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
24252425 mavutil .mavlink .MAV_CMD_DO_START_MAG_CAL , # command
24262426 0 , # confirmation
24272427 0 , # param 1, uint8_t bitmask of magnetometers (0 means all).
@@ -2434,7 +2434,7 @@ def calibrate_magnetometer(self):
24342434 )
24352435 else :
24362436 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
24382438 mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
24392439 0 , # confirmation
24402440 0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
@@ -2449,35 +2449,21 @@ def calibrate_magnetometer(self):
24492449 self ._logger .critical (calibration_command )
24502450 self .send_mavlink (calibration_command )
24512451
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.
24682454
2469- def calibrate_accelerometer_simple ( self ):
2470- """Request simple accelerometer calibration."""
2455+ :param simple: if True, perform simple accelerometer calibration
2456+ """
24712457
24722458 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
24742460 mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
24752461 0 , # confirmation
24762462 0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
24772463 0 , # param 2, 1: magnetometer calibration
24782464 0 , # param 3, 1: ground pressure calibration
24792465 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
24812467 0 , # param 6, 2: airspeed calibration
24822468 0 , # param 7, 1: ESC calibration, 3: barometer temperature calibration
24832469 )
@@ -2487,7 +2473,7 @@ def calibrate_board_level(self):
24872473 """Request board level calibration."""
24882474
24892475 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
24912477 mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
24922478 0 , # confirmation
24932479 0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
@@ -2504,7 +2490,7 @@ def calibrate_barometer(self):
25042490 """Request barometer calibration."""
25052491
25062492 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
25082494 mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION , # command
25092495 0 , # confirmation
25102496 0 , # param 1, 1: gyro calibration, 3: gyro temperature calibration
0 commit comments