mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: Add roll_range_valid() and pitch_range_valid() functions
Equivalent to yaw_range_valid().
This commit is contained in:
parent
7e8f9c72fb
commit
0e090faf05
|
@ -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); }
|
||||
|
|
Loading…
Reference in New Issue