diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 39a784ddb5..07ccd09663 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -244,6 +244,14 @@ protected: }; bool option_set(Options opt) const { return (_params.options.get() & (uint8_t)opt) != 0; } + // returns true if user has configured a valid roll angle range + // allows user to disable roll even on 3-axis gimbal + bool roll_range_valid() const { return (_params.roll_angle_min < _params.roll_angle_max); } + + // returns true if user has configured a valid pitch angle range + // allows user to disable pitch even on 3-axis gimbal + bool pitch_range_valid() const { return (_params.pitch_angle_min < _params.pitch_angle_max); } + // returns true if user has configured a valid yaw angle range // allows user to disable yaw even on 3-axis gimbal bool yaw_range_valid() const { return (_params.yaw_angle_min < _params.yaw_angle_max); }