Copter: support for AP_Gripper

This commit is contained in:
Peter Barker 2016-10-29 09:08:22 +11:00 committed by Randy Mackay
parent d2e798d549
commit 920868145c
10 changed files with 47 additions and 6 deletions

View File

@ -135,6 +135,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if EPM_ENABLED == ENABLED #if EPM_ENABLED == ENABLED
SCHED_TASK(epm_update, 10, 75), SCHED_TASK(epm_update, 10, 75),
#endif #endif
#if GRIPPER_ENABLED == ENABLED
SCHED_TASK(gripper_update, 10, 75),
#endif
#ifdef USERHOOK_FASTLOOP #ifdef USERHOOK_FASTLOOP
SCHED_TASK(userhook_FastLoop, 100, 75), SCHED_TASK(userhook_FastLoop, 100, 75),
#endif #endif

View File

@ -104,6 +104,9 @@
#if EPM_ENABLED == ENABLED #if EPM_ENABLED == ENABLED
#include <AP_EPM/AP_EPM.h> // EPM cargo gripper stuff #include <AP_EPM/AP_EPM.h> // EPM cargo gripper stuff
#endif #endif
#if GRIPPER_ENABLED == ENABLED
#include <AP_Gripper/AP_Gripper.h> // gripper stuff
#endif
#if PARACHUTE == ENABLED #if PARACHUTE == ENABLED
#include <AP_Parachute/AP_Parachute.h> // Parachute release library #include <AP_Parachute/AP_Parachute.h> // Parachute release library
#endif #endif
@ -1041,6 +1044,7 @@ private:
void read_battery(void); void read_battery(void);
void read_receiver_rssi(void); void read_receiver_rssi(void);
void epm_update(); void epm_update();
void gripper_update();
void terrain_update(); void terrain_update();
void terrain_logging(); void terrain_logging();
bool terrain_use(); bool terrain_use();

View File

@ -395,42 +395,42 @@ const AP_Param::Info Copter::var_info[] = {
// @Param: CH7_OPT // @Param: CH7_OPT
// @DisplayName: Channel 7 option // @DisplayName: Channel 7 option
// @Description: Select which function is performed when CH7 is above 1800 pwm // @Description: Select which function is performed when CH7 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
// @User: Standard // @User: Standard
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING), GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
// @Param: CH8_OPT // @Param: CH8_OPT
// @DisplayName: Channel 8 option // @DisplayName: Channel 8 option
// @Description: Select which function is performed when CH8 is above 1800 pwm // @Description: Select which function is performed when CH8 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
// @User: Standard // @User: Standard
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING), GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
// @Param: CH9_OPT // @Param: CH9_OPT
// @DisplayName: Channel 9 option // @DisplayName: Channel 9 option
// @Description: Select which function is performed when CH9 is above 1800 pwm // @Description: Select which function is performed when CH9 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
// @User: Standard // @User: Standard
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING), GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
// @Param: CH10_OPT // @Param: CH10_OPT
// @DisplayName: Channel 10 option // @DisplayName: Channel 10 option
// @Description: Select which function is performed when CH10 is above 1800 pwm // @Description: Select which function is performed when CH10 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
// @User: Standard // @User: Standard
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING), GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
// @Param: CH11_OPT // @Param: CH11_OPT
// @DisplayName: Channel 11 option // @DisplayName: Channel 11 option
// @Description: Select which function is performed when CH11 is above 1800 pwm // @Description: Select which function is performed when CH11 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
// @User: Standard // @User: Standard
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING), GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
// @Param: CH12_OPT // @Param: CH12_OPT
// @DisplayName: Channel 12 option // @DisplayName: Channel 12 option
// @Description: Select which function is performed when CH12 is above 1800 pwm // @Description: Select which function is performed when CH12 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
// @User: Standard // @User: Standard
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING), GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
@ -1039,6 +1039,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/AP_Stats/AP_Stats.cpp // @Path: ../libraries/AP_Stats/AP_Stats.cpp
AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats), AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats),
#if GRIPPER_ENABLED == ENABLED
// @Group: GRIP_
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
AP_SUBGROUPINFO(gripper, "GRIP_", 13, ParametersG2, AP_Gripper),
#endif
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -553,6 +553,10 @@ public:
// vehicle statistics // vehicle statistics
AP_Stats stats; AP_Stats stats;
#if GRIPPER_ENABLED
AP_Gripper gripper;
#endif
// Throw mode parameters // Throw mode parameters
AP_Int8 throw_nextmode; AP_Int8 throw_nextmode;
AP_Int8 throw_type; AP_Int8 throw_type;

View File

@ -301,6 +301,12 @@
# define EPM_ENABLED ENABLED # define EPM_ENABLED ENABLED
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// gripper
#ifndef GRIPPER_ENABLED
# define GRIPPER_ENABLED ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Parachute release // Parachute release
#ifndef PARACHUTE #ifndef PARACHUTE

View File

@ -63,3 +63,4 @@ LIBRARIES += AP_ADSB
LIBRARIES += AP_Avoidance LIBRARIES += AP_Avoidance
LIBRARIES += AP_Proximity LIBRARIES += AP_Proximity
LIBRARIES += AP_Stats LIBRARIES += AP_Stats
LIBRARIES += AP_Gripper

View File

@ -241,6 +241,14 @@ void Copter::epm_update()
} }
#endif #endif
#if GRIPPER_ENABLED == ENABLED
// gripper update
void Copter::gripper_update()
{
g2.gripper.update();
}
#endif
/* /*
update AP_Button update AP_Button
*/ */

View File

@ -383,10 +383,12 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
case AUXSW_EPM: case AUXSW_EPM:
switch(ch_flag) { switch(ch_flag) {
case AUX_SWITCH_LOW: case AUX_SWITCH_LOW:
g2.gripper.release();
epm.release(); epm.release();
Log_Write_Event(DATA_EPM_RELEASE); Log_Write_Event(DATA_EPM_RELEASE);
break; break;
case AUX_SWITCH_HIGH: case AUX_SWITCH_HIGH:
g2.gripper.grab();
epm.grab(); epm.grab();
Log_Write_Event(DATA_EPM_GRAB); Log_Write_Event(DATA_EPM_GRAB);
break; break;

View File

@ -133,6 +133,11 @@ void Copter::init_ardupilot()
epm.init(); epm.init();
#endif #endif
// init cargo gripper
#if GRIPPER_ENABLED == ENABLED
g2.gripper.init();
#endif
// initialise notify system // initialise notify system
// disable external leds if epm is enabled because of pin conflict on the APM // disable external leds if epm is enabled because of pin conflict on the APM
notify.init(true); notify.init(true);

View File

@ -32,6 +32,7 @@ def build(bld):
'AP_AdvancedFailsafe', 'AP_AdvancedFailsafe',
'AP_Proximity', 'AP_Proximity',
'AP_Stats', 'AP_Stats',
'AP_Gripper',
], ],
) )