Browse Source

Copter: Utilize Input Manager Class

master
Robert Lefebvre 9 years ago committed by Randy Mackay
parent
commit
34fb600c4f
  1. 3
      ArduCopter/Copter.cpp
  2. 10
      ArduCopter/Copter.h
  3. 6
      ArduCopter/Parameters.cpp
  4. 7
      ArduCopter/Parameters.h

3
ArduCopter/Copter.cpp

@ -32,6 +32,9 @@ Copter::Copter(void) : @@ -32,6 +32,9 @@ Copter::Copter(void) :
control_mode(STABILIZE),
#if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments
motors(g.rc_7, g.heli_servo_rsc, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4, MAIN_LOOP_RATE),
// ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4
input_manager(MAIN_LOOP_RATE),
#elif FRAME_CONFIG == TRI_FRAME // tri constructor requires additional rc_7 argument to allow tail servo reversing
motors(MAIN_LOOP_RATE),
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps

10
ArduCopter/Copter.h

@ -105,6 +105,9 @@ @@ -105,6 +105,9 @@
#include <AC_PrecLand/AC_PrecLand.h>
#include <AP_IRLock/AP_IRLock.h>
#endif
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
// AP_HAL to Arduino compatibility layer
// Configuration
@ -506,6 +509,13 @@ private: @@ -506,6 +509,13 @@ private:
AC_PrecLand precland;
#endif
// Pilot Input Management Library
// Only used for Helicopter for AC3.3, to be expanded to include Multirotor
// child class for AC3.4
#if FRAME_CONFIG == HELI_FRAME
AC_InputManager_Heli input_manager;
#endif
// use this to prevent recursion during sensor init
bool in_mavlink_delay;

6
ArduCopter/Parameters.cpp

@ -901,6 +901,12 @@ const AP_Param::Info Copter::var_info[] = { @@ -901,6 +901,12 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
GOBJECT(landinggear, "LGR_", AP_LandingGear),
#if FRAME_CONFIG == HELI_FRAME
// @Group: IM_
// @Path: ../libraries/AC_InputManager_Heli.cpp
GOBJECT(input_manager, "IM_", AC_InputManager_Heli),
#endif
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/Compass.cpp
GOBJECT(compass, "COMPASS_", Compass),

7
ArduCopter/Parameters.h

@ -83,8 +83,8 @@ public: @@ -83,8 +83,8 @@ public:
// Landing gear object
k_param_landinggear, // 18
// precision landing object
k_param_precland, // 19
// Input Management object
k_param_input_manager, // 19
// Misc
//
@ -145,6 +145,9 @@ public: @@ -145,6 +145,9 @@ public:
k_param_gps_glitch, // deprecated
k_param_baro_glitch, // 71 - deprecated
// 74: precision landing object
k_param_precland = 74,
//
// 75: Singlecopter, CoaxCopter
//

Loading…
Cancel
Save