From 1eec264d6c395295a20a0692f17690c678cb3564 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 23 Oct 2018 15:57:01 +1100 Subject: [PATCH] Copter: mission library handles gripper --- ArduCopter/mode.h | 3 --- ArduCopter/mode_auto.cpp | 28 ---------------------------- 2 files changed, 31 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 3770281089..e609c2eb5d 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -378,9 +378,6 @@ private: #if PARACHUTE == ENABLED void do_parachute(const AP_Mission::Mission_Command& cmd); #endif -#if GRIPPER_ENABLED == ENABLED - void do_gripper(const AP_Mission::Mission_Command& cmd); -#endif #if WINCH_ENABLED == ENABLED void do_winch(const AP_Mission::Mission_Command& cmd); #endif diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index fa2561c333..cf33034fca 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -519,12 +519,6 @@ bool Copter::ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) break; #endif -#if GRIPPER_ENABLED == ENABLED - case MAV_CMD_DO_GRIPPER: // Mission command to control gripper - do_gripper(cmd); - break; -#endif - #if NAV_GUIDED == ENABLED case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits do_guided_limits(cmd); @@ -714,7 +708,6 @@ bool Copter::ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_DO_DIGICAM_CONTROL: case MAV_CMD_DO_SET_CAM_TRIGG_DIST: case MAV_CMD_DO_PARACHUTE: // assume parachute was released successfully - case MAV_CMD_DO_GRIPPER: case MAV_CMD_DO_GUIDED_LIMITS: case MAV_CMD_DO_FENCE_ENABLE: case MAV_CMD_DO_WINCH: @@ -1381,27 +1374,6 @@ void Copter::ModeAuto::do_parachute(const AP_Mission::Mission_Command& cmd) } #endif -#if GRIPPER_ENABLED == ENABLED -// do_gripper - control gripper -void Copter::ModeAuto::do_gripper(const AP_Mission::Mission_Command& cmd) -{ - // Note: we ignore the gripper num parameter because we only support one gripper - switch (cmd.content.gripper.action) { - case GRIPPER_ACTION_RELEASE: - g2.gripper.release(); - Log_Write_Event(DATA_GRIPPER_RELEASE); - break; - case GRIPPER_ACTION_GRAB: - g2.gripper.grab(); - Log_Write_Event(DATA_GRIPPER_GRAB); - break; - default: - // do nothing - break; - } -} -#endif - #if WINCH_ENABLED == ENABLED // control winch based on mission command void Copter::ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)