mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Gripper: a valid() method
This commit is contained in:
parent
4a1439ca0b
commit
0e2b3781ae
@ -125,6 +125,7 @@ PASS_TO_BACKEND(update)
|
|||||||
return false; \
|
return false; \
|
||||||
}
|
}
|
||||||
|
|
||||||
|
PASS_TO_BACKEND(valid)
|
||||||
PASS_TO_BACKEND(released)
|
PASS_TO_BACKEND(released)
|
||||||
PASS_TO_BACKEND(grabbed)
|
PASS_TO_BACKEND(grabbed)
|
||||||
|
|
||||||
|
@ -44,6 +44,9 @@ public:
|
|||||||
// update - should be called at at least 10hz
|
// update - should be called at at least 10hz
|
||||||
void update();
|
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[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
// parameters
|
// parameters
|
||||||
|
@ -34,6 +34,9 @@ public:
|
|||||||
// release - move the servo output to the release position
|
// release - move the servo output to the release position
|
||||||
virtual void release() = 0;
|
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
|
// released - returns true if currently in released position
|
||||||
virtual bool released() const = 0;
|
virtual bool released() const = 0;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user