APM:Libraries
SIM_Gripper_Servo.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 (Servo) simulation class
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 
23 namespace SITL {
24 
26 public:
27  const uint8_t gripper_servo;
28 
29  Gripper_Servo(const uint8_t _gripper_servo) :
30  gripper_servo(_gripper_servo)
31  {}
32 
33  // update Gripper state
34  void update(const struct Aircraft::sitl_input &input);
35 
36  float payload_mass() const; // kg
37 
38  void set_aircraft(Aircraft *_aircraft) { aircraft = _aircraft; }
39 
40 private:
41 
43 
44  const uint32_t report_interval = 1000000; // microseconds
45  uint64_t last_report_us;
46 
47  const float gap = 30; // mm
48 
49  float position; // percentage
50  float position_slew_rate = 35; // percentage
51  float reported_position = -1; // unlikely
52 
53  uint64_t last_update_us;
54 
55  bool should_report();
56 
57  // dangle load from a string:
58  const float string_length = 2.0f; // metres
59  float load_mass = 0.0f; // kilograms
60 };
61 
62 }
const uint8_t gripper_servo
void update(const struct Aircraft::sitl_input &input)
const uint32_t report_interval
void set_aircraft(Aircraft *_aircraft)
Gripper_Servo(const uint8_t _gripper_servo)
float payload_mass() const