APM:Libraries
AP_Winch.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #pragma once
17 
18 #include <AP_Common/AP_Common.h>
19 #include <AP_Math/AP_Math.h>
20 #include <AP_Param/AP_Param.h>
21 #include <AC_PID/AC_PID.h>
23 
24 // winch rate control default gains
25 #define AP_WINCH_POS_P 1.00f
26 #define AP_WINCH_RATE_P 1.00f
27 #define AP_WINCH_RATE_I 0.50f
28 #define AP_WINCH_RATE_IMAX 1.00f
29 #define AP_WINCH_RATE_D 0.00f
30 #define AP_WINCH_RATE_FILT 5.00f
31 #define AP_WINCH_RATE_DT 0.10f
32 
33 class AP_Winch_Backend;
34 
35 class AP_Winch {
36  friend class AP_Winch_Backend;
37  friend class AP_Winch_Servo;
38 
39 public:
40  AP_Winch();
41 
42  // indicate whether this module is enabled
43  bool enabled() const;
44 
45  // initialise the winch
46  void init(const AP_WheelEncoder *wheel_encoder = nullptr);
47 
48  // update the winch
49  void update();
50 
51  // relax the winch so it does not attempt to maintain length or rate
53 
54  // get current line length
55  float get_line_length() const { return config.length_curr; }
56 
57  // release specified length of cable (in meters) at the specified rate
58  // if rate is zero, the RATE_MAX parameter value will be used
59  void release_length(float length, float rate = 0.0f);
60 
61  // deploy line at specified speed in m/s (+ve deploys line, -ve retracts line, 0 stops)
62  void set_desired_rate(float rate);
63 
64  // get rate maximum in m/s
65  float get_rate_max() const { return MAX(config.rate_max, 0.0f); }
66 
67  static const struct AP_Param::GroupInfo var_info[];
68 
69 private:
70 
71  // parameters
72  AP_Int8 _enabled; // grabber enable/disable
73 
74  // winch states
75  typedef enum {
76  STATE_RELAXED = 0, // winch is not operating
77  STATE_POSITION, // moving or maintaining a target length
78  STATE_RATE, // deploying or retracting at a target rate
79  } winch_state;
80 
81  struct Backend_Config {
82  AP_Int8 type; // winch type
83  AP_Float rate_max; // deploy or retract rate maximum (in m/s).
84  AP_Float pos_p; // position error P gain
86  winch_state state; // state of winch control (using target position or target rate)
87  float length_curr; // current length of the line (in meters) that has been deployed
88  float length_desired; // target desired length (in meters)
89  float rate_desired; // target deploy rate (in m/s, +ve = deploying, -ve = retracting)
90  } config;
91 
93 };
Generic PID algorithm, with EEPROM-backed storage of constants.
void relax()
Definition: AP_Winch.h:52
AP_Int8 _enabled
Definition: AP_Winch.h:72
bool enabled() const
Definition: AP_Winch.cpp:77
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
AP_Winch_Backend * backend
Definition: AP_Winch.h:92
float get_line_length() const
Definition: AP_Winch.h:55
A system for managing and storing variables that are of general interest to the system.
AP_Winch()
Definition: AP_Winch.cpp:71
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
#define f(i)
void release_length(float length, float rate=0.0f)
Definition: AP_Winch.cpp:109
#define AP_WINCH_RATE_IMAX
Definition: AP_Winch.h:28
#define AP_WINCH_RATE_D
Definition: AP_Winch.h:29
winch_state
Definition: AP_Winch.h:75
Common definitions and utility routines for the ArduPilot libraries.
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_WINCH_RATE_P
Definition: AP_Winch.h:26
#define AP_WINCH_RATE_I
Definition: AP_Winch.h:27
#define AP_WINCH_RATE_DT
Definition: AP_Winch.h:31
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Winch.h:67
#define AP_WINCH_RATE_FILT
Definition: AP_Winch.h:30