mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1
This commit is contained in:
parent
3941bb7347
commit
ad094b9073
@ -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());
|
||||
|
@ -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);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user