1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586 |
- #pragma once
- #include <AP_Param/AP_Param.h>
- class AP_Gripper_Backend;
- class AP_Gripper {
- public:
- AP_Gripper();
- AP_Gripper(const AP_Gripper &other) = delete;
- AP_Gripper &operator=(const AP_Gripper&) = delete;
- static AP_Gripper *get_singleton();
- static AP_Gripper *_singleton;
-
- bool enabled() const { return _enabled; }
-
- void init();
-
- void grab();
-
- void release();
-
- bool released() const;
-
- bool grabbed() const;
-
- void update();
-
- bool valid() const;
- static const struct AP_Param::GroupInfo var_info[];
-
- AP_Int8 _enabled;
- typedef enum {
- STATE_GRABBING,
- STATE_RELEASING,
- STATE_GRABBED,
- STATE_RELEASED,
- } gripper_state;
- struct Backend_Config {
- AP_Int8 type;
- AP_Int16 grab_pwm;
- AP_Int16 release_pwm;
- AP_Int16 neutral_pwm;
- AP_Int8 regrab_interval;
- AP_Int16 uavcan_hardpoint_id;
- gripper_state state = STATE_RELEASED;
- } config;
- private:
- AP_Gripper_Backend *backend;
- };
- namespace AP {
- AP_Gripper *gripper();
- };
|