APM:Libraries
SIM_Sprayer.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 sprayer simulation class
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 
23 namespace SITL {
24 
25 class Sprayer {
26 public:
27  const uint8_t pump_servo;
28  const int8_t spinner_servo;
29 
30  Sprayer(const uint8_t _pump_servo, int8_t _spinner_servo) :
31  pump_servo(_pump_servo),
32  spinner_servo(_spinner_servo)
33  {}
34 
35  // update sprayer state
36  void update(const struct Aircraft::sitl_input &input);
37 
38  float payload_mass() const { return capacity; }; // kg; water, so kg=l
39 
40 private:
41 
42  const uint32_t report_interval = 1000000; // microseconds
43  uint64_t last_report_us;
44 
45  const float pump_max_rate = 0.01; // litres/second
46  const float pump_slew_rate = 20; // percent/scond
47  float last_pump_output; // percentage
48 
49  const float spinner_max_rate = 3600; // degrees/second
50  const float spinner_slew_rate = 20; // percent/second
51  float last_spinner_output; // percentage
52 
53  double capacity = 0.25; // litres
54 
55  uint64_t last_update_us;
56 
57  bool should_report();
58  bool zero_report_done = false;
59 };
60 
61 }
const float spinner_slew_rate
Definition: SIM_Sprayer.h:50
void update(const struct Aircraft::sitl_input &input)
Definition: SIM_Sprayer.cpp:27
uint64_t last_report_us
Definition: SIM_Sprayer.h:43
float payload_mass() const
Definition: SIM_Sprayer.h:38
const uint8_t pump_servo
Definition: SIM_Sprayer.h:27
float last_spinner_output
Definition: SIM_Sprayer.h:51
const float pump_slew_rate
Definition: SIM_Sprayer.h:46
bool zero_report_done
Definition: SIM_Sprayer.h:58
float last_pump_output
Definition: SIM_Sprayer.h:47
const uint32_t report_interval
Definition: SIM_Sprayer.h:42
bool should_report()
Definition: SIM_Sprayer.cpp:72
const int8_t spinner_servo
Definition: SIM_Sprayer.h:28
const float spinner_max_rate
Definition: SIM_Sprayer.h:49
double capacity
Definition: SIM_Sprayer.h:53
const float pump_max_rate
Definition: SIM_Sprayer.h:45
uint64_t last_update_us
Definition: SIM_Sprayer.h:55
Sprayer(const uint8_t _pump_servo, int8_t _spinner_servo)
Definition: SIM_Sprayer.h:30