Skip to content

Commit c3cfa7f

Browse files
pietrodnpeterbarker
authored andcommitted
Rename "calibrate_*" to "send_calibrate_*" (non-blocking methods)
1 parent e4314de commit c3cfa7f

File tree

2 files changed

+11
-11
lines changed

2 files changed

+11
-11
lines changed

dronekit/__init__.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -2398,7 +2398,7 @@ def reboot(self):
23982398

23992399
self.send_mavlink(reboot_msg)
24002400

2401-
def calibrate_gyro(self):
2401+
def send_calibrate_gyro(self):
24022402
"""Request gyroscope calibration."""
24032403

24042404
calibration_command = self.message_factory.command_long_encode(
@@ -2415,7 +2415,7 @@ def calibrate_gyro(self):
24152415
)
24162416
self.send_mavlink(calibration_command)
24172417

2418-
def calibrate_magnetometer(self):
2418+
def send_calibrate_magnetometer(self):
24192419
"""Request magnetometer calibration."""
24202420

24212421
# ArduPilot requires the MAV_CMD_DO_START_MAG_CAL command, only present in the ardupilotmega.xml definition
@@ -2448,7 +2448,7 @@ def calibrate_magnetometer(self):
24482448

24492449
self.send_mavlink(calibration_command)
24502450

2451-
def calibrate_accelerometer(self, simple=False):
2451+
def send_calibrate_accelerometer(self, simple=False):
24522452
"""Request accelerometer calibration.
24532453
24542454
:param simple: if True, perform simple accelerometer calibration
@@ -2468,7 +2468,7 @@ def calibrate_accelerometer(self, simple=False):
24682468
)
24692469
self.send_mavlink(calibration_command)
24702470

2471-
def calibrate_vehicle_level(self):
2471+
def send_calibrate_vehicle_level(self):
24722472
"""Request vehicle level (accelerometer trim) calibration."""
24732473

24742474
calibration_command = self.message_factory.command_long_encode(
@@ -2485,7 +2485,7 @@ def calibrate_vehicle_level(self):
24852485
)
24862486
self.send_mavlink(calibration_command)
24872487

2488-
def calibrate_barometer(self):
2488+
def send_calibrate_barometer(self):
24892489
"""Request barometer calibration."""
24902490

24912491
calibration_command = self.message_factory.command_long_encode(

dronekit/test/sitl/test_sensor_calibration.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ def test_gyro_calibration(connpath):
1313
vehicle = connect(connpath, wait_ready=True)
1414

1515
with assert_command_ack(vehicle, mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, timeout=30):
16-
vehicle.calibrate_gyro()
16+
vehicle.send_calibrate_gyro()
1717

1818
vehicle.close()
1919

@@ -30,7 +30,7 @@ def test_magnetometer_calibration(connpath):
3030
timeout=30,
3131
ack_result=mavutil.mavlink.MAV_RESULT_UNSUPPORTED, # TODO: change when APM is upgraded
3232
):
33-
vehicle.calibrate_magnetometer()
33+
vehicle.send_calibrate_magnetometer()
3434

3535
vehicle.close()
3636

@@ -47,7 +47,7 @@ def test_simple_accelerometer_calibration(connpath):
4747
timeout=30,
4848
ack_result=mavutil.mavlink.MAV_RESULT_FAILED,
4949
):
50-
vehicle.calibrate_accelerometer(simple=True)
50+
vehicle.send_calibrate_accelerometer(simple=True)
5151

5252
vehicle.close()
5353

@@ -66,7 +66,7 @@ def test_accelerometer_calibration(connpath):
6666
timeout=30,
6767
ack_result=mavutil.mavlink.MAV_RESULT_FAILED,
6868
):
69-
vehicle.calibrate_accelerometer(simple=False)
69+
vehicle.send_calibrate_accelerometer(simple=False)
7070

7171
vehicle.close()
7272

@@ -78,7 +78,7 @@ def test_board_level_calibration(connpath):
7878
vehicle = connect(connpath, wait_ready=True)
7979

8080
with assert_command_ack(vehicle, mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, timeout=30):
81-
vehicle.calibrate_vehicle_level()
81+
vehicle.send_calibrate_vehicle_level()
8282

8383
vehicle.close()
8484

@@ -90,6 +90,6 @@ def test_barometer_calibration(connpath):
9090
vehicle = connect(connpath, wait_ready=True)
9191

9292
with assert_command_ack(vehicle, mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, timeout=30):
93-
vehicle.calibrate_barometer()
93+
vehicle.send_calibrate_barometer()
9494

9595
vehicle.close()

0 commit comments

Comments
 (0)