AP_Gripper: a valid() method

This commit is contained in:
Peter Barker 2016-11-18 18:52:15 +11:00
parent 4a1439ca0b
commit 0e2b3781ae
3 changed files with 7 additions and 0 deletions

View File

@ -125,6 +125,7 @@ PASS_TO_BACKEND(update)
return false; \
}
PASS_TO_BACKEND(valid)
PASS_TO_BACKEND(released)
PASS_TO_BACKEND(grabbed)

View File

@ -44,6 +44,9 @@ public:
// update - should be called at at least 10hz
void update();
// valid - returns true if we have a gripper and it should work
bool valid() const;
static const struct AP_Param::GroupInfo var_info[];
// parameters

View File

@ -34,6 +34,9 @@ public:
// release - move the servo output to the release position
virtual void release() = 0;
// valid - returns true if the backend should be working
bool valid() const { return true; };
// released - returns true if currently in released position
virtual bool released() const = 0;