mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Gripper: Add Neutral state after init
This commit is contained in:
parent
7d38164176
commit
7857bb2210
@ -63,6 +63,7 @@ public:
|
|||||||
AP_Int8 _enabled; // grabber enable/disable
|
AP_Int8 _enabled; // grabber enable/disable
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
STATE_NEUTRAL,
|
||||||
STATE_GRABBING,
|
STATE_GRABBING,
|
||||||
STATE_RELEASING,
|
STATE_RELEASING,
|
||||||
STATE_GRABBED,
|
STATE_GRABBED,
|
||||||
@ -78,7 +79,7 @@ public:
|
|||||||
AP_Float autoclose_time; // Automatic close time (in seconds)
|
AP_Float autoclose_time; // Automatic close time (in seconds)
|
||||||
AP_Int16 uavcan_hardpoint_id;
|
AP_Int16 uavcan_hardpoint_id;
|
||||||
|
|
||||||
gripper_state state = STATE_RELEASED;
|
gripper_state state = STATE_NEUTRAL;
|
||||||
} config;
|
} config;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
Loading…
Reference in New Issue
Block a user