From ad094b90734ede243fc98fcaceebe62eab01b371 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 3 Nov 2015 11:46:29 -0200 Subject: [PATCH] AP_Mount: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1 --- libraries/AP_Mount/AP_Mount.cpp | 2 +- libraries/AP_Mount/AP_Mount.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 22ed150ea8..896dff4711 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -583,7 +583,7 @@ MAV_MOUNT_MODE AP_Mount::get_mode(uint8_t instance) const } // set_mode_to_default - restores the mode to it's default mode held in the MNT_MODE parameter -// this operation requires 230us on an APM2, 60us on a Pixhawk/PX4 +// this operation requires 60us on a Pixhawk/PX4 void AP_Mount::set_mode_to_default(uint8_t instance) { set_mode(instance, (enum MAV_MOUNT_MODE)state[instance]._default_mode.get()); diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 017e4ab8c3..3608319ba0 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -102,7 +102,7 @@ public: void set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode); // set_mode_to_default - restores the mode to it's default mode held in the MNT_DEFLT_MODE parameter - // this operation requires 230us on an APM2, 60us on a Pixhawk/PX4 + // this operation requires 60us on a Pixhawk/PX4 void set_mode_to_default() { set_mode_to_default(_primary); } void set_mode_to_default(uint8_t instance);