SIM_Sprayer.cpp 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. simple sprayer simulator class
  15. */
  16. #include "SIM_Sprayer.h"
  17. #include "AP_HAL/AP_HAL.h"
  18. #include "AP_Math/AP_Math.h"
  19. #include <stdio.h>
  20. using namespace SITL;
  21. // table of user settable parameters
  22. const AP_Param::GroupInfo Sprayer::var_info[] = {
  23. // @Param: ENABLE
  24. // @DisplayName: Gripper servo Sim enable/disable
  25. // @Description: Allows you to enable (1) or disable (0) the gripper servo simulation
  26. // @Values: 0:Disabled,1:Enabled
  27. // @User: Advanced
  28. AP_GROUPINFO("ENABLE", 0, Sprayer, sprayer_enable, 0),
  29. // @Param: PUMP
  30. // @DisplayName: Sprayer pump pin
  31. // @Description: The pin number that the Sprayer pump is connected to. (start at 1)
  32. // @Range: 0 15
  33. // @User: Advanced
  34. AP_GROUPINFO("PUMP", 1, Sprayer, sprayer_pump_pin, -1),
  35. // @Param: SPIN
  36. // @DisplayName: Sprayer spinner servo pin
  37. // @Description: The pin number that the Sprayer spinner servo is connected to. (start at 1)
  38. // @Range: 0 15
  39. // @User: Advanced
  40. AP_GROUPINFO("SPIN", 2, Sprayer, sprayer_spin_pin, -1),
  41. AP_GROUPEND
  42. };
  43. /*
  44. update sprayer state
  45. */
  46. void Sprayer::update(const struct sitl_input &input)
  47. {
  48. const int16_t pump_pwm = sprayer_pump_pin >= 1 ? input.servos[sprayer_pump_pin-1] : -1;
  49. const int16_t spinner_pwm = sprayer_spin_pin >= 1 ? input.servos[sprayer_spin_pin-1] : -1;
  50. const uint64_t now = AP_HAL::micros64();
  51. const float dt = (now - last_update_us) * 1.0e-6f;
  52. if (pump_pwm >= 0) {
  53. // update remaining payload
  54. if (capacity > 0) {
  55. const double delta = last_pump_output * pump_max_rate * dt;
  56. capacity -= delta;
  57. if (capacity < 0) {
  58. capacity = 0.0f;
  59. }
  60. }
  61. // update pump
  62. float pump_demand = (pump_pwm - 1000) * 0.001f;
  63. // ::fprintf(stderr, "pump_demand=%f\n", pump_demand);
  64. if (pump_demand < 0) { // never updated
  65. pump_demand = 0;
  66. }
  67. const float pump_max_change = pump_slew_rate / 100.0f * dt;
  68. last_pump_output =
  69. constrain_float(pump_demand, last_pump_output - pump_max_change, last_pump_output + pump_max_change);
  70. last_pump_output = constrain_float(last_pump_output, 0, 1);
  71. } else {
  72. last_pump_output = 0.0f;
  73. }
  74. // update spinner (if any)
  75. if (spinner_pwm >= 0) {
  76. const float spinner_demand = (spinner_pwm - 1000) * 0.001f;
  77. const float spinner_max_change = spinner_slew_rate * 0.01f * dt;
  78. last_spinner_output = constrain_float(spinner_demand,
  79. last_spinner_output - spinner_max_change,
  80. last_spinner_output + spinner_max_change);
  81. last_spinner_output = constrain_float(last_spinner_output, 0, 1);
  82. }
  83. if (should_report()) {
  84. printf("Remaining: %f litres\n", capacity);
  85. printf("Pump: %f l/s\n", last_pump_output * pump_max_rate);
  86. if (spinner_pwm >= 0) {
  87. printf("Spinner: %f rev/s\n", (last_spinner_output * spinner_max_rate) / 360.0f);
  88. }
  89. last_report_us = now;
  90. }
  91. last_update_us = now;
  92. }
  93. bool Sprayer::should_report()
  94. {
  95. if (AP_HAL::micros64() - last_report_us < report_interval) {
  96. return false;
  97. }
  98. if (!is_zero(last_pump_output) || !is_zero(last_spinner_output)) {
  99. zero_report_done = false;
  100. return true;
  101. }
  102. if (!zero_report_done) {
  103. zero_report_done = true;
  104. return true;
  105. }
  106. return false;
  107. }