APM:Libraries
AC_InputManager_Heli.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include <AP_Param/AP_Param.h>
7 #include <AP_Common/AP_Common.h>
8 #include "AC_InputManager.h"
9 
10 # define AC_ATTITUDE_HELI_STAB_COLLECTIVE_MIN_DEFAULT 0
11 # define AC_ATTITUDE_HELI_STAB_COLLECTIVE_LOW_DEFAULT 400
12 # define AC_ATTITUDE_HELI_STAB_COLLECTIVE_HIGH_DEFAULT 600
13 # define AC_ATTITUDE_HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000
14 
18 public:
19  // Constructor
21  : AC_InputManager()
22  {
23  // setup parameter defaults
25  }
26 
27  /* Do not allow copies */
28  AC_InputManager_Heli(const AC_InputManager_Heli &other) = delete;
30 
31  // get_pilot_desired_collective - rescale's pilot collective pitch input in Stabilize and Acro modes
32  float get_pilot_desired_collective(int16_t control_in);
33 
34  // set_use_stab_col - setter function
35  void set_use_stab_col(bool use) { _im_flags_heli.use_stab_col = use; }
36 
37  // set_heli_stab_col_ramp - setter function
38  void set_stab_col_ramp(float ramp) { _stab_col_ramp = constrain_float(ramp, 0.0, 1.0); }
39 
40  static const struct AP_Param::GroupInfo var_info[];
41 
42 private:
44  uint8_t use_stab_col : 1; // 1 if we should use Stabilise mode collective range, 0 for Acro range
46 
47  // factor used to smoothly ramp collective from Acro value to Stab-Col value
48  float _stab_col_ramp = 0;
49 
50  AP_Int16 _heli_stab_col_min; // minimum collective pitch setting at zero throttle input in Stabilize mode
51  AP_Int16 _heli_stab_col_low; // collective pitch setting at mid-low throttle input in Stabilize mode
52  AP_Int16 _heli_stab_col_high; // collective pitch setting at mid-high throttle input in Stabilize mode
53  AP_Int16 _heli_stab_col_max; // maximum collective pitch setting at full throttle input in Stabilize mode
54  AP_Float _acro_col_expo; // used to soften collective pitch inputs near center point in Acro mode
55 
56 };
struct AC_InputManager_Heli::InputManagerHeliFlags _im_flags_heli
AC_InputManager_Heli & operator=(const AC_InputManager_Heli &)=delete
float get_pilot_desired_collective(int16_t control_in)
A system for managing and storing variables that are of general interest to the system.
static const struct AP_Param::GroupInfo var_info[]
void set_stab_col_ramp(float ramp)
void set_use_stab_col(bool use)
Common definitions and utility routines for the ArduPilot libraries.
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
Pilot manual control input library.
Class managing the pilot&#39;s control inputs.
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214