AP_Volz_Protocol.h 2.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. /*
  2. * AP_VOLZ_PROTOCOL.h
  3. *
  4. * Created on: Oct 31, 2017
  5. * Author: guy tzoler
  6. *
  7. * Baud-Rate: 115.200 bits per second
  8. * Number of Data bits: 8
  9. * Number of Stop bits: 1
  10. * Parity: None
  11. * Half/Full Duplex: Half Duplex
  12. *
  13. * Volz Command and Response are all 6 bytes
  14. *
  15. * Command
  16. * byte | Communication Type
  17. * 1 Command Code
  18. * 2 Actuator ID
  19. * 3 Argument 1
  20. * 4 Argument 2
  21. * 5 CRC High-byte
  22. * 6 CRC Low-Byte
  23. *
  24. * byte | Communication Type
  25. * 1 Response Code
  26. * 2 Actuator ID
  27. * 3 Argument 1
  28. * 4 Argument 2
  29. * 5 CRC High-byte
  30. * 6 CRC Low-Byte
  31. *
  32. */
  33. #pragma once
  34. #include <AP_HAL/AP_HAL.h>
  35. #include <AP_SerialManager/AP_SerialManager.h>
  36. #include <AP_Param/AP_Param.h>
  37. //#include <GCS_MAVLink/GCS.h>
  38. #define VOLZ_SCALE_VALUE (uint16_t)(VOLZ_EXTENDED_POSITION_MAX - VOLZ_EXTENDED_POSITION_MIN) // Extended Position Data Format defines 100 as 0x0F80, which results in 1920 steps for +100 deg and 1920 steps for -100 degs meaning if you take movement a scaled between -1 ... 1 and multiply by 1920 you get the travel from center
  39. #define VOLZ_SET_EXTENDED_POSITION_CMD 0xDC
  40. #define VOLZ_SET_EXTENDED_POSITION_RSP 0x2C
  41. #define VOLZ_DATA_FRAME_SIZE 6
  42. #define VOLZ_EXTENDED_POSITION_MIN 0x0080 // Extended Position Data Format defines -100 as 0x0080 decimal 128
  43. #define VOLZ_EXTENDED_POSITION_CENTER 0x0800 // Extended Position Data Format defines 0 as 0x0800 - decimal 2048
  44. #define VOLZ_EXTENDED_POSITION_MAX 0x0F80 // Extended Position Data Format defines +100 as 0x0F80 decimal 3968 -> full range decimal 3840
  45. class AP_Volz_Protocol {
  46. public:
  47. AP_Volz_Protocol();
  48. /* Do not allow copies */
  49. AP_Volz_Protocol(const AP_Volz_Protocol &other) = delete;
  50. AP_Volz_Protocol &operator=(const AP_Volz_Protocol&) = delete;
  51. static const struct AP_Param::GroupInfo var_info[];
  52. void update();
  53. private:
  54. AP_HAL::UARTDriver *port;
  55. void init(void);
  56. void send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE]);
  57. void update_volz_bitmask(uint32_t new_bitmask);
  58. uint32_t last_volz_update_time;
  59. uint32_t volz_time_frame_micros;
  60. uint32_t last_used_bitmask;
  61. AP_Int32 bitmask;
  62. bool initialised;
  63. };