APM:Libraries
SIM_Sprayer.cpp
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 simulator class
17 */
18 
19 #include "SIM_Sprayer.h"
20 #include <stdio.h>
21 
22 using namespace SITL;
23 
24 /*
25  update sprayer state
26  */
28 {
29  const uint64_t now = AP_HAL::micros64();
30  const float dt = (now - last_update_us) * 1.0e-6f;
31 
32  // update remaining payload
33  if (capacity > 0) {
34  const double delta = last_pump_output * pump_max_rate * dt;
35  capacity -= delta;
36  if (capacity < 0) {
37  capacity = 0.0f;
38  }
39  }
40 
41  // update pump
42  float pump_demand = (input.servos[pump_servo]-1000) * 0.001f;
43  // ::fprintf(stderr, "pump_demand=%f\n", pump_demand);
44  if (pump_demand < 0) { // never updated
45  pump_demand = 0;
46  }
47  const float pump_max_change = pump_slew_rate/100.0f * dt;
48  last_pump_output = constrain_float(pump_demand, last_pump_output-pump_max_change, last_pump_output+pump_max_change);
50 
51  // update spinner (if any)
52  if (spinner_servo >= 0) {
53  const float spinner_demand = (input.servos[spinner_servo]-1000) * 0.001f;
54  const float spinner_max_change = spinner_slew_rate * 0.01f * dt;
55  last_spinner_output = constrain_float(spinner_demand, last_spinner_output-spinner_max_change, last_spinner_output+spinner_max_change);
57  }
58 
59  if (should_report()) {
60  printf("Remaining: %f litres\n", capacity);
61  printf("Pump: %f l/s\n", last_pump_output * pump_max_rate);
62  if (spinner_servo >= 0) {
63  printf("Spinner: %f rev/s\n", (last_spinner_output * spinner_max_rate)/360.0f);
64  }
65  last_report_us = now;
66  }
67 
68  last_update_us = now;
69  return;
70 }
71 
73 {
75  return false;
76  }
77 
79  zero_report_done = false;
80  return true;
81  }
82 
83  if (!zero_report_done) {
84  zero_report_done = true;
85  return true;
86  }
87 
88  return false;
89 }
90 
const float spinner_slew_rate
Definition: SIM_Sprayer.h:50
int printf(const char *fmt,...)
Definition: stdio.c:113
void update(const struct Aircraft::sitl_input &input)
Definition: SIM_Sprayer.cpp:27
uint64_t last_report_us
Definition: SIM_Sprayer.h:43
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
static int8_t delta
Definition: RCOutput.cpp:21
bool zero_report_done
Definition: SIM_Sprayer.h:58
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
uint64_t micros64()
Definition: system.cpp:162
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
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
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