diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index a52905f159..3060306202 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -114,6 +114,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update), // run low level rate controllers that only require IMU data FAST_TASK(run_rate_controller), +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + FAST_TASK(run_custom_controller), +#endif // send outputs to the motors library immediately FAST_TASK(motors_output), // run EKF state estimator (expensive) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 230aa8f762..0cf8109de3 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -157,6 +157,10 @@ #include #endif +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#include // Custom control library +#endif + #if AC_AVOID_ENABLED && !AP_FENCE_ENABLED #error AC_Avoidance relies on AP_FENCE_ENABLED which is disabled #endif @@ -464,6 +468,10 @@ private: AC_WPNav *wp_nav; AC_Loiter *loiter_nav; +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + AC_CustomControl custom_control{ahrs_view, attitude_control, motors, scheduler.get_loop_period_s()}; +#endif + #if MODE_CIRCLE_ENABLED == ENABLED AC_Circle *circle_nav; #endif @@ -687,6 +695,10 @@ private: uint16_t get_pilot_speed_dn() const; void run_rate_controller() { attitude_control->rate_controller_run(); } +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + void run_custom_controller() { custom_control.update(); } +#endif + // avoidance.cpp void low_alt_avoidance(); diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 79b185f2cc..c0ec27b495 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -718,6 +718,12 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(osd, "OSD", AP_OSD), #endif +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + // @Group: CC + // @Path: ../libraries/AC_CustomControl/AC_CustomControl.cpp + GOBJECT(custom_control, "CC", AC_CustomControl), +#endif + // @Group: // @Path: Parameters.cpp GOBJECT(g2, "", ParametersG2), diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index cf6c92a9a4..953f1d00fa 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -199,6 +199,7 @@ public: k_param_pos_control, k_param_circle_nav, k_param_loiter_nav, // 105 + k_param_custom_control, // 110: Telemetry control // diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 1380b6d0f4..dfad573d6e 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -120,6 +120,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxS case AUX_FUNC::WINCH_ENABLE: case AUX_FUNC::AIRMODE: case AUX_FUNC::FORCEFLYING: + case AUX_FUNC::CUSTOM_CONTROLLER: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; default: @@ -611,6 +612,12 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi } break; +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + case AUX_FUNC::CUSTOM_CONTROLLER: + copter.custom_control.set_custom_controller(ch_flag == AuxSwitchPos::HIGH); + break; +#endif + default: return RC_Channel::do_aux_function(ch_option, ch_flag); } diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 10eb35943c..50250d9bec 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -711,3 +711,7 @@ #ifndef HAL_FRAME_TYPE_DEFAULT #define HAL_FRAME_TYPE_DEFAULT AP_Motors::MOTOR_FRAME_TYPE_X #endif + +#ifndef AC_CUSTOMCONTROL_MULTI_ENABLED +#define AC_CUSTOMCONTROL_MULTI_ENABLED FRAME_CONFIG == MULTICOPTER_FRAME && AP_CUSTOMCONTROL_ENABLED +#endif diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 6bea6eae8d..20ee805e9a 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -183,6 +183,10 @@ void Copter::init_ardupilot() g2.scripting.init(); #endif // AP_SCRIPTING_ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + custom_control.init(); +#endif + // set landed flags set_land_complete(true); set_land_complete_maybe(true);