APM:Libraries
AP_Winch.cpp
Go to the documentation of this file.
1 #include "AP_Winch.h"
2 #include "AP_Winch_Servo.h"
3 
4 extern const AP_HAL::HAL& hal;
5 
7  // @Param: ENABLE
8  // @DisplayName: Winch enable/disable
9  // @Description: Winch enable/disable
10  // @User: Standard
11  // @Values: 0:Disabled, 1:Enabled
12  AP_GROUPINFO_FLAGS("_ENABLE", 0, AP_Winch, _enabled, 0, AP_PARAM_FLAG_ENABLE),
13 
14  // @Param: TYPE
15  // @DisplayName: Winch Type
16  // @Description: Winch Type
17  // @User: Standard
18  // @Values: 1:Servo with encoder
19  AP_GROUPINFO("_TYPE", 1, AP_Winch, config.type, 1),
20 
21  // @Param: _RATE_MAX
22  // @DisplayName: Winch deploy or retract rate maximum
23  // @Description: Winch deploy or retract rate maximum. Set to maximum rate with no load.
24  // @User: Standard
25  // @Range: 0 10
26  // @Units: m/s
27  AP_GROUPINFO("_RATE_MAX", 2, AP_Winch, config.rate_max, 1.0f),
28 
29  // @Param: _POS_P
30  // @DisplayName: Winch control position error P gain
31  // @Description: Winch control position error P gain
32  // @Range: 0.01 10.0
33  // @User: Standard
34  AP_GROUPINFO("_POS_P", 3, AP_Winch, config.pos_p, AP_WINCH_POS_P),
35 
36  // @Param: _RATE_P
37  // @DisplayName: Winch control rate P gain
38  // @Description: Winch control rate P gain. Converts rate error (in radians/sec) to pwm output (in the range -1 to +1)
39  // @Range: 0.100 2.000
40  // @User: Standard
41 
42  // @Param: _RATE_I
43  // @DisplayName: Winch control I gain
44  // @Description: Winch control I gain. Corrects long term error between the desired rate (in rad/s) and actual
45  // @Range: 0.000 2.000
46  // @User: Standard
47 
48  // @Param: _RATE_IMAX
49  // @DisplayName: Winch control I gain maximum
50  // @Description: Winch control I gain maximum. Constrains the output (range -1 to +1) that the I term will generate
51  // @Range: 0.000 1.000
52  // @User: Standard
53 
54  // @Param: _RATE_D
55  // @DisplayName: Winch control D gain
56  // @Description: Winch control D gain. Compensates for short-term change in desired rate vs actual
57  // @Range: 0.000 0.400
58  // @User: Standard
59 
60  // @Param: _RATE_FILT
61  // @DisplayName: Winch control filter frequency
62  // @Description: Winch control input filter. Lower values reduce noise but add delay.
63  // @Range: 1.000 100.000
64  // @Units: Hz
65  // @User: Standard
66  AP_SUBGROUPINFO(config.rate_pid, "_RATE_", 4, AP_Winch, AC_PID),
67 
69 };
70 
72 {
74 }
75 
76 // indicate whether this module is enabled
77 bool AP_Winch::enabled() const
78 {
79  if (!_enabled) {
80  return false;
81  }
82 
83  return ((config.type > 0) && (backend != nullptr));
84 }
85 
86 void AP_Winch::init(const AP_WheelEncoder *wheel_encoder)
87 {
88  // return immediately if not enabled
89  if (!_enabled.get()) {
90  return;
91  }
92 
93  switch(config.type.get()) {
94  case 0:
95  break;
96  case 1:
98  break;
99  default:
100  break;
101  }
102  if (backend != nullptr) {
103  backend->init(wheel_encoder);
104  }
105 }
106 
107 // release specified length of cable (in meters) at the specified rate
108 // if rate is zero, the RATE_MAX parameter value will be used
109 void AP_Winch::release_length(float length, float rate)
110 {
113  if (is_zero(rate)) {
115  } else {
117  }
118 }
119 
120 // deploy line at specified speed in m/s (+ve deploys line, -ve retracts line, 0 stops)
122 {
125 }
126 
127 // update - should be called at at least 10hz
128 #define PASS_TO_BACKEND(function_name) \
129  void AP_Winch::function_name() \
130  { \
131  if (!enabled()) { \
132  return; \
133  } \
134  if (backend != nullptr) { \
135  backend->function_name(); \
136  } \
137  }
138 
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
#define PASS_TO_BACKEND(function_name)
Definition: AP_Winch.cpp:128
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Int8 _enabled
Definition: AP_Winch.h:72
bool enabled() const
Definition: AP_Winch.cpp:77
AP_Winch_Backend * backend
Definition: AP_Winch.h:92
AP_Winch()
Definition: AP_Winch.cpp:71
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
virtual void init(const AP_WheelEncoder *wheel_encoder)=0
void update()
void init(const AP_WheelEncoder *wheel_encoder=nullptr)
Definition: AP_Winch.cpp:86
float get_rate_max() const
Definition: AP_Winch.h:65
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
void release_length(float length, float rate=0.0f)
Definition: AP_Winch.cpp:109
friend class AP_Winch_Servo
Definition: AP_Winch.h:37
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
#define AP_WINCH_POS_P
Definition: AP_Winch.h:25
struct AP_Winch::Backend_Config config
void set_desired_rate(float rate)
Definition: AP_Winch.cpp:121
Copter PID control class.
Definition: AC_PID.h:17
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Winch.h:67
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214