mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Motors: bug fix to reached_limits so by default it returns true if any limits have been breached
This commit is contained in:
parent
efb46ca2ad
commit
d74636b980
@ -55,6 +55,7 @@
|
||||
#define AP_MOTOR_ROLLPITCH_LIMIT 0x01
|
||||
#define AP_MOTOR_YAW_LIMIT 0x02
|
||||
#define AP_MOTOR_THROTTLE_LIMIT 0x04
|
||||
#define AP_MOTOR_ANY_LIMIT 0xFF
|
||||
|
||||
/// @class AP_Motors
|
||||
class AP_Motors {
|
||||
@ -127,7 +128,7 @@ public:
|
||||
};
|
||||
|
||||
// reached_limits - return whether we hit the limits of the motors
|
||||
virtual uint8_t reached_limit( uint8_t which_limit = 0x00 ) {
|
||||
virtual uint8_t reached_limit( uint8_t which_limit = AP_MOTOR_ANY_LIMIT ) {
|
||||
return _reached_limit & which_limit;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user