mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
Copter: make EPM a subclass of AP_Gripper_Backend
This commit is contained in:
parent
48cd35609c
commit
236b8ab6b7
@ -28,7 +28,6 @@
|
||||
//#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally)
|
||||
//#define AC_TERRAIN DISABLED // disable terrain library
|
||||
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
|
||||
//#define EPM_ENABLED DISABLED // disable epm cargo gripper to save 500bytes of flash
|
||||
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
||||
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
||||
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
|
||||
|
@ -132,9 +132,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||
SCHED_TASK(afs_fs_check, 10, 100),
|
||||
#endif
|
||||
SCHED_TASK(terrain_update, 10, 100),
|
||||
#if EPM_ENABLED == ENABLED
|
||||
SCHED_TASK(epm_update, 10, 75),
|
||||
#endif
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
SCHED_TASK(gripper_update, 10, 75),
|
||||
#endif
|
||||
|
@ -101,9 +101,6 @@
|
||||
#if SPRAYER == ENABLED
|
||||
#include <AC_Sprayer/AC_Sprayer.h> // crop sprayer library
|
||||
#endif
|
||||
#if EPM_ENABLED == ENABLED
|
||||
#include <AP_EPM/AP_EPM.h> // EPM cargo gripper stuff
|
||||
#endif
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
#include <AP_Gripper/AP_Gripper.h> // gripper stuff
|
||||
#endif
|
||||
@ -568,11 +565,6 @@ private:
|
||||
AC_Sprayer sprayer;
|
||||
#endif
|
||||
|
||||
// EPM Cargo Griper
|
||||
#if EPM_ENABLED == ENABLED
|
||||
AP_EPM epm;
|
||||
#endif
|
||||
|
||||
// Parachute release
|
||||
#if PARACHUTE == ENABLED
|
||||
AP_Parachute parachute;
|
||||
@ -1122,7 +1114,7 @@ private:
|
||||
#if PARACHUTE == ENABLED
|
||||
void do_parachute(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
#if EPM_ENABLED == ENABLED
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
void do_gripper(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
|
||||
|
@ -1377,20 +1377,20 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
result = copter.mavlink_motor_test_start(chan, (uint8_t)packet.param1, (uint8_t)packet.param2, (uint16_t)packet.param3, packet.param4);
|
||||
break;
|
||||
|
||||
#if EPM_ENABLED == ENABLED
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
case MAV_CMD_DO_GRIPPER:
|
||||
// param1 : gripper number (ignored)
|
||||
// param2 : action (0=release, 1=grab). See GRIPPER_ACTIONS enum.
|
||||
if(!copter.epm.enabled()) {
|
||||
if(!copter.g2.gripper.enabled()) {
|
||||
result = MAV_RESULT_FAILED;
|
||||
} else {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
switch ((uint8_t)packet.param2) {
|
||||
case GRIPPER_ACTION_RELEASE:
|
||||
copter.epm.release();
|
||||
copter.g2.gripper.release();
|
||||
break;
|
||||
case GRIPPER_ACTION_GRAB:
|
||||
copter.epm.grab();
|
||||
copter.g2.gripper.grab();
|
||||
break;
|
||||
default:
|
||||
result = MAV_RESULT_FAILED;
|
||||
|
@ -707,12 +707,6 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
||||
GOBJECT(relay, "RELAY_", AP_Relay),
|
||||
|
||||
#if EPM_ENABLED == ENABLED
|
||||
// @Group: EPM_
|
||||
// @Path: ../libraries/AP_EPM/AP_EPM.cpp
|
||||
GOBJECT(epm, "EPM_", AP_EPM),
|
||||
#endif
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
// @Group: CHUTE_
|
||||
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
|
||||
|
@ -67,8 +67,8 @@ public:
|
||||
// relay object
|
||||
k_param_relay,
|
||||
|
||||
// EPM object
|
||||
k_param_epm,
|
||||
// (old) EPM object
|
||||
k_param_epm_unused,
|
||||
|
||||
// BoardConfig object
|
||||
k_param_BoardConfig,
|
||||
|
@ -132,8 +132,8 @@ bool Copter::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if EPM_ENABLED == ENABLED
|
||||
case MAV_CMD_DO_GRIPPER: // Mission command to control EPM gripper
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
case MAV_CMD_DO_GRIPPER: // Mission command to control gripper
|
||||
do_gripper(cmd);
|
||||
break;
|
||||
#endif
|
||||
@ -571,19 +571,19 @@ void Copter::do_parachute(const AP_Mission::Mission_Command& cmd)
|
||||
}
|
||||
#endif
|
||||
|
||||
#if EPM_ENABLED == ENABLED
|
||||
// do_gripper - control EPM gripper
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
// do_gripper - control gripper
|
||||
void Copter::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:
|
||||
epm.release();
|
||||
Log_Write_Event(DATA_EPM_RELEASE);
|
||||
g2.gripper.release();
|
||||
Log_Write_Event(DATA_GRIPPER_RELEASE);
|
||||
break;
|
||||
case GRIPPER_ACTION_GRAB:
|
||||
epm.grab();
|
||||
Log_Write_Event(DATA_EPM_GRAB);
|
||||
g2.gripper.grab();
|
||||
Log_Write_Event(DATA_GRIPPER_GRAB);
|
||||
break;
|
||||
default:
|
||||
// do nothing
|
||||
|
@ -295,12 +295,6 @@
|
||||
# define PRECISION_LANDING ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// EPM cargo gripper
|
||||
#ifndef EPM_ENABLED
|
||||
# define EPM_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// gripper
|
||||
#ifndef GRIPPER_ENABLED
|
||||
|
@ -49,7 +49,7 @@ enum aux_sw_func {
|
||||
AUXSW_AUTO = 16, // change to auto flight mode
|
||||
AUXSW_AUTOTUNE = 17, // auto tune
|
||||
AUXSW_LAND = 18, // change to LAND flight mode
|
||||
AUXSW_EPM = 19, // Operate the EPM cargo gripper low=off, middle=neutral, high=on
|
||||
AUXSW_GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
|
||||
AUXSW_PARACHUTE_ENABLE = 21, // Parachute enable/disable
|
||||
AUXSW_PARACHUTE_RELEASE = 22, // Parachute release
|
||||
AUXSW_PARACHUTE_3POS = 23, // Parachute disable, enable, release with 3 position switch
|
||||
@ -361,8 +361,8 @@ enum DevOptions {
|
||||
#define DATA_ACRO_TRAINER_DISABLED 43
|
||||
#define DATA_ACRO_TRAINER_LEVELING 44
|
||||
#define DATA_ACRO_TRAINER_LIMITED 45
|
||||
#define DATA_EPM_GRAB 46
|
||||
#define DATA_EPM_RELEASE 47
|
||||
#define DATA_GRIPPER_GRAB 46
|
||||
#define DATA_GRIPPER_RELEASE 47
|
||||
#define DATA_PARACHUTE_DISABLED 49
|
||||
#define DATA_PARACHUTE_ENABLED 50
|
||||
#define DATA_PARACHUTE_RELEASED 51
|
||||
|
@ -51,7 +51,6 @@ LIBRARIES += AP_BattMonitor
|
||||
LIBRARIES += AP_BoardConfig
|
||||
LIBRARIES += AP_Frsky_Telem
|
||||
LIBRARIES += AC_Sprayer
|
||||
LIBRARIES += AP_EPM
|
||||
LIBRARIES += AP_Parachute
|
||||
LIBRARIES += AP_LandingGear
|
||||
LIBRARIES += AP_Terrain
|
||||
|
@ -233,14 +233,6 @@ void Copter::accel_cal_update()
|
||||
#endif
|
||||
}
|
||||
|
||||
#if EPM_ENABLED == ENABLED
|
||||
// epm update - moves epm pwm output back to neutral after grab or release is completed
|
||||
void Copter::epm_update()
|
||||
{
|
||||
epm.update();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
// gripper update
|
||||
void Copter::gripper_update()
|
||||
|
@ -221,7 +221,7 @@ void Copter::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
|
||||
case AUXSW_FENCE:
|
||||
case AUXSW_SUPERSIMPLE_MODE:
|
||||
case AUXSW_ACRO_TRAINER:
|
||||
case AUXSW_EPM:
|
||||
case AUXSW_GRIPPER:
|
||||
case AUXSW_SPRAYER:
|
||||
case AUXSW_PARACHUTE_ENABLE:
|
||||
case AUXSW_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
|
||||
@ -379,18 +379,16 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
break;
|
||||
}
|
||||
break;
|
||||
#if EPM_ENABLED == ENABLED
|
||||
case AUXSW_EPM:
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
case AUXSW_GRIPPER:
|
||||
switch(ch_flag) {
|
||||
case AUX_SWITCH_LOW:
|
||||
g2.gripper.release();
|
||||
epm.release();
|
||||
Log_Write_Event(DATA_EPM_RELEASE);
|
||||
Log_Write_Event(DATA_GRIPPER_RELEASE);
|
||||
break;
|
||||
case AUX_SWITCH_HIGH:
|
||||
g2.gripper.grab();
|
||||
epm.grab();
|
||||
Log_Write_Event(DATA_EPM_GRAB);
|
||||
Log_Write_Event(DATA_GRIPPER_GRAB);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
@ -128,11 +128,6 @@ void Copter::init_ardupilot()
|
||||
|
||||
BoardConfig.init();
|
||||
|
||||
// init EPM cargo gripper
|
||||
#if EPM_ENABLED == ENABLED
|
||||
epm.init();
|
||||
#endif
|
||||
|
||||
// init cargo gripper
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
g2.gripper.init();
|
||||
|
@ -17,7 +17,6 @@ def build(bld):
|
||||
'AC_Sprayer',
|
||||
'AC_WPNav',
|
||||
'AP_Camera',
|
||||
'AP_EPM',
|
||||
'AP_Frsky_Telem',
|
||||
'AP_IRLock',
|
||||
'AP_InertialNav',
|
||||
|
Loading…
Reference in New Issue
Block a user