SIM_Gripper_Servo.cpp 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  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 Gripper (Servo) simulation class
  15. */
  16. #include "SIM_Gripper_Servo.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 Gripper_Servo::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, Gripper_Servo, gripper_enable, 0),
  29. // @Param: PIN
  30. // @DisplayName: Gripper servo pin
  31. // @Description: The pin number that the gripper servo is connected to. (start at 1)
  32. // @Range: 0 15
  33. // @User: Advanced
  34. AP_GROUPINFO("PIN", 1, Gripper_Servo, gripper_servo_pin, -1),
  35. // @Param: GRAB
  36. // @DisplayName: Gripper Grab PWM
  37. // @Description: PWM value in microseconds sent to Gripper to initiate grabbing the cargo
  38. // @User: Advanced
  39. // @Range: 1000 2000
  40. // @Units: PWM
  41. AP_GROUPINFO("GRAB", 2, Gripper_Servo, grab_pwm, SIM_GRIPPER_GRAB_PWM_DEFAULT),
  42. // @Param: RELEASE
  43. // @DisplayName: Gripper Release PWM
  44. // @Description: PWM value in microseconds sent to Gripper to release the cargo
  45. // @User: Advanced
  46. // @Range: 1000 2000
  47. // @Units: PWM
  48. AP_GROUPINFO("RELEASE", 3, Gripper_Servo, release_pwm, SIM_GRIPPER_RELEASE_PWM_DEFAULT),
  49. // @Param: REVERSE
  50. // @DisplayName: Gripper close direction
  51. // @Description: Reverse the closing direction.
  52. // @User: Advanced
  53. // @Values: 0:Normal,1:Reverse
  54. AP_GROUPINFO("REVERSE", 4, Gripper_Servo, reverse, 0),
  55. AP_GROUPEND
  56. };
  57. /*
  58. update gripper state
  59. */
  60. void Gripper_Servo::update(const struct sitl_input &input)
  61. {
  62. const int16_t gripper_pwm = gripper_servo_pin >= 1 ? input.servos[gripper_servo_pin-1] : -1;
  63. const uint64_t now = AP_HAL::micros64();
  64. const float dt = (now - last_update_us) * 1.0e-6f;
  65. // update gripper position
  66. if (gripper_pwm < 0) {
  67. last_update_us = now;
  68. return;
  69. }
  70. const int16_t diff_pwm = abs(grab_pwm - release_pwm);
  71. float position_demand = (gripper_pwm - diff_pwm) * 0.001f;
  72. if (gripper_pwm < MIN(grab_pwm, release_pwm) || position_demand > 1.0f) { // never updated
  73. position_demand = position;
  74. }
  75. const float position_max_change = position_slew_rate / 100.0f * dt;
  76. position = constrain_float(position_demand, position - position_max_change, position + position_max_change);
  77. float jaw_gap;
  78. if ((release_pwm < grab_pwm && reverse) || (release_pwm > grab_pwm && !reverse)) {
  79. jaw_gap = gap * position;
  80. } else {
  81. jaw_gap = gap * (1.0f - position);
  82. }
  83. if (should_report()) {
  84. ::fprintf(stderr, "position_demand=%f jaw_gap=%f load=%f\n", position_demand, jaw_gap, load_mass);
  85. last_report_us = now;
  86. reported_position = position;
  87. }
  88. if (jaw_gap < 5) {
  89. if (altitude <= 0.0f) {
  90. load_mass = 1.0f; // attach the load
  91. jaw_open = false;
  92. }
  93. } else if (jaw_gap > 10) {
  94. load_mass = 0.0f; // detach the load
  95. jaw_open = true;
  96. }
  97. last_update_us = now;
  98. }
  99. bool Gripper_Servo::should_report()
  100. {
  101. if (AP_HAL::micros64() - last_report_us < report_interval) {
  102. return false;
  103. }
  104. if (!is_equal(reported_position, position)) {
  105. return true;
  106. }
  107. return false;
  108. }
  109. float Gripper_Servo::payload_mass() const
  110. {
  111. if (altitude < string_length) {
  112. return 0.0f;
  113. }
  114. return load_mass;
  115. }