diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 3aba8f6297..d093a92452 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -76,6 +76,7 @@ Copter::Copter(void) : pos_control(ahrs, inertial_nav, motors, attitude_control, g.p_alt_hold, g.p_vel_z, g.pid_accel_z, g.p_pos_xy, g.pi_vel_xy), + avoid(ahrs, inertial_nav, fence), wp_nav(inertial_nav, ahrs, pos_control, attitude_control), circle_nav(inertial_nav, ahrs, pos_control), pmTest1(0), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 5a5b94c1b3..390256ee1b 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -76,6 +76,7 @@ #include // circle navigation library #include // ArduPilot Mega Declination Helper Library #include // Arducopter Fence library +#include // Arducopter stop at fence library #include // main loop scheduler #include // RC input mapping library #include // Notify library @@ -458,6 +459,7 @@ private: AC_AttitudeControl_Multi attitude_control; #endif AC_PosControl pos_control; + AC_Avoid avoid; AC_WPNav wp_nav; AC_Circle circle_nav; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 362bf81a25..2f1231bcfc 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -825,6 +825,10 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(fence, "FENCE_", AC_Fence), #endif + // @Group: AVOID_ + // @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp + GOBJECT(avoid, "AVOID_", AC_Avoid), + #if AC_RALLY == ENABLED // @Group: RALLY_ // @Path: ../libraries/AP_Rally/AP_Rally.cpp diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 33d629ea9b..361fe7e38e 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -181,6 +181,7 @@ public: k_param_fs_crash_check, k_param_throw_motor_start, k_param_terrain_follow, // 94 + k_param_avoid, // 97: RSSI k_param_rssi = 97, diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 260dc01a58..e161507a2a 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -200,6 +200,7 @@ void Copter::init_ardupilot() Location_Class::set_terrain(&terrain); wp_nav.set_terrain(&terrain); #endif + wp_nav.set_avoidance(&avoid); pos_control.set_dt(MAIN_LOOP_SECONDS);