APM:Libraries
AP_Gripper.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #pragma once
17 
18 #include <AP_Param/AP_Param.h>
19 
20 class AP_Gripper_Backend;
21 
22 class AP_Gripper {
23 public:
24  AP_Gripper();
25 
26  // indicate whether this module is enabled or not
27  bool enabled() const { return _enabled; }
28 
29  // initialise the gripper
30  void init();
31 
32  // grab - move the servo to the grab position
33  void grab();
34 
35  // release - move the servo output to the release position
36  void release();
37 
38  // released - returns true if currently in released position
39  bool released() const;
40 
41  // grabbed - returns true if currently in grabbed position
42  bool grabbed() const;
43 
44  // update - should be called at at least 10hz
45  void update();
46 
47  // valid - returns true if we have a gripper and it should work
48  bool valid() const;
49 
50  static const struct AP_Param::GroupInfo var_info[];
51 
52  // parameters
53  AP_Int8 _enabled; // grabber enable/disable
54 
55  typedef enum {
60  } gripper_state;
61 
62  struct Backend_Config {
63  AP_Int8 type; // grabber type (e.g. EPM or servo)
64  AP_Int16 grab_pwm; // PWM value sent to Gripper to initiate grabbing the cargo
65  AP_Int16 release_pwm; // PWM value sent to Gripper to release the cargo
66  AP_Int16 neutral_pwm; // PWM value sent to gripper when not grabbing or releasing
67  AP_Int8 regrab_interval; // Time in seconds that gripper will regrab the cargo to ensure grip has not weakend
69 
70  gripper_state state = STATE_RELEASED;
71  } config;
72 
73 private:
74 
76 };
bool enabled() const
Definition: AP_Gripper.h:27
bool valid() const
bool grabbed() const
void release()
void grab()
A system for managing and storing variables that are of general interest to the system.
AP_Int8 _enabled
Definition: AP_Gripper.h:53
AP_Gripper_Backend * backend
Definition: AP_Gripper.h:75
struct AP_Gripper::Backend_Config config
void init()
Definition: AP_Gripper.cpp:76
bool released() const
void update()
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Gripper.h:50