APM:Libraries
SIM_Gripper_EPM.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  simple Gripper (EPM) simulation class
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 
23 namespace SITL {
24 
25 class Gripper_EPM {
26 public:
27  const uint8_t gripper_servo;
28 
29  Gripper_EPM(const uint8_t _gripper_servo) :
30  gripper_servo(_gripper_servo)
31  {}
32 
33  // update field stength
34  void update(const struct Aircraft::sitl_input &input);
35 
36 private:
37 
38  const uint32_t report_interval = 100000; // microseconds
39  uint64_t last_report_us;
40 
41  bool servo_based = true;
42 
43  double field_strength; // percentage
44  double reported_field_strength = -1; // unlikely
45 
46  // I've a feeling these are probably a higher order than this:
47  const float field_strength_slew_rate = 400; // (percentage of delta between field strength and 100)/second
48  const float field_decay_rate = 2; // percent of field strength/second
49  const float field_degauss_rate = 300; // percent of field strength/second
50 
51  uint64_t last_update_us;
52 
53  bool should_report();
54 
55  void update_from_demand(const Aircraft::sitl_input &input);
56  void update_servobased(const struct Aircraft::sitl_input &input);
57 
58  float tesla();
59 
60  float demand;
61 };
62 
63 }
void update_from_demand(const Aircraft::sitl_input &input)
double reported_field_strength
const float field_decay_rate
const float field_degauss_rate
const float field_strength_slew_rate
const uint8_t gripper_servo
const uint32_t report_interval
void update(const struct Aircraft::sitl_input &input)
void update_servobased(const struct Aircraft::sitl_input &input)
Gripper_EPM(const uint8_t _gripper_servo)