SIM_Gripper_Servo.h 2.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768
  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. #pragma once
  17. #include "stdint.h"
  18. #include <AP_Param/AP_Param.h>
  19. #include "SITL_Input.h"
  20. namespace SITL {
  21. class Gripper_Servo {
  22. public:
  23. Gripper_Servo() {
  24. AP_Param::setup_object_defaults(this, var_info);
  25. };
  26. // update Gripper state
  27. void update(const struct sitl_input &input);
  28. float payload_mass() const; // kg
  29. void set_alt(float alt) {altitude = alt;};
  30. static const struct AP_Param::GroupInfo var_info[];
  31. bool is_enabled() const {return static_cast<bool>(gripper_enable);}
  32. bool is_jaw_open() const {return jaw_open;}
  33. private:
  34. static constexpr int16_t SIM_GRIPPER_GRAB_PWM_DEFAULT = 2000;
  35. static constexpr int16_t SIM_GRIPPER_RELEASE_PWM_DEFAULT = 1000;
  36. AP_Int8 gripper_enable; // enable gripper sim
  37. AP_Int8 gripper_servo_pin;
  38. AP_Int16 grab_pwm; // PWM value sent to Gripper to initiate grabbing the cargo
  39. AP_Int16 release_pwm; // PWM value sent to Gripper to release the cargo
  40. AP_Int8 reverse; // reverse closing direction
  41. const uint32_t report_interval = 1000000; // microseconds
  42. uint64_t last_report_us;
  43. bool jaw_open = false;
  44. const float gap = 30; // mm
  45. float altitude;
  46. float position; // percentage
  47. float position_slew_rate = 35; // percentage
  48. float reported_position = -1; // unlikely
  49. uint64_t last_update_us;
  50. bool should_report();
  51. // dangle load from a string:
  52. const float string_length = 2.0f; // metres
  53. float load_mass = 0.0f; // kilograms
  54. };
  55. }