mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
Copter: integrate EPM ver2
This commit is contained in:
parent
1401ee4077
commit
14d80910ec
@ -823,6 +823,9 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
{ telemetry_send, 80, 10 },
|
{ telemetry_send, 80, 10 },
|
||||||
#endif
|
#endif
|
||||||
|
#if EPM_ENABLED == ENABLED
|
||||||
|
{ epm_update, 40, 10 },
|
||||||
|
#endif
|
||||||
#ifdef USERHOOK_FASTLOOP
|
#ifdef USERHOOK_FASTLOOP
|
||||||
{ userhook_FastLoop, 4, 10 },
|
{ userhook_FastLoop, 4, 10 },
|
||||||
#endif
|
#endif
|
||||||
@ -888,6 +891,9 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
{ telemetry_send, 20, 100 },
|
{ telemetry_send, 20, 100 },
|
||||||
#endif
|
#endif
|
||||||
|
#if EPM_ENABLED == ENABLED
|
||||||
|
{ epm_update, 10, 20 },
|
||||||
|
#endif
|
||||||
#ifdef USERHOOK_FASTLOOP
|
#ifdef USERHOOK_FASTLOOP
|
||||||
{ userhook_FastLoop, 1, 100 },
|
{ userhook_FastLoop, 1, 100 },
|
||||||
#endif
|
#endif
|
||||||
|
@ -292,8 +292,8 @@ enum FlipState {
|
|||||||
#define DATA_ACRO_TRAINER_DISABLED 43
|
#define DATA_ACRO_TRAINER_DISABLED 43
|
||||||
#define DATA_ACRO_TRAINER_LEVELING 44
|
#define DATA_ACRO_TRAINER_LEVELING 44
|
||||||
#define DATA_ACRO_TRAINER_LIMITED 45
|
#define DATA_ACRO_TRAINER_LIMITED 45
|
||||||
#define DATA_EPM_ON 46
|
#define DATA_EPM_GRAB 46
|
||||||
#define DATA_EPM_OFF 47
|
#define DATA_EPM_RELEASE 47
|
||||||
#define DATA_EPM_NEUTRAL 48
|
#define DATA_EPM_NEUTRAL 48
|
||||||
#define DATA_PARACHUTE_DISABLED 49
|
#define DATA_PARACHUTE_DISABLED 49
|
||||||
#define DATA_PARACHUTE_ENABLED 50
|
#define DATA_PARACHUTE_ENABLED 50
|
||||||
|
@ -133,3 +133,11 @@ void read_receiver_rssi(void)
|
|||||||
receiver_rssi = constrain_int16(ret, 0, 255);
|
receiver_rssi = constrain_int16(ret, 0, 255);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if EPM_ENABLED == ENABLED
|
||||||
|
// epm update - moves epm pwm output back to neutral after grab or release is completed
|
||||||
|
void epm_update()
|
||||||
|
{
|
||||||
|
epm.update();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
@ -310,16 +310,16 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|||||||
case AUX_SWITCH_EPM:
|
case AUX_SWITCH_EPM:
|
||||||
switch(ch_flag) {
|
switch(ch_flag) {
|
||||||
case AUX_SWITCH_LOW:
|
case AUX_SWITCH_LOW:
|
||||||
epm.off();
|
epm.release();
|
||||||
Log_Write_Event(DATA_EPM_OFF);
|
Log_Write_Event(DATA_EPM_RELEASE);
|
||||||
break;
|
break;
|
||||||
case AUX_SWITCH_MIDDLE:
|
case AUX_SWITCH_MIDDLE:
|
||||||
epm.neutral();
|
epm.neutral();
|
||||||
Log_Write_Event(DATA_EPM_NEUTRAL);
|
Log_Write_Event(DATA_EPM_NEUTRAL);
|
||||||
break;
|
break;
|
||||||
case AUX_SWITCH_HIGH:
|
case AUX_SWITCH_HIGH:
|
||||||
epm.on();
|
epm.grab();
|
||||||
Log_Write_Event(DATA_EPM_ON);
|
Log_Write_Event(DATA_EPM_GRAB);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -131,17 +131,14 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
BoardConfig.init();
|
BoardConfig.init();
|
||||||
|
|
||||||
bool enable_external_leds = true;
|
|
||||||
|
|
||||||
// init EPM cargo gripper
|
// init EPM cargo gripper
|
||||||
#if EPM_ENABLED == ENABLED
|
#if EPM_ENABLED == ENABLED
|
||||||
epm.init();
|
epm.init();
|
||||||
enable_external_leds = !epm.enabled();
|
|
||||||
#endif
|
#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(enable_external_leds);
|
notify.init(true);
|
||||||
|
|
||||||
// initialise battery monitor
|
// initialise battery monitor
|
||||||
battery.init();
|
battery.init();
|
||||||
|
Loading…
Reference in New Issue
Block a user