Browse Source

AP_Gripper: a valid() method

master
Peter Barker 8 years ago
parent
commit
0e2b3781ae
  1. 1
      libraries/AP_Gripper/AP_Gripper.cpp
  2. 3
      libraries/AP_Gripper/AP_Gripper.h
  3. 3
      libraries/AP_Gripper/AP_Gripper_Backend.h

1
libraries/AP_Gripper/AP_Gripper.cpp

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

3
libraries/AP_Gripper/AP_Gripper.h

@ -44,6 +44,9 @@ public: @@ -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

3
libraries/AP_Gripper/AP_Gripper_Backend.h

@ -34,6 +34,9 @@ public: @@ -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;

Loading…
Cancel
Save